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
00035
00036
00037 import roslib; roslib.load_manifest('pr2_calibration_propagation')
00038 import sensor_msgs.msg
00039 import sensor_msgs.srv
00040 import rospy
00041 import rosbag
00042
00043 import math
00044 import sys
00045 import yaml
00046
00047 def usage():
00048 print "Usage: ./baseline_updater camera:=[camera_namespace] [calibration_bagfile] [system_filename] [config_camera_name]"
00049 print " camera_namespace: Ros name to prepend onto the call to set_calibration"
00050 print " config_filename: yaml file that stores the baseline shift"
00051 print " config_camera_name: Name of the camera in the configuration file. Tells script which baseline shift to use"
00052
00053 def main():
00054 rospy.init_node('baseline_updater', anonymous=True)
00055
00056 argv = rospy.myargv()
00057
00058 if len(argv) != 4:
00059 usage()
00060 sys.exit(0)
00061
00062 bag_filename = argv[1]
00063 system_filename = argv[2]
00064 config_cam_name = argv[3]
00065
00066
00067
00068 cam_info = None
00069 bag = rosbag.Bag(bag_filename)
00070 for topic, msg, t in bag.read_messages():
00071 if topic == "robot_measurement":
00072 for cam_measurement in msg.M_cam:
00073 if cam_measurement.camera_id == config_cam_name:
00074 print "Found a sample with camera [%s] in it" % cam_measurement.camera_id
00075 cam_info = cam_measurement.cam_info
00076 break
00077 if cam_info != None:
00078 break
00079
00080 if cam_info == None:
00081 print "Could not find a camera of the name [%s]" % config_cam_name
00082 sys.exit(-1)
00083
00084 print "Original Projection Matrix:"
00085 for k in range(3):
00086 print " %s" % " ".join(["% 12.5f" % p for p in cam_info.P[k*4:k*4+4]])
00087 original_baseline = cam_info.P[3]
00088
00089
00090 system_dict = yaml.load(open(system_filename))
00091 cam_dict = system_dict['rectified_cams']
00092 target_cam_dict = cam_dict[config_cam_name]
00093 baseline_shift = target_cam_dict['baseline_shift']
00094
00095 print "Baseline Shift:"
00096 print " % 12.5f" % baseline_shift
00097
00098
00099 updated_baseline = original_baseline + baseline_shift
00100
00101
00102 updated_P = list(cam_info.P)
00103 updated_P[3] = updated_baseline
00104 cam_info.P = updated_P
00105
00106 print "Updated Projection Matrix:"
00107 for k in range(3):
00108 print " %s" % " ".join(["% 12.5f" % p for p in cam_info.P[k*4:k*4+4]])
00109
00110
00111 cam_name = rospy.resolve_name("camera")
00112 set_cal_service_name = cam_name + "/set_camera_info"
00113
00114 print "Waiting for service [%s] to be available" % set_cal_service_name
00115 rospy.wait_for_service(set_cal_service_name)
00116 print "Writing camera info to camera memory..."
00117 set_cal_srv = rospy.ServiceProxy(set_cal_service_name, sensor_msgs.srv.SetCameraInfo)
00118 resp = set_cal_srv(cam_info)
00119 if resp.success:
00120 print "Done writing to camera"
00121 else:
00122 print "**************** ERROR WRITING TO CAMERA. PLEASE RETRY ***********************"
00123 sys.exit(-1)
00124
00125 if __name__ == "__main__":
00126 main()