34 import roslib; roslib.load_manifest(
'calibration_estimation')
40 """ Look for cam info in the calibration bagfile """ 42 bag = rosbag.Bag(bag_filename)
43 for topic, msg, t
in bag.read_messages():
44 if topic ==
"robot_measurement":
45 for cam_measurement
in msg.M_cam:
46 if cam_measurement.camera_id == cam_name:
47 print "Found a sample with camera [%s] in it" % cam_measurement.camera_id
48 cam_info = cam_measurement.cam_info
56 """ Get the robot description out of a bagfile """ 59 return rospy.get_param(
"robot_description")
60 bag = rosbag.Bag(bag_filename)
61 for topic, msg, t
in bag.read_messages(topics=[
'robot_description']):
62 if topic ==
'robot_description':
70 """ Get the number of measurements in our bagfile """ 72 bag = rosbag.Bag(bag_filename)
74 for topic, msg, t
in bag.read_messages(topics=[
'robot_measurement']):
75 if topic ==
'robot_measurement':
76 if index
in sample_skip_list:
77 print "Skipping sample:", index
86 """ Get all sensors from bagfile. """ 87 bag = rosbag.Bag(bag_filename)
90 for topic, msg, t
in bag.read_messages(topics=[
'robot_measurement']):
91 if topic ==
"robot_measurement":
92 if index
in sample_skip_list:
93 print "Skipping sample:", index
96 for cur_laser
in msg.M_laser:
97 if cur_laser.laser_id
in [
"tilt_laser_6x8",
"tilt_laser_8x6",
"tilt_laser_7x6",
"tilt_laser_6x7"]:
98 cur_laser.laser_id =
"tilt_laser" 100 ms.sensors_from_message(msg)
101 multisensors.append(ms)
def get_cam_info(bag_filename, cam_name)
def get_robot_measurement_count(bag_filename, sample_skip_list=[])
def get_robot_description(bag_filename, use_topic=False)
def get_multisensors(bag_filename, cur_sensors, sample_skip_list=[])