• ROS系列(二):rosbag 中提取视频数据


    一、环境安装

    当前环境在上一篇文章的基础上进行配置。

    ROS系列(一):【环境配置】rosbag 包安装_安装rosbag-CSDN博客

    继续安装

    sudo apt install ffmpeg

    python 包如下

    pip install sensor_msgs --extra-index-url https://rospypi.github.io/simple/
    pip install geometry_msgs --extra-index-url https://rospypi.github.io/simple/
    pip install opencv-python
    pip install roslz4 --extra-index-url https://rospypi.github.io/simple/

    安装好环境后:

    使用如下脚本:

    1. #!/usr/bin/env python3
    2. """
    3. rosbag2video.py
    4. rosbag to video file conversion tool
    5. by Abel Gabor 2019
    6. baquatelle@gmail.com
    7. requirements:
    8. sudo apt install python3-roslib python3-sensor-msgs python3-opencv ffmpeg
    9. based on the tool by Maximilian Laiacker 2016
    10. post@mlaiacker.de"""
    11. import roslib
    12. #roslib.load_manifest('rosbag')
    13. import rospy
    14. import rosbag
    15. import sys, getopt
    16. import os
    17. from sensor_msgs.msg import CompressedImage
    18. from sensor_msgs.msg import Image
    19. import cv2
    20. import numpy as np
    21. import shlex, subprocess
    22. MJPEG_VIDEO = 1
    23. RAWIMAGE_VIDEO = 2
    24. VIDEO_CONVERTER_TO_USE = "ffmpeg" # or you may want to use "avconv"
    25. def print_help():
    26. print('rosbag2video.py [--fps 25] [--rate 1] [-o outputfile] [-v] [-s] [-t topic] bagfile1 [bagfile2] ...')
    27. print()
    28. print('Converts image sequence(s) in ros bag file(s) to video file(s) with fixed frame rate using',VIDEO_CONVERTER_TO_USE)
    29. print(VIDEO_CONVERTER_TO_USE,'needs to be installed!')
    30. print()
    31. print('--fps Sets FPS value that is passed to',VIDEO_CONVERTER_TO_USE)
    32. print(' Default is 25.')
    33. print('-h Displays this help.')
    34. print('--ofile (-o) sets output file name.')
    35. print(' If no output file name (-o) is given the filename \'.mp4\' is used and default output codec is h264.')
    36. print(' Multiple image topics are supported only when -o option is _not_ used.')
    37. print(' ',VIDEO_CONVERTER_TO_USE,' will guess the format according to given extension.')
    38. print(' Compressed and raw image messages are supported with mono8 and bgr8/rgb8/bggr8/rggb8 formats.')
    39. print('--rate (-r) You may slow down or speed up the video.')
    40. print(' Default is 1.0, that keeps the original speed.')
    41. print('-s Shows each and every image extracted from the rosbag file (cv_bride is needed).')
    42. print('--topic (-t) Only the images from topic "topic" are used for the video output.')
    43. print('-v Verbose messages are displayed.')
    44. print('--prefix (-p) set a output file name prefix othervise \'bagfile1\' is used (if -o is not set).')
    45. print('--start Optional start time in seconds.')
    46. print('--end Optional end time in seconds.')
    47. class RosVideoWriter():
    48. def __init__(self, fps=25.0, rate=1.0, topic="", output_filename ="", display= False, verbose = False, start = rospy.Time(0), end = rospy.Time(sys.maxsize)):
    49. self.opt_topic = topic
    50. self.opt_out_file = output_filename
    51. self.opt_verbose = verbose
    52. self.opt_display_images = display
    53. self.opt_start = start
    54. self.opt_end = end
    55. self.rate = rate
    56. self.fps = fps
    57. self.opt_prefix= None
    58. self.t_first={}
    59. self.t_file={}
    60. self.t_video={}
    61. self.p_avconv = {}
    62. def parseArgs(self, args):
    63. opts, opt_files = getopt.getopt(args,"hsvr:o:t:p:",["fps=","rate=","ofile=","topic=","start=","end=","prefix="])
    64. for opt, arg in opts:
    65. if opt == '-h':
    66. print_help()
    67. sys.exit(0)
    68. elif opt == '-s':
    69. self.opt_display_images = True
    70. elif opt == '-v':
    71. self.opt_verbose = True
    72. elif opt in ("--fps"):
    73. self.fps = float(arg)
    74. elif opt in ("-r", "--rate"):
    75. self.rate = float(arg)
    76. elif opt in ("-o", "--ofile"):
    77. self.opt_out_file = arg
    78. elif opt in ("-t", "--topic"):
    79. self.opt_topic = arg
    80. elif opt in ("-p", "--prefix"):
    81. self.opt_prefix = arg
    82. elif opt in ("--start"):
    83. self.opt_start = rospy.Time(int(arg))
    84. if(self.opt_verbose):
    85. print("starting at",self.opt_start.to_sec())
    86. elif opt in ("--end"):
    87. self.opt_end = rospy.Time(int(arg))
    88. if(self.opt_verbose):
    89. print("ending at",self.opt_end.to_sec())
    90. else:
    91. print("opz:", opt,'arg:', arg)
    92. if (self.fps<=0):
    93. print("invalid fps", self.fps)
    94. self.fps = 1
    95. if (self.rate<=0):
    96. print("invalid rate", self.rate)
    97. self.rate = 1
    98. if(self.opt_verbose):
    99. print("using ",self.fps," FPS")
    100. return opt_files
    101. # filter messages using type or only the opic we whant from the 'topic' argument
    102. def filter_image_msgs(self, topic, datatype, md5sum, msg_def, header):
    103. if(datatype=="sensor_msgs/CompressedImage"):
    104. if (self.opt_topic != "" and self.opt_topic == topic) or self.opt_topic == "":
    105. print("############# COMPRESSED IMAGE ######################")
    106. print(topic,' with datatype:', str(datatype))
    107. print()
    108. return True;
    109. if(datatype=="theora_image_transport/Packet"):
    110. if (self.opt_topic != "" and self.opt_topic == topic) or self.opt_topic == "":
    111. print(topic,' with datatype:', str(datatype))
    112. print('!!! theora is not supported, sorry !!!')
    113. return False;
    114. if(datatype=="sensor_msgs/Image"):
    115. if (self.opt_topic != "" and self.opt_topic == topic) or self.opt_topic == "":
    116. print("############# UNCOMPRESSED IMAGE ######################")
    117. print(topic,' with datatype:', str(datatype))
    118. print()
    119. return True;
    120. return False;
    121. def write_output_video(self, msg, topic, t, video_fmt, pix_fmt = ""):
    122. # no data in this topic
    123. if len(msg.data) == 0 :
    124. return
    125. # initiate data for this topic
    126. if not topic in self.t_first :
    127. self.t_first[topic] = t # timestamp of first image for this topic
    128. self.t_video[topic] = 0
    129. self.t_file[topic] = 0
    130. # if multiple streams of images will start at different times the resulting video files will not be in sync
    131. # current offset time we are in the bag file
    132. self.t_file[topic] = (t-self.t_first[topic]).to_sec()
    133. # fill video file up with images until we reache the current offset from the beginning of the bag file
    134. while self.t_video[topic] < self.t_file[topic]/self.rate :
    135. if not topic in self.p_avconv:
    136. # we have to start a new process for this topic
    137. if self.opt_verbose :
    138. print("Initializing pipe for topic", topic, "at time", t.to_sec())
    139. if self.opt_out_file=="":
    140. out_file = self.opt_prefix + str(topic).replace("/", "_")+".mp4"
    141. else:
    142. out_file = self.opt_out_file
    143. if self.opt_verbose :
    144. print("Using output file ", out_file, " for topic ", topic, ".")
    145. if video_fmt == MJPEG_VIDEO :
    146. cmd = [VIDEO_CONVERTER_TO_USE, '-v', '1', '-stats', '-r',str(self.fps),'-c','mjpeg','-f','mjpeg','-i','-','-an',out_file]
    147. self.p_avconv[topic] = subprocess.Popen(cmd, stdin=subprocess.PIPE)
    148. if self.opt_verbose :
    149. print("Using command line:")
    150. print(cmd)
    151. elif video_fmt == RAWIMAGE_VIDEO :
    152. size = str(msg.width)+"x"+str(msg.height)
    153. cmd = [VIDEO_CONVERTER_TO_USE, '-v', '1', '-stats','-r',str(self.fps),'-f','rawvideo','-s',size,'-pix_fmt', pix_fmt,'-i','-','-an',out_file]
    154. self.p_avconv[topic] = subprocess.Popen(cmd, stdin=subprocess.PIPE)
    155. if self.opt_verbose :
    156. print("Using command line:")
    157. print(cmd)
    158. else :
    159. print("Script error, unknown value for argument video_fmt in function write_output_video.")
    160. exit(1)
    161. # send data to ffmpeg process pipe
    162. self.p_avconv[topic].stdin.write(msg.data)
    163. # next frame time
    164. self.t_video[topic] += 1.0/self.fps
    165. def addBag(self, filename):
    166. if self.opt_display_images:
    167. from cv_bridge import CvBridge, CvBridgeError
    168. bridge = CvBridge()
    169. cv_image = []
    170. if self.opt_verbose :
    171. print("Bagfile: {}".format(filename))
    172. if not self.opt_prefix:
    173. # create the output in the same folder and name as the bag file minu '.bag'
    174. self.opt_prefix = bagfile[:-4]
    175. #Go through the bag file
    176. bag = rosbag.Bag(filename)
    177. if self.opt_verbose :
    178. print("Bag opened.")
    179. # loop over all topics
    180. for topic, msg, t in bag.read_messages(connection_filter=self.filter_image_msgs, start_time=self.opt_start, end_time=self.opt_end):
    181. try:
    182. if msg.format.find("jpeg")!=-1 :
    183. if msg.format.find("8")!=-1 and (msg.format.find("rgb")!=-1 or msg.format.find("bgr")!=-1 or msg.format.find("bgra")!=-1 ):
    184. if self.opt_display_images:
    185. np_arr = np.fromstring(msg.data, np.uint8)
    186. cv_image = cv2.imdecode(np_arr, cv2.CV_LOAD_IMAGE_COLOR)
    187. self.write_output_video( msg, topic, t, MJPEG_VIDEO )
    188. elif msg.format.find("mono8")!=-1 :
    189. if self.opt_display_images:
    190. np_arr = np.fromstring(msg.data, np.uint8)
    191. cv_image = cv2.imdecode(np_arr, cv2.CV_LOAD_IMAGE_COLOR)
    192. self.write_output_video( msg, topic, t, MJPEG_VIDEO )
    193. elif msg.format.find("16UC1")!=-1 :
    194. if self.opt_display_images:
    195. np_arr = np.fromstring(msg.data, np.uint16)
    196. cv_image = cv2.imdecode(np_arr, cv2.CV_LOAD_IMAGE_COLOR)
    197. self.write_output_video( msg, topic, t, MJPEG_VIDEO )
    198. else:
    199. print('unsupported jpeg format:', msg.format, '.', topic)
    200. # has no attribute 'format'
    201. except AttributeError:
    202. try:
    203. pix_fmt=None
    204. if msg.encoding.find("mono8")!=-1 or msg.encoding.find("8UC1")!=-1:
    205. pix_fmt = "gray"
    206. if self.opt_display_images:
    207. cv_image = bridge.imgmsg_to_cv2(msg, "bgr8")
    208. elif msg.encoding.find("bgra")!=-1 :
    209. pix_fmt = "bgra"
    210. if self.opt_display_images:
    211. cv_image = bridge.imgmsg_to_cv2(msg, "bgr8")
    212. elif msg.encoding.find("bgr8")!=-1 :
    213. pix_fmt = "bgr24"
    214. if self.opt_display_images:
    215. cv_image = bridge.imgmsg_to_cv2(msg, "bgr8")
    216. elif msg.encoding.find("bggr8")!=-1 :
    217. pix_fmt = "bayer_bggr8"
    218. if self.opt_display_images:
    219. cv_image = bridge.imgmsg_to_cv2(msg, "bayer_bggr8")
    220. elif msg.encoding.find("rggb8")!=-1 :
    221. pix_fmt = "bayer_rggb8"
    222. if self.opt_display_images:
    223. cv_image = bridge.imgmsg_to_cv2(msg, "bayer_rggb8")
    224. elif msg.encoding.find("rgb8")!=-1 :
    225. pix_fmt = "rgb24"
    226. if self.opt_display_images:
    227. cv_image = bridge.imgmsg_to_cv2(msg, "bgr8")
    228. elif msg.encoding.find("16UC1")!=-1 :
    229. pix_fmt = "gray16le"
    230. else:
    231. print('unsupported encoding:', msg.encoding, topic)
    232. #exit(1)
    233. if pix_fmt:
    234. self.write_output_video( msg, topic, t, RAWIMAGE_VIDEO, pix_fmt )
    235. except AttributeError:
    236. # maybe theora packet
    237. # theora not supported
    238. if self.opt_verbose :
    239. print("Could not handle this format. Maybe thoera packet? theora is not supported.")
    240. pass
    241. if self.opt_display_images:
    242. cv2.imshow(topic, cv_image)
    243. key=cv2.waitKey(1)
    244. if key==1048603:
    245. exit(1)
    246. if self.p_avconv == {}:
    247. print("No image topics found in bag:", filename)
    248. bag.close()
    249. if __name__ == '__main__':
    250. #print()
    251. #print('rosbag2video, by Maximilian Laiacker 2020 and Abel Gabor 2019')
    252. #print()
    253. if len(sys.argv) < 2:
    254. print('Please specify ros bag file(s)!')
    255. print_help()
    256. sys.exit(1)
    257. else :
    258. videowriter = RosVideoWriter()
    259. try:
    260. opt_files = videowriter.parseArgs(sys.argv[1:])
    261. except getopt.GetoptError:
    262. print_help()
    263. sys.exit(2)
    264. # loop over all files
    265. for files in range(0,len(opt_files)):
    266. #First arg is the bag to look at
    267. bagfile = opt_files[files]
    268. videowriter.addBag(bagfile)
    269. print("finished")
    使用方法介绍:

    python rosbag2video.py XXX.bag

    参数说明:

    [–fps] :设置传递给ffmpeg的帧率,默认为25;
    [-h]:显示帮助;
    [–ofile]:设置输出文件名;
    [–rate]:放慢或加快视频。默认值是1.0,保持原来的速度;
    [-s]:显示从rosbag文件提取的每个图像;
    [–topic]:仅来自“topic”的图像用于视频输出;
    [-v]:显示详细消息;
    [–prefix]:设置输出文件名前缀,否则使用“ bagfile1”(如果未设置-o);
    [–start]:可选的开始时间(以秒为单位);
    [–end]:可选结束时间,单位为秒;

    执行结果:

  • 相关阅读:
    SpringCloud之Sentinel
    《web课程设计》用HTML CSS做一个简洁、漂亮的个人博客网站
    如何将转换器应用于时序模型
    docker 服务自动重启
    【MySql进阶】索引详解(三):索引的使用和创建原则、索引失效、索引优化
    论文阅读 Dynamic Graph Representation Learning Via Self-Attention Networks
    c++ 程序通用多线程单例设计 c++ web 框架设计经验谈
    【白帽子讲Web安全】第二章 浏览器安全
    倩女幽魂手游攻略:云手机自动搬砖辅助教程!
    (附源码)spring boot信佳玩具有限公司仓库管理系统 毕业设计 011553
  • 原文地址:https://blog.csdn.net/ckq707718837/article/details/133853535