ROS bag文件处理之从bag文件中提取图片并合成视频

API以及环境依赖

原理是使用rosbag api,从bag文件中过滤出sensor_msgs/CompressedImage类型的数据,对每一帧压缩图片使用ffmpeg进行编码,所以需要使用ffmpeg,如果未安装ffmpeg,可使用如下命令进行安装:

sudo apt-get install ffmpeg

脚本依赖还有opencv,可使用如下命令进行安装:

pip3 install opencv-python

安装opencv可能会出现一些问题,可参考我另外一篇博客

完整代码

# !/usr/bin/env python3
# import roslib
#roslib.load_manifest('rosbag')
import rospy
import rosbag
import sys, getopt
import os
from sensor_msgs.msg import CompressedImage
from sensor_msgs.msg import Image

ros_path = '/opt/ros/kinetic/lib/python2.7/dist-packages'
if ros_path in sys.path:
    sys.path.remove(ros_path)

import cv2
import numpy as np
import subprocess

sys.path.append('/opt/ros/kinetic/lib/python2.7/dist-packages')

MJPEG_VIDEO = 1
RAWIMAGE_VIDEO = 2
VIDEO_CONVERTER_TO_USE = "ffmpeg" # or use "avconv"

class RosVideoWriter():
    def __init__(self, fps=30.0, rate=1.0, topic="", output_filename ="", output_path = "", display= False, verbose = False, start = rospy.Time(0), end = rospy.Time(sys.maxsize)):
        self.opt_topic = topic
        self.opt_out_file = output_filename
        self.opt_verbose = verbose
        self.opt_display_images = display
        self.opt_start = start
        self.opt_end = end
        self.rate = rate
        self.fps = fps
        self.opt_prefix= None
        self.t_first={}
        self.t_file={}
        self.t_video={}
        self.p_avconv = {}
        self.out_path = output_path

    def parseArgs(self, args):
        opts, opt_files = getopt.getopt(args,"hsvr:o:t:p:",["fps=","rate=","opath=","topic=","start=","end=","prefix="])
        for opt, arg in opts:
            if opt == '-h':
                sys.exit(0)
            elif opt == '-s':
                self.opt_display_images = True
            elif opt == '-v':
                self.opt_verbose = True
            elif opt in ("--fps"):
                self.fps = float(arg)
            elif opt in ("-r", "--rate"):
                self.rate = float(arg)
            elif opt in ("-o", "--opath"):
                self.out_path = arg
            elif opt in ("-t", "--topic"):
                self.opt_topic = arg
            elif opt in ("-p", "--prefix"):
                self.opt_prefix = arg
            elif opt in ("--start"):
                self.opt_start = rospy.Time(int(arg))
                if(self.opt_verbose):
                    print("starting at",self.opt_start.to_sec())
            elif opt in ("--end"):
                self.opt_end = rospy.Time(int(arg))
                if(self.opt_verbose):
                    print("ending at",self.opt_end.to_sec())
            else:
                print("opz:", opt,'arg:', arg)

        if (self.fps<=0):
            print("invalid fps", self.fps)
            self.fps = 1

        if (self.rate<=0):
            print("invalid rate", self.rate)
            self.rate = 1

        if(self.opt_verbose):
            print("using ",self.fps," FPS")
        return opt_files


    # 根据话题类型过滤话题
    def filter_image_msgs(self, topic, datatype, md5sum, msg_def, header):
        if(datatype=="sensor_msgs/CompressedImage"):
            if (self.opt_topic != "" and self.opt_topic == topic) or self.opt_topic == "":
                return True;

        if(datatype=="theora_image_transport/Packet"):
            if (self.opt_topic != "" and self.opt_topic == topic) or self.opt_topic == "":
                return False;

        if(datatype=="sensor_msgs/Image"):
            if (self.opt_topic != "" and self.opt_topic == topic) or self.opt_topic == "":
                return True;

        return False;


    def write_output_video(self, msg, topic, t, video_fmt, pix_fmt = ""):
        # no data in this topic
        if len(msg.data) == 0 :
            return
        # initiate data for this topic
        if not topic in self.t_first :
            self.t_first[topic] = t # timestamp of first image for this topic
            self.t_video[topic] = 0
            self.t_file[topic] = 0
        # if multiple streams of images will start at different times the resulting video files will not be in sync
        # current offset time we are in the bag file
        self.t_file[topic] = (t-self.t_first[topic]).to_sec()
        # fill video file up with images until we reache the current offset from the beginning of the bag file
        while self.t_video[topic] < self.t_file[topic]/self.rate :
            if not topic in self.p_avconv:
                # we have to start a new process for this topic
                if self.opt_verbose :
                    print("Initializing pipe for topic", topic, "at time", t.to_sec())
                if self.out_path != "":
                    out_file = self.out_path + self.opt_prefix + str(topic).replace("/", "_")+".mp4"
                else:
                    out_file = self.opt_prefix + str(topic).replace("/", "_")+".mp4"

                if self.opt_verbose :
                    print("Using output file ", out_file, " for topic ", topic, ".")

                if video_fmt == MJPEG_VIDEO :
                    cmd = [VIDEO_CONVERTER_TO_USE, '-v', '1', '-stats', '-r',str(self.fps),'-c','mjpeg','-f','mjpeg','-i','-','-an',out_file]
                    self.p_avconv[topic] = subprocess.Popen(cmd, stdin=subprocess.PIPE)
                    if self.opt_verbose :
                        print("Using command line:")
                        print(cmd)
                elif video_fmt == RAWIMAGE_VIDEO :
                    size = str(msg.width)+"x"+str(msg.height)
                    cmd = [VIDEO_CONVERTER_TO_USE, '-v', '1', '-stats','-r',str(self.fps),'-f','rawvideo','-s',size,'-pix_fmt', pix_fmt,'-i','-','-an',out_file]
                    self.p_avconv[topic] = subprocess.Popen(cmd, stdin=subprocess.PIPE)
                    if self.opt_verbose :
                        print("Using command line:")
                        print(cmd)

                else :
                    print("Script error, unknown value for argument video_fmt in function write_output_video.")
                    exit(1)
            # send data to ffmpeg process pipe
            self.p_avconv[topic].stdin.write(msg.data)
            # next frame time
            self.t_video[topic] += 1.0/self.fps

    def addBag(self, filename):
        if self.opt_display_images:
            from cv_bridge import CvBridge, CvBridgeError
            bridge = CvBridge()
            cv_image = []

        if self.opt_verbose :
            print("Bagfile: {}".format(filename))

        if not self.opt_prefix:
            # create the output in the same folder and name as the bag file minu '.bag'
            self.opt_prefix = bagfile[:-4]
        
        if self.out_path != "":
            for f in os.listdir(self.out_path):
                if f.find(bagfile[:-4])>=0 and f.find(".mp4")>=0:
                    os.remove(self.out_path + f)
        else:
            for f in os.listdir("./"):
                if f.find(bagfile[:-4])>=0 and f.find(".mp4")>=0:
                    os.remove(self.out_path + f)

        #Go through the bag file
        bag = rosbag.Bag(filename)
        if self.opt_verbose :
            print("Bag opened.")
        # loop over all topics
        for topic, msg, t in bag.read_messages(connection_filter=self.filter_image_msgs, start_time=self.opt_start, end_time=self.opt_end):
            try:
                if msg.format.find("jpeg")!=-1 :
                    if msg.format.find("8")!=-1 and (msg.format.find("rgb")!=-1 or msg.format.find("bgr")!=-1 or msg.format.find("bgra")!=-1 ):
                        if self.opt_display_images:
                            np_arr = np.fromstring(msg.data, np.uint8)
                            cv_image = cv2.imdecode(np_arr, cv2.CV_LOAD_IMAGE_COLOR)
                        self.write_output_video( msg, topic, t, MJPEG_VIDEO )
                    elif msg.format.find("mono8")!=-1 :
                        if self.opt_display_images:
                            np_arr = np.fromstring(msg.data, np.uint8)
                            cv_image = cv2.imdecode(np_arr, cv2.CV_LOAD_IMAGE_COLOR)
                        self.write_output_video( msg, topic, t, MJPEG_VIDEO )
                    elif msg.format.find("16UC1")!=-1 :
                        if self.opt_display_images:
                            np_arr = np.fromstring(msg.data, np.uint16)
                            cv_image = cv2.imdecode(np_arr, cv2.CV_LOAD_IMAGE_COLOR)
                        self.write_output_video( msg, topic, t, MJPEG_VIDEO )
                    else:
                        # np_arr = np.fromstring(msg.data, np.uint8)
                        # cv_image = bridge.compressed_imgmsg_to_cv2(msg, "bgr8")
                        self.write_output_video( msg, topic, t, MJPEG_VIDEO)
                        # print('unsupported jpeg format:', msg.format, '.', topic)

            # has no attribute 'format'
            except AttributeError:
                try:
                        pix_fmt=None
                        if msg.encoding.find("mono8")!=-1 or msg.encoding.find("8UC1")!=-1:
                            pix_fmt = "gray"
                            if self.opt_display_images:
                                cv_image = bridge.imgmsg_to_cv2(msg, "bgr8")

                        elif msg.encoding.find("bgra")!=-1 :
                            pix_fmt = "bgra"
                            if self.opt_display_images:
                                cv_image = bridge.imgmsg_to_cv2(msg, "bgr8")

                        elif msg.encoding.find("bgr8")!=-1 :
                            pix_fmt = "bgr24"
                            if self.opt_display_images:
                                cv_image = bridge.imgmsg_to_cv2(msg, "bgr8")
                        elif msg.encoding.find("bggr8")!=-1 :
                            pix_fmt = "bayer_bggr8"
                            if self.opt_display_images:
                                cv_image = bridge.imgmsg_to_cv2(msg, "bayer_bggr8")
                        elif msg.encoding.find("rggb8")!=-1 :
                            pix_fmt = "bayer_rggb8"
                            if self.opt_display_images:
                                cv_image = bridge.imgmsg_to_cv2(msg, "bayer_rggb8")
                        elif msg.encoding.find("rgb8")!=-1 :
                            pix_fmt = "rgb24"
                            if self.opt_display_images:
                                cv_image = bridge.imgmsg_to_cv2(msg, "bgr8")
                        elif msg.encoding.find("16UC1")!=-1 :
                            pix_fmt = "gray16le"
                        else:
                            print('unsupported encoding:', msg.encoding, topic)
                            #exit(1)
                        if pix_fmt:
                            self.write_output_video( msg, topic, t, RAWIMAGE_VIDEO, pix_fmt )

                except AttributeError:
                    # maybe theora packet
                    # theora not supported
                    if self.opt_verbose :
                        print("Could not handle this format. Maybe thoera packet? theora is not supported.")
                    pass
            if self.opt_display_images:
                cv2.imshow(topic, cv_image)
                key=cv2.waitKey(1)
                if key==1048603:
                    exit(1)
        if self.p_avconv == {}:
            print("No image topics found in bag:", filename)
        bag.close()



