1.首先查看rosbag中的详细信息
rosbag info *.bag //*为你自己的数据包的名称
如下图所示
从中可以看出,存在两个topic,/cam0/image_raw为图像topic,/imu0为imu topic,我们需要将这两个信息转成图像序列和.txt格式
2.解析bag文件得到带时间戳的.png图片
#coding:utf-8
import roslib;
import rosbag
import rospy
import cv2
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
from cv_bridge import CvBridgeError
path='/home/xlgm/' #存放图片的位置
class ImageCreator():
def __init__(self):
self.bridge = CvBridge()
with rosbag.Bag('kalibr.bag', 'r') as bag: #要读取的bag文件;
for topic,msg,t in bag.read_messages():
if topic == "/cam0/image_raw": #图像的topic;
try:
cv_image = self.bridge.imgmsg_to_cv2(msg,"bgr8")
except CvBridgeError as e:
print e
timeq = msg.header.stamp.to_sec()
timestr = "{:.6f}".format(timeq)
#%.6f表示小数点后带有6位,可根据精确度需要修改;"%.6f" % msg.header.stamp.to_sec() * pow(10, 9)
image_name = timestr+ ".png" #图像命名:时间戳.png
cv2.imwrite(path+image_name, cv_image) #保存;
imu = open("imu0.txt",'w')
for topic,msg,t in bag.read_messages():
if topic == "/imu0": #imu topic;
acc_y = "%.6f" % msg.linear_acceleration.y
acc_x = "%.6f" % msg.linear_acceleration.x
acc_z = "%.6f" % msg.linear_acceleration.z
w_y = "%.6f" % msg.angular_velocity.y
w_x = "%.6f" % msg.angular_velocity.x
w_z = "%.6f" % msg.angular_velocity.z
timeimu = "%.6f" % msg.header.stamp.to_sec()
imudata = timeimu + " " + w_x + " " + w_y + " " + w_z + " " + acc_x + " " + acc_y + " " + acc_z
imu.write(imudata)
imu.write('\n')
imu.close()
if __name__ == '__main__':
#rospy.init_node(PKG)
try:
image_creator = ImageCreator()
except rospy.ROSInterruptException:
pass
通过解析,在cam0下得到相对应的图像序列,如下图
保存带.txt格式的imu数据