$search
00001 #! /usr/bin/env ipython 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2008, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of Willow Garage, Inc. nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 00034 # author: Vijay Pradeep 00035 00036 import roslib; roslib.load_manifest('pr2_calibration_estimation') 00037 00038 import sys 00039 import rospy 00040 import time 00041 import numpy 00042 import rosbag 00043 import yaml 00044 import os.path 00045 import numpy 00046 from numpy import kron, ones, eye, array, matrix, diag 00047 import multi_step_cov_estimator as est_helpers 00048 import opt_runner 00049 from sensors.multi_sensor import MultiSensor 00050 from robot_params import RobotParams 00051 from single_transform import SingleTransform 00052 from visualization_msgs.msg import Marker, MarkerArray 00053 import geometry_msgs.msg 00054 00055 def usage(): 00056 rospy.logerr("Not enough arguments") 00057 print "Usage:" 00058 print " ./proto1.py [bagfile] [output_dir] [loop_list.yaml]" 00059 sys.exit(0) 00060 00061 if __name__ == '__main__': 00062 rospy.init_node("scatterplot_viewer") 00063 00064 marker_guess_pub = rospy.Publisher("cb_guess", Marker) 00065 marker_fk_pub = rospy.Publisher("cal_markers", Marker) 00066 00067 print "Starting The Post Processing App\n" 00068 00069 if (len(rospy.myargv()) < 3): 00070 usage() 00071 else: 00072 bag_filename = rospy.myargv()[1] 00073 output_dir = rospy.myargv()[2] 00074 loop_list_filename = rospy.myargv()[3] 00075 00076 print "Using Bagfile: %s\n" % bag_filename 00077 if not os.path.isfile(bag_filename): 00078 rospy.logerr("Bagfile does not exist. Exiting...") 00079 sys.exit(1) 00080 00081 loop_list = yaml.load(open(loop_list_filename)) 00082 00083 config_param_name = "calibration_config" 00084 if not rospy.has_param(config_param_name): 00085 rospy.logerr("Could not find parameter [%s]. Please populate this namespace with the estimation configuration.", config_param_name) 00086 sys.exit(1) 00087 config = rospy.get_param(config_param_name) 00088 00089 # Process all the sensor definitions that are on the parameter server 00090 sensors_name = "sensors" 00091 if sensors_name not in config.keys(): 00092 rospy.logerr("Could not find namespace [%s/%s]. Please populate this namespace with sensors.", (config_param_name, sensors_name)) 00093 sys.exit(1) 00094 sensors_dump = [yaml.load(x) for x in config[sensors_name].values()] 00095 all_sensors_dict = est_helpers.build_sensor_defs(sensors_dump) 00096 all_sensor_types = list(set([x['sensor_type'] for x in all_sensors_dict.values()])) 00097 00098 # Load all the calibration steps. 00099 step_list = est_helpers.load_calibration_steps(config["cal_steps"]) 00100 # Only process the last step 00101 cur_step = step_list[-1] 00102 00103 # Load the resulting system definition 00104 system_def_dict = yaml.load(open(output_dir + "/" + cur_step["output_filename"] + ".yaml")) 00105 cb_poses = yaml.load(open(output_dir + "/" + cur_step["output_filename"] + "_poses.yaml")) 00106 free_dict = yaml.load(cur_step["free_params"]) 00107 00108 # Build the sensor definition subset for this step 00109 #sensor_defs = est_helpers.load_requested_sensors(all_sensors_dict, cur_step['sensors']) 00110 00111 00112 # sensor_3d_name = 'tilt_laser' 00113 # loop_list1 = [(sensor_3d_name, 'narrow_right_rect', {'color':'b', 'marker':'o'}), 00114 # (sensor_3d_name, 'narrow_left_rect', {'color':'b', 'marker':'s'}), 00115 # (sensor_3d_name, 'wide_left_rect', {'color':'r', 'marker':'o'}), 00116 # (sensor_3d_name, 'wide_right_rect', {'color':'r', 'marker':'s'})] 00117 # #loop_list1 = [] 00118 # 00119 # sensor_3d_name = 'right_arm_chain' 00120 # loop_list2r= [(sensor_3d_name, 'narrow_right_rect', {'color':'g', 'marker':'s'}), 00121 # (sensor_3d_name, 'narrow_left_rect', {'color':'g', 'marker':'s'}), 00122 # (sensor_3d_name, 'wide_left_rect', {'color':'y', 'marker':'s'}), 00123 # (sensor_3d_name, 'wide_right_rect', {'color':'y', 'marker':'s'})] 00124 # 00125 # sensor_3d_name = 'left_arm_chain' 00126 # loop_list2l= [(sensor_3d_name, 'narrow_right_rect', {'color':'g', 'marker':'o'}), 00127 # (sensor_3d_name, 'narrow_left_rect', {'color':'g', 'marker':'o'}), 00128 # (sensor_3d_name, 'wide_left_rect', {'color':'y', 'marker':'o'}), 00129 # (sensor_3d_name, 'wide_right_rect', {'color':'y', 'marker':'o'})] 00130 # 00131 # loop_list2 = loop_list2r + loop_list2l 00132 # #loop_list2 = [] 00133 # 00134 # loop_list3 = [('right_arm_chain', 'forearm_right_rect', {'color':'c', 'marker':'o'}), 00135 # ( 'right_arm_chain', 'forearm_left_rect', {'color':'m', 'marker':'o'}), 00136 # ( 'left_arm_chain', 'forearm_right_rect', {'color':'m', 'marker':'s'}), 00137 # ( 'left_arm_chain', 'forearm_left_rect', {'color':'c', 'marker':'s'})] 00138 # #loop_list3 = [] 00139 # 00140 # loop_list = loop_list1 + loop_list2 + loop_list3 00141 #loop_list = loop_list[0:1] 00142 00143 # loop_list = [('tilt_laser', 'narrow_right_rect', {'color':'b', 'marker':'o'})] 00144 00145 scatter_list = [] 00146 00147 marker_count = 0 00148 for cur_loop in loop_list: 00149 marker_count += 1 00150 sensor_defs = est_helpers.load_requested_sensors(all_sensors_dict, [cur_loop['cam'], cur_loop['3d']]) 00151 00152 # Generate the multisensor samples from the bag 00153 # f = open(bag_filename) 00154 multisensors = [] 00155 bag = rosbag.Bag(bag_filename) 00156 for topic, msg, t in bag.read_messages(topics=['robot_measurement']): 00157 if topic == "robot_measurement": 00158 # Hack to rename laser id 00159 for cur_laser in msg.M_laser: 00160 #pass 00161 if cur_laser.laser_id in ["tilt_laser_6x8", "tilt_laser_8x6", "tilt_laser_7x6", "tilt_laser_6x7"]: 00162 cur_laser.laser_id = "tilt_laser" 00163 #else: 00164 # cur_laser.laser_id = "tilt_laser_blah" 00165 ms = MultiSensor(sensor_defs) 00166 ms.sensors_from_message(msg) 00167 multisensors.append(ms) 00168 bag.close() 00169 00170 if (len([ms for ms in multisensors if len(ms.sensors) == 2]) == 0): 00171 print "********** No Data for [%s] + [%s] pair **********" % (cur_loop['cam'], cur_loop['3d']) 00172 continue 00173 00174 # Only grab the samples that have both the requested cam and requested 3D sensor 00175 multisensors_pruned, cb_poses_pruned = zip(*[(ms,cb) for ms,cb in zip(multisensors, cb_poses) if len(ms.sensors) == 2]) 00176 sample_ind = [k for k,ms in zip(range(len(multisensors)), multisensors) if len(ms.sensors) == 2] 00177 00178 print "Sample Indices:" 00179 print ", ".join(["%u" % i for i in sample_ind]) 00180 00181 system_def = RobotParams() 00182 system_def.configure(system_def_dict) 00183 for ms in multisensors: 00184 ms.update_config(system_def) 00185 00186 00187 error_calc = opt_runner.ErrorCalc(system_def, free_dict, multisensors_pruned, False) 00188 opt_all_vec = opt_runner.build_opt_vector(system_def, free_dict, numpy.array(cb_poses_pruned)) 00189 e = error_calc.calculate_error(opt_all_vec) 00190 #J = error_calc.calculate_jacobian(opt_all_vec) 00191 00192 # Display error breakdown 00193 errors_dict = opt_runner.compute_errors_breakdown(error_calc, multisensors_pruned, numpy.array(cb_poses_pruned)) 00194 00195 print "" 00196 print "Errors Breakdown:" 00197 for sensor_id, error_list in errors_dict.items(): 00198 error_cat = numpy.concatenate(error_list) 00199 rms_error = numpy.sqrt( numpy.mean(error_cat**2) ) 00200 print " %s: %.6f" % (sensor_id, rms_error) 00201 00202 00203 00204 # Calculate loop errors 00205 chain_sensors = [[s for s in ms.sensors if s.sensor_id == cur_loop['3d']][0] for ms in multisensors_pruned] 00206 cam_sensors = [[s for s in ms.sensors if s.sensor_id == cur_loop['cam']][0] for ms in multisensors_pruned] 00207 fk_points = [s.get_measurement() for s in chain_sensors] 00208 cb_points = [SingleTransform(pose).transform * system_def.checkerboards[ms.checkerboard].generate_points() for pose, ms in zip(cb_poses_pruned,multisensors_pruned)] 00209 00210 points_list_fk = [ geometry_msgs.msg.Point(cur_pt[0, 0], cur_pt[0, 1], cur_pt[0, 2]) for cur_pt in list(numpy.concatenate(fk_points,1).T)] 00211 points_list_guess = [ geometry_msgs.msg.Point(cur_pt[0, 0], cur_pt[0, 1], cur_pt[0, 2]) for cur_pt in list(numpy.concatenate(cb_points,1).T)] 00212 00213 m = Marker() 00214 m.header.frame_id = "/torso_lift_link" 00215 m.ns = "uncal_sensor" 00216 m.id = marker_count 00217 m.type = Marker.SPHERE_LIST 00218 m.action = Marker.MODIFY 00219 m.points = points_list_fk 00220 m.color.r = 0.0 00221 m.color.g = 0.0 00222 m.color.b = 1.0 00223 m.color.a = 1.0 00224 m.scale.x = 0.01 00225 m.scale.y = 0.01 00226 m.scale.z = 0.01 00227 00228 marker_fk_pub.publish(m) 00229 00230 m.points = points_list_guess 00231 m.ns = "estimated" 00232 m.color.r = 1.0 00233 m.color.g = 0.0 00234 m.color.b = 0.0 00235 marker_fk_pub.publish(m) 00236 00237 #fk_points = cb_points 00238 00239 #import code; code.interact(local=locals()) 00240 00241 cam_Js = [s.compute_expected_J(fk) for s,fk in zip(cam_sensors, fk_points)] 00242 cam_covs = [matrix(array(s.compute_cov(fk)) * kron(eye(s.get_residual_length()/2),ones([2,2]))) for s,fk in zip(cam_sensors, fk_points)] 00243 fk_covs = [matrix(array(s.compute_cov(None)) * kron(eye(s.get_residual_length()/3),ones([3,3]))) for s in chain_sensors] 00244 00245 full_covs = [matrix(cam_J)*fk_cov*matrix(cam_J).T + cam_cov for cam_J, cam_cov, fk_cov in zip(cam_Js, cam_covs, fk_covs)] 00246 00247 #import code; code.interact(local=locals()) 00248 00249 proj_points = [s.compute_expected(pts) for (s,pts) in zip(cam_sensors,fk_points)] 00250 meas_points = [s.get_measurement() for s in cam_sensors] 00251 00252 sample_ind = sum([ [sample_ind[k]]*meas_points[k].shape[0] for k in range(len(proj_points))], []) 00253 00254 00255 r = numpy.concatenate(proj_points) - numpy.concatenate(meas_points) 00256 00257 00258 bearing_list = [] 00259 #for ms in multisensors_pruned: 00260 # laser_sensor = [s for s in ms.sensors if s.sensor_id == "tilt_laser"][0] 00261 # cur_bearings = [js.position[1] for js in laser_sensor._M_laser.joint_points] 00262 # bearing_list.append(numpy.array(cur_bearings)) 00263 #y_coord_list = [ numpy.array(SingleTransform(pose).transform * system_def.checkerboards[ms.checkerboard].generate_points())[1,:] for pose, ms in zip(cb_poses_pruned,multisensors_pruned)] 00264 #y_coords = numpy.concatenate(y_coord_list) 00265 00266 #bearings = numpy.concatenate(bearing_list) 00267 00268 import matplotlib.pyplot as plt 00269 #print "Plot ops:" 00270 #print cur_loop['plot_ops'] 00271 cur_scatter = plt.scatter(array(r)[:,0], array(r)[:,1], **cur_loop['plot_ops']) 00272 scatter_list.append(cur_scatter) 00273 #plt.scatter(r[:,0], bearings, **plot_opts) 00274 00275 for k in range(len(sample_ind)): 00276 #plt.text(r[k,0], r[k,1], "%u" % sample_ind[k]) 00277 #plt.text(r[k,0], bearings[k], "%u" % sample_ind[k]) 00278 pass 00279 00280 for cur_cov in full_covs[0:1]: 00281 circ_angles = numpy.linspace(0,2*numpy.pi, 360, endpoint=True) 00282 circ_pos = numpy.concatenate( [ [numpy.sin(circ_angles)], 00283 [numpy.cos(circ_angles)] ] ) 00284 for k in range(cur_cov.shape[0]/2)[0:1]: 00285 l,v = numpy.linalg.eig(cur_cov[(2*k):(2*k+2),(2*k):(2*k+2)]) 00286 ellip = numpy.sqrt(4.6052) * matrix(v) * matrix(diag(numpy.sqrt(l))) * matrix(circ_pos) 00287 ellip_shifted = array(ellip + r[k,:].T) 00288 #import code; code.interact(local=locals()) 00289 #plt.plot(ellip_shifted[0,:], ellip_shifted[1,:], 'b') 00290 00291 plt.axis('equal') 00292 plt.grid(True) 00293 #plt.legend(scatter_list, [x['name'] for x in loop_list], prop={'size':'x-small'}) 00294 plt.show() 00295 00296 sys.exit(0) 00297 00298 #import code; code.interact(local=locals())