if __name__ == '__main__':
    #print()
    #print('rosbag2video, by Maximilian Laiacker 2020 and Abel Gabor 2019')
    #print()

    if len(sys.argv) < 2:
        print('Please specify ros bag file(s)!')
        sys.exit(1)
    else :
        videowriter = RosVideoWriter()
        try:
            opt_files = videowriter.parseArgs(sys.argv[1:])
        except getopt.GetoptError:
            sys.exit(2)


    # loop over all files
    for files in range(0,len(opt_files)):
        #First arg is the bag to look at
        bagfile = opt_files[files]
        videowriter.addBag(bagfile)
    print("finished")

脚本使用方法

rosbag2video.py [--fps 25] [--rate 1] [-o outputfile] [-v] [-s] [-t topic] bagfile1 [bagfile2] ...

Converts image sequence(s) in ros bag file(s) to video file(s) with fixed frame rate using ffmpeg
ffmpeg needs to be installed!

--fps   Sets FPS value that is passed to ffmpeg
        Default is 25.
-h      Displays this help.
--ofile (-o) sets output file name.
        If no output file name (-o) is given the filename '<prefix><topic>.mp4' is used and default output codec is h264.
        Multiple image topics are supported only when -o option is _not_ used.
        ffmpeg  will guess the format according to given extension.
        Compressed and raw image messages are supported with mono8 and bgr8/rgb8/bggr8/rggb8 formats.
