LingxinMeng 5 mesi fa
parent
commit
affd4dfd96

+ 12 - 63
src/python2/pjibot/camera-pjibot_guide.py

@@ -2,86 +2,36 @@
 import os
 import time
 import oss2
-import json
-
 from resource import parse_pji_image
-
+from utils import json_utils
 import logging
-
 path1 = '/mnt/disk001/dcl_data_process/src/python2/pjibot/'
-
-logging.basicConfig(filename=path1 + 'log/camera-pjibot_guide.log', level=logging.INFO,
-                    format='%(asctime)s - %(levelname)s - %(message)s')
-
+logging.basicConfig(filename=path1 + 'log/camera-pjibot_guide.log', level=logging.INFO,format='%(asctime)s - %(levelname)s - %(message)s')
 key1 = 'pjibot/'
-sleep_time = 2  # 每多少秒扫描一次
-
+sleep_time = 30  # 每多少秒扫描一次
 error_bag_json = "/mnt/disk001/dcl_data_process/src/python2/pjibot/camera-errorBag.json"
 
 
-def parse_json_to_string_array(file_path):
-    try:
-        # 打开并读取JSON文件(Python 2中不支持encoding参数,需要使用codecs模块或处理文件读取后的编码)
-        with open(file_path, 'r') as file:
-            # 读取文件内容
-            file_content = file.read()
-            # 解析JSON内容(Python 2中json.loads用于解析字符串)
-            data = json.loads(file_content.decode('utf-8'))  # 假设文件是UTF-8编码,这里需要手动解码
-
-        # 检查数据是否是一个列表,并且列表中的元素是否是字符串
-        if isinstance(data, list):
-            for item in data:
-                if not isinstance(item, basestring):  # Python 2中字符串类型包括str和unicode,用basestring检查
-                    raise ValueError("JSON数组中的元素不是字符串")
-            return data
-        else:
-            return []
-    except Exception as e:
-        return []
-
-
-def list_to_json_file(data, file_path):
-    """
-    将列表转换为JSON格式并写入指定的文件路径。
-    如果文件已存在,则覆盖它。
-
-    参数:
-    data (list): 要转换为JSON的列表。
-    file_path (str): 要写入JSON数据的文件路径。
-    """
-    # 将列表转换为JSON格式的字符串,并确保输出为UTF-8编码的字符串
-    json_data = json.dumps(data, ensure_ascii=False, indent=4)
-    json_data_utf8 = json_data.encode('utf-8')  # 编码为UTF-8
-
-    # 以写入模式打开文件,如果文件已存在则覆盖
-    with open(file_path, 'w') as file:
-        # 将UTF-8编码的JSON字符串写入文件
-        file.write(json_data_utf8)
-
-
 def parse_to_mp4(merged_bag_file_path, parse_prefix, local_parse_dir, local_delete_list):
     try:
-        local_mp4_dir1 = parse_pji_image.parse1('/ob_camera_01/color/image_raw', merged_bag_file_path,
-                                                local_parse_dir + '/camera1/')
-        mp4_file_name1 = 'camera'
-        local_mp4_file_path1 = local_mp4_dir1 + '/' + mp4_file_name1 + '.mp4'
+        local_mp4_dir1 = parse_pji_image.parse1('/ob_camera_01/color/image_raw', merged_bag_file_path,local_parse_dir + '/camera1/')
+        local_mp4_file_path1 = local_parse_dir + '/camera1/camera1.mp4'
         local_delete_list.append(local_mp4_file_path1)
-        oss_csv_object_key1 = parse_prefix + mp4_file_name1 + '.mp4'
+        oss_csv_object_key1 = parse_prefix +  'camera.mp4'
         bucket.put_object_from_file(oss_csv_object_key1, local_mp4_file_path1)
-        logging.info("上传 camera.mp4 成功: %s" , str(oss_csv_object_key1))
-        local_mp4_dir2 = parse_pji_image.parse2('/ob_camera_02/color/image_raw', merged_bag_file_path,
-                                                local_parse_dir + '/camera2/')
+        logging.info("上传 camera1.mp4 成功: %s" , str(oss_csv_object_key1))
+        local_mp4_dir2 = parse_pji_image.parse2('/ob_camera_02/color/image_raw', merged_bag_file_path,local_parse_dir + '/camera2/')
         mp4_file_name2 = 'camera2'
