'''This is a converter for the Intel Research Lab SLAM dataset ( http://kaspar.informatik.uni-freiburg.de/~slamEvaluation/datasets/intel.clf ) to rosbag'''
import rospy import rosbag from sensor_msgs.msg import LaserScan from nav_msgs.msg import Odometry from math import pi from tf2_msgs.msg import TFMessage from geometry_msgs.msg import TransformStamped import tf import sys import logging logging.basicConfig()
defmake_tf_msg(x, y, theta, t,base,base0): trans = TransformStamped() trans.header.stamp = t trans.header.frame_id = base trans.child_frame_id = base0 trans.transform.translation.x = x trans.transform.translation.y = y q = tf.transformations.quaternion_from_euler(0, 0, theta) trans.transform.rotation.x = q[0] trans.transform.rotation.y = q[1] trans.transform.rotation.z = q[2] trans.transform.rotation.w = q[3]
msg = TFMessage() msg.transforms.append(trans) return msg if __name__ == "__main__": iflen(sys.argv) < 3: print"请输入dataset文件名。" exit() print"正在处理" + sys.argv[1] + "..." withopen(sys.argv[1]) as dataset: with rosbag.Bag(sys.argv[2], 'w') as bag: i = 1 for line in dataset.readlines(): line = line.strip() tokens = line.split(' ') iflen(tokens) <= 2: continue if tokens[0] == 'FLASER': msg = LaserScan() num_scans = int(tokens[1])