--rate  (-r) You may slow down or speed up the video.
        Default is 1.0, that keeps the original speed.
-s      Shows each and every image extracted from the rosbag file (cv_bride is needed).
--topic (-t) Only the images from topic "topic" are used for the video output.
-v      Verbose messages are displayed.
--prefix (-p) set a output file name prefix othervise 'bagfile1' is used (if -o is not set).
--start Optional start time in seconds.
--end   Optional end time in seconds.

代码是参照github上的一个开源项目进行修改的,可参照完整项目地址

  • 0
    点赞
  • 6
    收藏
    觉得还不错? 一键收藏
  • 1
    评论
制作数据集的bag文件是一种常用的方法,用于存储和管理大量的传感器数据。bag文件ROS(机器人操作系统)的一种文件格式,它可以包含多个传感器源生成的数据,如图像、点云、IMU数据等。 创建bag文件的过程首先需要安装ROS,并使用ROS提供的命令行工具进行操作。在终端,使用rosbag命令可以录制和回放bag文件。 录制bag文件的步骤如下: 1. 启动ROS系统,确保所有传感器和节点都正常运行。 2. 在终端输入以下命令开始录制bag文件: ``` rosbag record -a ``` 这将录制所有ROS话题发布的数据。可以使用"-h"选项查看更多命令参数,如指定特定话题录制等。 3. 在需要停止录制时,使用Ctrl+C快捷键结束录制过程。 回放bag文件的步骤如下: 1. 在终端输入以下命令回放bag文件: ``` rosbag play <bag文件路径> ``` 替换"<bag文件路径>"为实际的bag文件路径。 2. ROS将按照记录时的时间顺序回放数据,可以使用"-s"选项指定开始回放的时间。 通过在录制期间选择适当的话题,我们可以创建自己的数据集来训练机器学习算法、测试导航系统等。可以使用ROS提供的工具和库对bag文件进行处理和分析,如提取特定话题的数据、转换数据格式等。 总之,制作数据集的bag文件是一种方便的方法,可用于记录和管理大量传感器数据,为机器学习和机器人领域的实验和应用提供支持。

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值