-        local_mp4_file_path2 = local_mp4_dir2 + '/' + mp4_file_name2 + '.mp4'
+        local_mp4_file_path2 = local_parse_dir + '/camera2/' + mp4_file_name2 + '.mp4'
         local_delete_list.append(local_mp4_file_path2)
         oss_csv_object_key2 = parse_prefix + mp4_file_name2 + '.mp4'
         bucket.put_object_from_file(oss_csv_object_key2, local_mp4_file_path2)
         logging.info("上传 camera2.mp4 成功: %s" , str(oss_csv_object_key1))
 
     except Exception as e2:
-        error_bag_list = parse_json_to_string_array(error_bag_json)
+        error_bag_list = json_utils.parse_json_to_string_array(error_bag_json)
         error_bag_list.append(parse_prefix)
-        list_to_json_file(error_bag_list, error_bag_json)
+        json_utils.list_to_json_file(error_bag_list, error_bag_json)
         # 当出现异常时执行的代码
         logging.exception("生成摄像头视频报错,添加到 camera-errorBag.json: %s", e2)
 
@@ -117,7 +67,7 @@ if __name__ == '__main__':
                             camera2_done = True
                     if camera_done and camera2_done:
                         continue
-                    error_bag_list = parse_json_to_string_array(error_bag_json)
+                    error_bag_list = json_utils.parse_json_to_string_array(error_bag_json)
                     if parse_prefix_full in error_bag_list:
                         continue
                     logging.info("%s 等待处理到: %s", merged_bag_object_key, parse_prefix_full)
@@ -146,7 +96,6 @@ if __name__ == '__main__':
                         os.remove(local_delete)
                     except Exception as e:
                         pass
-                        # logging.exception("捕获到一个异常: %s" % str(e))
             time.sleep(sleep_time)
         except Exception as e:
             logging.exception("全局错误处理: %s" % str(e))

+ 25 - 5
src/python2/pjibot/resource/convert_rosbag_to_pcd.py

@@ -5,6 +5,9 @@ import os
 import subprocess
 import multiprocessing
 import rosbag
+import numpy as np
+import cv2
+
 
 
 def convert_bag_to_pcd(input_dir, output_dir):
@@ -14,22 +17,33 @@ def convert_bag_to_pcd(input_dir, output_dir):
     stdout, stderr = process.communicate()
 
 
-def calculate_frame_rate(rosbag_path):
+
+def calculate_frame_rate(rosbag_path,output_dir):
     with rosbag.Bag(rosbag_path, 'r') as bag:
+        bag_start_time = bag.get_start_time()
+        bag_end_time = bag.get_end_time()
+        #根据rosbag的起止时间生成黑色图片
+        
+        black_image = np.zeros((512, 512, 3), dtype=np.uint8)
+        cv2.imwrite(os.path.join(output_dir,str(bag_start_time)+'.jpg'), black_image)
+        cv2.imwrite(os.path.join(output_dir,str(bag_end_time)+'.jpg'), black_image)
+        '''
         num_count = 0
         for topic, msg, t in bag.read_messages():
             if topic == "/scan_map_icp_amcl_node/scan_point_transformed":
                 num_count += 1
         duration = bag.get_end_time() - bag.get_start_time()
         frame_rate = num_count / float(duration) if duration > 0 else 0
-    return frame_rate
+        '''
+    return bag_start_time,bag_end_time
 
 
+'''
 def save_frame_rate(lidar_output_base, frame_rate):
     frame_rate_file = os.path.join(lidar_output_base, 'frame_rate.txt')
     with open(frame_rate_file, 'w') as file:
         file.write(str(frame_rate))
-
+'''
 
 def process_file(file):
     root, filename = file
@@ -49,19 +63,25 @@ def process_file(file):
 def main():
     rosbag_path = sys.argv[1]
     output_base_path = sys.argv[2]
+    #rosbag_path = '/home/dell/下载/2024-10-16-04-11-25_obstacledetection_30.bag'
+    #output_base_path ='/home/dell/下载'
+    
     bag_base_name = os.path.basename(rosbag_path).split('.')[0]
     lidar_output_base = os.path.join(output_base_path, bag_base_name + '_pcd_lidar')
     pcd_folder_path = os.path.join(lidar_output_base, 'pcd')
+    jpg_folder_path = os.path.join(lidar_output_base, 'jpg')
 
     if not os.path.exists(pcd_folder_path):
         os.makedirs(pcd_folder_path)
