$search
00001 #! /usr/bin/env python 00002 00003 import roslib; roslib.load_manifest('pr2_calibration_propagation') 00004 import rospy 00005 import pr2_calibration_propagation.update_urdf as update_urdf 00006 00007 import math 00008 import pdb 00009 import sys 00010 # from ros import rosrecord 00011 import rosbag 00012 00013 00014 00015 try: 00016 import yaml 00017 except ImportError, e: 00018 print >> sys.stderr, "Cannot import yaml. Please make sure the pyyaml system dependency is installed" 00019 raise e 00020 00021 if __name__ == '__main__': 00022 00023 #rospy.init_node("propagate_config") 00024 00025 if len(rospy.myargv()) < 5: 00026 print "Usage: ./propagate_config [initial.yaml] [calibrated.yaml] [cal_measurements.bag] [cal_output.xml]" 00027 sys.exit(0) 00028 00029 #filenames 00030 initial_yaml_filename = rospy.myargv()[1] 00031 calibrated_yaml_filename = rospy.myargv()[2] 00032 measurement_filename = rospy.myargv()[3] 00033 output_filename = rospy.myargv()[4] 00034 00035 bag = rosbag.Bag(measurement_filename) 00036 xml_in = None 00037 for topic, msg, t in bag.read_messages(): 00038 if topic == "robot_description" or topic == "/robot_description": 00039 xml_in = msg.data 00040 if xml_in is None: 00041 print "Error: Could not find URDF in bagfile. Make sure topic 'robot_description' exists" 00042 sys.exit(-1) 00043 bag.close() 00044 00045 #read in files 00046 system_default = yaml.load(file(initial_yaml_filename, 'r')) 00047 system_calibrated = yaml.load(file(calibrated_yaml_filename, 'r')) 00048 00049 xml_out = update_urdf.update_urdf(system_default, system_calibrated, xml_in) 00050 00051 outfile = open(output_filename, 'w') 00052 outfile.write(xml_out) 00053 outfile.close()