参考链接:http://wiki.ros.org/rosbag/Cookbook#CA-eb21df553314f94f3af8b3daf2f1fb49c3e78cf7_3
- 修改rosbag文件中对应topic的时间戳
#!/usr/bin/env python3
import rospy
import rosbag
import sys
if sys.getdefaultencoding() != 'utf-8':
reload(sys)
sys.setdefaultencoding('utf-8')
bag_name = '2021-06-09-15-16-30.bag' #被修改的bag名
out_bag_name = 'change_2021-06-09-15-16-30.bag' #修改后的bag名
dst_dir = '/home/stone/Desktop/data/' #使用路径
with rosbag.Bag(dst_dir+out_bag_name, 'w') as outbag:
stamp = None
#topic:就是发布的topic msg:该topic在当前时间点下的message t:消息记录时间(非header)
##read_messages内可以指定的某个topic
for topic, msg, t in rosbag.Bag(dst_dir+bag_name).read_messages():
if topic == '/livox/imu':
stamp = msg.header.stamp
# print("imu")
#print(stamp)
#针对没有header的文件,使用上面帧数最高的topic(即:/gps)的时间戳
##因为read_messages是逐时间读取,所以该方法可以使用
elif topic == '/livox/lidar' and stamp is not None:
#print("lidar")
#print(msg.header.stamp)
outbag.write(topic, msg, stamp)
# continue
# #针对格式为Header的topic
elif topic == '/a_image' and stamp is not None:
#print("image")
#print(msg.header.stamp)
outbag.write(topic, msg, stamp+rospy.Duration(6))
# outbag.write(topic, msg, msg.stamp)
# continue
# #针对一般topic
#outbag.write(topic, msg, msg.header.stamp)
print("finished")
- 对激光雷达进行积分