+    if not os.path.exists(jpg_folder_path):
+        os.makedirs(jpg_folder_path)
 
     # Convert ROS bag to PCD
     convert_bag_to_pcd(rosbag_path, pcd_folder_path)
 
     # Calculate and save frame rate
-    frame_rate = calculate_frame_rate(rosbag_path)
-    save_frame_rate(lidar_output_base, frame_rate)
+    #calculate_frame_rate(rosbag_path,jpg_folder_path)
+    #save_frame_rate(lidar_output_base, frame_rate)
 
     # Process files in parallel
     files_to_process = []

+ 70 - 20
src/python2/pjibot/resource/create_video_from_pcd.py

@@ -5,6 +5,9 @@ import os
 import numpy as np
 from pyntcloud import PyntCloud
 import subprocess
+from subprocess import Popen, PIPE
+import shutil
+
 
 
 def find_global_min_max(pcd_folder_path):
@@ -38,43 +41,90 @@ def process_pcd_to_top_view_image(pcd_path, output_path, axis_limits):
     plt.close()
 
 
-def create_video_from_images(image_folder, output_video_path, frame_rate):
-    images = [img for img in sorted(os.listdir(image_folder)) if img.endswith(".jpg")]
-    frame = cv2.imread(os.path.join(image_folder, images[0]))
-    height, width, layers = frame.shape
-    video = cv2.VideoWriter(output_video_path, cv2.VideoWriter_fourcc(*'mp4v'), float(frame_rate), (width, height))
-    for image in images:
-        frame = cv2.imread(os.path.join(image_folder, image))
-        video.write(frame)
-    video.release()
-    print(f"Video successfully saved to: {output_video_path}")
-    convert_video(output_video_path)
-
-
+def create_video_from_images(image_folder, output_video_path):
+   dirt=image_folder
+   #指定视频帧率
+   hz=10.0
+   
+   # 定义图片文件夹路径
+   folder_path = dirt
+
+   # 获取文件夹中的所有图片文件
+   image_files = [f for f in os.listdir(folder_path) if f.endswith('.jpg')]
+
+   # 对文件名进行排序,以便按顺序处理图片
+   image_files.sort()
+
+   # 读取第一张图片
+   first_image = cv2.imread(os.path.join(folder_path, image_files[0]))
+
+   # 获取图片的形状
+   image_shape = first_image.shape
+
+   # 创建视频写入对象
+   video_path=os.path.join(dirt,'camera.mp4')
+   video_writer = cv2.VideoWriter(video_path, cv2.VideoWriter_fourcc('m', 'p', '4', 'v'), hz, (image_shape[1], image_shape[0]))
+
+   # 遍历图片文件列表
+   for i in range(len(image_files) - 1):
+       # 读取当前图片和下一张图片
+       current_image = cv2.imread(os.path.join(folder_path, image_files[i]))
+       next_image = cv2.imread(os.path.join(folder_path, image_files[i + 1]))
+
+       # 获取当前图片和下一张图片的时间戳
+       current_timestamp = float(image_files[i].split('.jpg')[0]) 
+       next_timestamp = float(image_files[i + 1].split('.jpg')[0]) 
+
+       # 计算时间间隔
+       time_interval = next_timestamp - current_timestamp
+       #print(time_interval)
+
+       
+
+       # 根据实际时间间隔调整循环次数
+       video_writer.write(current_image)
+       if int(time_interval * hz)>1.5:
+           for _ in range(int(time_interval * hz)):     
+               video_writer.write(current_image)
+
+   # 释放资源
+   video_writer.release()
+   if os.path.exists(video_path):
+        video_output_path=os.path.join(image_folder[0:-4],'pcd_overlook.mp4')
+        command = ["ffmpeg", "-i", video_path, "-c:v", "libx264", video_output_path]
+        p = Popen(command, stdout=subprocess.PIPE, stderr=subprocess.PIPE)
+        p.communicate()
+        shutil.rmtree(image_folder)
+        shutil.rmtree(os.path.join(image_folder[0:-4],'pcd'))
+        shutil.rmtree(os.path.join(image_folder[0:-4],'pcd_ascii'))
+
+'''
 def convert_video(input_video_path):
     output_video_path = input_video_path.replace(".mp4", "_converted.mp4")
     command = f"ffmpeg -i {input_video_path} -c:v libx264 -preset fast -crf 23 {output_video_path}"
     subprocess.run(command, shell=True)
     os.remove(input_video_path)
     print(f"Converted video saved as {output_video_path} and original video deleted.")
-
+'''
 
 if __name__ == '__main__':
     bag_base_name = sys.argv[1]
     output_base_path = sys.argv[2]
