Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 import roslib; roslib.load_manifest('calibration_estimation')
00035 import rosbag
00036
00037 from calibration_estimation.sensors.multi_sensor import MultiSensor
00038
00039 def get_cam_info(bag_filename, cam_name):
00040 """ Look for cam info in the calibration bagfile """
00041 cam_info = None
00042 bag = rosbag.Bag(bag_filename)
00043 for topic, msg, t in bag.read_messages():
00044 if topic == "robot_measurement":
00045 for cam_measurement in msg.M_cam:
00046 if cam_measurement.camera_id == cam_name:
00047 print "Found a sample with camera [%s] in it" % cam_measurement.camera_id
00048 cam_info = cam_measurement.cam_info
00049 break
00050 if cam_info != None:
00051 break
00052 return cam_info
00053
00054
00055 def get_robot_description(bag_filename, use_topic=False):
00056 """ Get the robot description out of a bagfile """
00057 if use_topic:
00058 import rospy
00059 return rospy.get_param("robot_description")
00060 bag = rosbag.Bag(bag_filename)
00061 for topic, msg, t in bag.read_messages(topics=['robot_description']):
00062 if topic == 'robot_description':
00063 bag.close()
00064 return msg.data
00065 bag.close()
00066 return ""
00067
00068
00069 def get_robot_measurement_count(bag_filename, sample_skip_list=[]):
00070 """ Get the number of measurements in our bagfile """
00071 msg_count = 0
00072 bag = rosbag.Bag(bag_filename)
00073 index = 0
00074 for topic, msg, t in bag.read_messages(topics=['robot_measurement']):
00075 if topic == 'robot_measurement':
00076 if index in sample_skip_list:
00077 print "Skipping sample:", index
00078 else:
00079 msg_count+=1
00080 index += 1
00081 bag.close()
00082 return msg_count
00083
00084
00085 def get_multisensors(bag_filename, cur_sensors, sample_skip_list=[]):
00086 """ Get all sensors from bagfile. """
00087 bag = rosbag.Bag(bag_filename)
00088 multisensors = []
00089 index = 0
00090 for topic, msg, t in bag.read_messages(topics=['robot_measurement']):
00091 if topic == "robot_measurement":
00092 if index in sample_skip_list:
00093 print "Skipping sample:", index
00094 else:
00095
00096 for cur_laser in msg.M_laser:
00097 if cur_laser.laser_id in ["tilt_laser_6x8", "tilt_laser_8x6", "tilt_laser_7x6", "tilt_laser_6x7"]:
00098 cur_laser.laser_id = "tilt_laser"
00099 ms = MultiSensor(cur_sensors)
00100 ms.sensors_from_message(msg)
00101 multisensors.append(ms)
00102 index += 1
00103 bag.close()
00104 return multisensors
00105