+    #bag_base_name = '2024-10-16-04-11-25_obstacledetection_30'
+    #output_base_path = '/home/dell/下载'
 
     lidar_output_base = os.path.join(output_base_path, bag_base_name + '_pcd_lidar')
     pcd_folder_path = os.path.join(lidar_output_base, 'pcd_ascii')
-    images_folder_path = os.path.join(lidar_output_base, 'images')
-    video_path = os.path.join(lidar_output_base, 'output_video.mp4')
-    frame_rate_file = os.path.join(output_base_path, bag_base_name + '_pcd_lidar', 'frame_rate.txt')
+    images_folder_path = os.path.join(lidar_output_base, 'jpg')
+    video_path = os.path.join(images_folder_path, 'output_video.mp4')
+    #frame_rate_file = os.path.join(output_base_path, bag_base_name + '_pcd_lidar', 'frame_rate.txt')
 
     if not os.path.exists(images_folder_path):
         os.makedirs(images_folder_path)
-
+    ''' 
     with open(frame_rate_file, 'r') as file:
         frame_rate = file.read().strip()
-
+    '''
     axis_limits = find_global_min_max(pcd_folder_path)
 
     pcd_files = [f for f in os.listdir(pcd_folder_path) if f.endswith('.pcd')]
@@ -83,4 +133,4 @@ if __name__ == '__main__':
         image_file_path = os.path.join(images_folder_path, file_name.replace('.pcd', '.jpg'))
         process_pcd_to_top_view_image(pcd_file_path, image_file_path, axis_limits)
 
-    create_video_from_images(images_folder_path, video_path, frame_rate)
+    create_video_from_images(images_folder_path, video_path)

+ 135 - 28
src/python2/pjibot/resource/parse_pji_image.py

@@ -12,15 +12,20 @@ import argparse
 import struct
 import subprocess
 from subprocess import Popen, PIPE
-
+import numpy as np
+import shutil
 bridge = CvBridge()
-
+bag_start_time=0
+bag_end_time=0
 
 def parsebag(f, output_dir, target_topic):
     rosbag_name = f[f.rindex("/"):-4]
     output_path = output_dir + rosbag_name
 
-    with rosbag.Bag(f, 'r') as bag:
+    with rosbag.Bag(f, 'r') as bag:  
+        global bag_start_time
+        global bag_end_time
+        
         count = 0
         for key, val in bag.get_type_and_topic_info()[1].items():
             if val[0] == 'sensor_msgs/Image':
@@ -30,7 +35,7 @@ def parsebag(f, output_dir, target_topic):
                         img = bridge.imgmsg_to_cv2(msg, 'bgr8')
                         # img = bridge.compressed_imgmsg_to_cv2(msg, 'bgr8')
                         timestr = msg.header.stamp.to_nsec()
-                        image_name = str(timestr) + ".jpg"
+                        image_name = str(timestr)[:10]+'.'+str(timestr)[10:] + ".jpg"
                         if not os.path.exists(output_path + '_' + 'image'):
                             os.makedirs(output_path + '_' + 'image')
                         output_path_img = os.path.join(output_path + '_' + 'image', image_name)
@@ -41,43 +46,145 @@ def parsebag(f, output_dir, target_topic):
 
 
 def parse1(topic, input_bag_file, output_mp4_dir):
+    global bag_start_time
+    global bag_end_time 
     input_dir = input_bag_file
     output_dir = output_mp4_dir
     num_count = parsebag(input_dir, output_dir, topic)
-    print("解析完成")
+    #print("解析完成")
     dirt = os.path.join(output_dir, input_dir.split('/')[-1].split('.')[0] + '_' + 'image')
     bagtime = int(input_dir.split('/')[-1].split('.')[0].split('_')[-1])
-    hz = str(float(num_count / bagtime))
-    print(hz)
-    command = ['ffmpeg', '-f', 'image2', '-r', hz, '-pattern_type', 'glob', '-i'] + [dirt + '/*.jpg'] + ['-tag:v',
-                                                                                                         'avc1',
-                                                                                                         '-y'] + [
-                  dirt + '/camera.mp4']
-    p = Popen(command, stdout=subprocess.PIPE, stderr=subprocess.PIPE)
-    p.communicate()
+    #hz = str(float(num_count / bagtime))
+    #print(hz)
     list1 = os.listdir(dirt)
-    for i in list1:
-        if i.split('.')[-1] == 'jpg':
-            os.remove(os.path.join(dirt, i))
+    if list1!=[]:
+        #指定视频帧率
+        hz=10.0
+        
+        # 定义图片文件夹路径
+        folder_path = dirt
+
+        #根据rosbag的起止时间生成黑色图片
+        if bag_end_time!=0 and bag_end_time!=0:
+            black_image = np.zeros((512, 512, 3), dtype=np.uint8)
+            cv2.imwrite(os.path.join(dirt,str(bag_start_time)+'.jpg'), black_image)
+            cv2.imwrite(os.path.join(dirt,str(bag_end_time)+'.jpg'), black_image)
+        
+        # 获取文件夹中的所有图片文件
+        image_files = [f for f in os.listdir(folder_path) if f.endswith('.jpg')]
+
+        # 对文件名进行排序,以便按顺序处理图片
+        image_files.sort()
+
+        # 读取第一张图片
+        first_image = cv2.imread(os.path.join(folder_path, image_files[0]))
+
+        # 获取图片的形状
+        image_shape = first_image.shape
+
+        # 创建视频写入对象
+        video_path=os.path.join(dirt,'camera1.mp4')
+        video_writer = cv2.VideoWriter(video_path, cv2.VideoWriter_fourcc('m', 'p', '4', 'v'), hz, (image_shape[1], image_shape[0]))
+
+        # 遍历图片文件列表
+        for i in range(len(image_files) - 1):
+            # 读取当前图片和下一张图片
+            current_image = cv2.imread(os.path.join(folder_path, image_files[i]))
+            next_image = cv2.imread(os.path.join(folder_path, image_files[i + 1]))
+
+            # 获取当前图片和下一张图片的时间戳
+            current_timestamp = float(image_files[i].split('.jpg')[0]) 
+            next_timestamp = float(image_files[i + 1].split('.jpg')[0]) 
+
+            # 计算时间间隔
+            time_interval = next_timestamp - current_timestamp
+            #print(time_interval)
+
+            # 根据实际时间间隔调整循环次数
+            video_writer.write(current_image)
+            if int(time_interval * hz)>1.5:
+                for _ in range(int(time_interval * hz)):     
+                    video_writer.write(current_image)
+
+        # 释放资源
+        video_writer.release()
+        if os.path.exists(video_path):
+            video_output_path=os.path.join(output_dir,'camera1.mp4')
+            command = ["ffmpeg", "-i", video_path, "-c:v", "libx264", video_output_path]
+            p = Popen(command, stdout=subprocess.PIPE, stderr=subprocess.PIPE)
+            p.communicate()
+            shutil.rmtree(folder_path)
+
     return dirt
 
 def parse2(topic, input_bag_file, output_mp4_dir):
+    global bag_start_time
+    global bag_end_time 
     input_dir = input_bag_file
     output_dir = output_mp4_dir
     num_count = parsebag(input_dir, output_dir, topic)
-    print("解析完成")
+    #print("解析完成")
     dirt = os.path.join(output_dir, input_dir.split('/')[-1].split('.')[0] + '_' + 'image')
     bagtime = int(input_dir.split('/')[-1].split('.')[0].split('_')[-1])
-    hz = str(float(num_count / bagtime))
-    print(hz)
-    command = ['ffmpeg', '-f', 'image2', '-r', hz, '-pattern_type', 'glob', '-i'] + [dirt + '/*.jpg'] + ['-tag:v',
-                                                                                                         'avc1',
-                                                                                                         '-y'] + [
-                  dirt + '/camera2.mp4']
-    p = Popen(command, stdout=subprocess.PIPE, stderr=subprocess.PIPE)
-    p.communicate()
+    #hz = str(float(num_count / bagtime))
+    #print(hz)
     list1 = os.listdir(dirt)
-    for i in list1:
-        if i.split('.')[-1] == 'jpg':
-            os.remove(os.path.join(dirt, i))
+    if list1!=[]:
+        #指定视频帧率
+        hz=10.0
+        
+        # 定义图片文件夹路径
+        folder_path = dirt
+
+        #根据rosbag的起止时间生成黑色图片
+        if bag_end_time!=0 and bag_end_time!=0:
+            black_image = np.zeros((512, 512, 3), dtype=np.uint8)
+            cv2.imwrite(os.path.join(dirt,str(bag_start_time)+'.jpg'), black_image)
+            cv2.imwrite(os.path.join(dirt,str(bag_end_time)+'.jpg'), black_image)
+        
+        # 获取文件夹中的所有图片文件
+        image_files = [f for f in os.listdir(folder_path) if f.endswith('.jpg')]
+
+        # 对文件名进行排序,以便按顺序处理图片
+        image_files.sort()
+
+        # 读取第一张图片
+        first_image = cv2.imread(os.path.join(folder_path, image_files[0]))
+
+        # 获取图片的形状
+        image_shape = first_image.shape
+
+        # 创建视频写入对象
+        video_path=os.path.join(dirt,'camera2.mp4')
+        video_writer = cv2.VideoWriter(video_path, cv2.VideoWriter_fourcc('m', 'p', '4', 'v'), hz, (image_shape[1], image_shape[0]))
+
+        # 遍历图片文件列表
+        for i in range(len(image_files) - 1):
+            # 读取当前图片和下一张图片
+            current_image = cv2.imread(os.path.join(folder_path, image_files[i]))
+            next_image = cv2.imread(os.path.join(folder_path, image_files[i + 1]))
+
+            # 获取当前图片和下一张图片的时间戳
+            current_timestamp = float(image_files[i].split('.jpg')[0]) 
+            next_timestamp = float(image_files[i + 1].split('.jpg')[0]) 
+
+            # 计算时间间隔
+            time_interval = next_timestamp - current_timestamp
+            #print(time_interval)
+
+            # 根据实际时间间隔调整循环次数
+            video_writer.write(current_image)
+            if int(time_interval * hz)>1.5:
+                for _ in range(int(time_interval * hz)):     
+                    video_writer.write(current_image)
+
+        # 释放资源
+        video_writer.release()
+        if os.path.exists(video_path):
+            video_output_path=os.path.join(output_dir,'camera2.mp4')
+            command = ["ffmpeg", "-i", video_path, "-c:v", "libx264", video_output_path]
+            p = Popen(command, stdout=subprocess.PIPE, stderr=subprocess.PIPE)
+            p.communicate()
+            shutil.rmtree(folder_path)
+
     return dirt

+ 3 - 3
src/python2/pjibot_delivery/2camera-pjibot_delivery.py

@@ -23,10 +23,11 @@ def parse_to_mp4(merged_bag_file_path, parse_prefix1, local_parse_dir2, local_de
     oss_csv_object_key1 = parse_prefix1 + mp4_file_name + '.mp4'
     try:
         flag, local_mp4_dir = parse_robot_image.parse(merged_bag_file_path, local_parse_dir2 + '/camera/')
-        if flag:  # 没有话题就不生成视频了
+        if flag:
             bucket.put_object_from_file(oss_csv_object_key1, local_mp4_file_path1)
             logging.info("上传 camera.mp4 成功: %s", str(oss_csv_object_key1))
-        else:
+        else: 
+            # 如果没有图像话题,也添加到错误列表,防止后面重复扫描生成
             json_utils.add_error(parse_prefix1,error_bag_json)
             logging.info("没有图像话题: %s", merged_bag_file_path)
     except Exception as e2:
@@ -45,7 +46,6 @@ def judge(parse_prefix_full):
         return True
     
 def end_delete(local_delete_list):
-    # 删除本地临时文件
     if len(local_delete_list) > 0:
         for local_delete in local_delete_list:
             try:

+ 2 - 1
src/python2/pjibot_delivery/csv-errorBag.json

@@ -303,5 +303,6 @@
     "pjibot_delivery/pjibot-P1YYPS1M227M00107/data_parse/VD100M6-BJ-Perception2024-11-08-16-45-05/", 
     "pjibot_delivery/pjibot-P1YYPS1M227M00107/data_parse/VD100M6-BJ-Perception2024-11-08-16-46-29/", 
     "pjibot_delivery/pjibot-P1YYPS1M227M00107/data_parse/VD100M6-BJ-Perception2024-11-08-16-48-55/", 
-    "pjibot_delivery/pjibot-P1YYPS1M227M00107/data_parse/2024-12-04-11-06-47/"
+    "pjibot_delivery/pjibot-P1YYPS1M227M00107/data_parse/2024-12-04-11-06-47/", 
+    "pjibot_delivery/pjibot-P1YVPS1M22CM00020/data_parse/2024-12-04-10-32-38/"
 ]