36 import roslib; roslib.load_manifest(
'calibration_estimation')
46 from numpy
import kron, ones, eye, array, matrix, diag
53 from visualization_msgs.msg
import Marker, MarkerArray
54 import geometry_msgs.msg
57 rospy.logerr(
"Not enough arguments")
59 print " ./error_visualization.py [bagfile] [output_dir] [loop_list.yaml]" 62 if __name__ ==
'__main__':
63 rospy.init_node(
"error_visualization")
64 marker_pub = rospy.Publisher(
"calibration_error", Marker)
66 print "Starting The Error Visualization App\n" 68 if (len(rospy.myargv()) < 3):
71 bag_filename = rospy.myargv()[1]
72 output_dir = rospy.myargv()[2]
73 loop_list_filename = rospy.myargv()[3]
75 print "Using Bagfile: %s\n" % bag_filename
76 if not os.path.isfile(bag_filename):
77 rospy.logerr(
"Bagfile does not exist. Exiting...")
80 loop_list = yaml.load(open(loop_list_filename))
83 config_param_name =
"calibration_config" 84 if not rospy.has_param(config_param_name):
85 rospy.logerr(
"Could not find parameter [%s]. Please populate this namespace with the estimation configuration.", config_param_name)
87 config = rospy.get_param(config_param_name)
90 sensors_name =
"sensors" 91 if sensors_name
not in config.keys():
92 rospy.logerr(
"Could not find namespace [%s/%s]. Please populate this namespace with sensors.", (config_param_name, sensors_name))
94 all_sensors_dict = est_helpers.build_sensor_defs(config[sensors_name])
95 all_sensor_types = list(set([x[
'sensor_type']
for x
in all_sensors_dict.values()]))
98 step_list = est_helpers.load_calibration_steps(config[
"cal_steps"])
100 cur_step = step_list[-1]
103 system_def_dict = yaml.load(open(output_dir +
"/" + cur_step[
"output_filename"] +
".yaml"))
105 cb_poses = yaml.load(open(output_dir +
"/" + cur_step[
"output_filename"] +
"_poses.yaml"))
106 free_dict = yaml.load(cur_step[
"free_params"])
108 sample_skip_list = rospy.get_param(
'calibration_skip_list', [])
112 for cur_loop
in loop_list:
115 sensor_defs = est_helpers.load_requested_sensors(all_sensors_dict, [cur_loop[
'cam'], cur_loop[
'3d']])
118 if (len([ms
for ms
in multisensors
if len(ms.sensors) == 2]) == 0):
119 print "********** No Data for [%s] + [%s] pair **********" % (cur_loop[
'cam'], cur_loop[
'3d'])
121 label_list.append(cur_loop)
124 multisensors_pruned, cb_poses_pruned = zip(*[(ms,cb)
for ms,cb
in zip(multisensors, cb_poses)
if len(ms.sensors) == 2])
125 sample_ind = [k
for k,ms
in zip(range(len(multisensors)), multisensors)
if len(ms.sensors) == 2]
126 sample_ind = [i
for i
in sample_ind
if i
not in sample_skip_list]
128 print "Sample Indices:" 129 print ", ".join([
"%u" % i
for i
in sample_ind])
131 for ms
in multisensors:
132 ms.update_config(system_def)
135 opt_all_vec = opt_runner.build_opt_vector(system_def, free_dict, numpy.array(cb_poses_pruned))
136 e = error_calc.calculate_error(opt_all_vec)
139 errors_dict = opt_runner.compute_errors_breakdown(error_calc, multisensors_pruned, numpy.array(cb_poses_pruned))
142 print "Errors Breakdown:" 143 for sensor_id, error_list
in errors_dict.items():
144 print " %s:" % sensor_id
146 for error
in error_list:
148 rms_error = numpy.sqrt( numpy.mean(error**2) )
149 print " Sample %d: %.6f" % (i, rms_error)
151 error_cat = numpy.concatenate(error_list)
152 rms_error = numpy.sqrt( numpy.mean(error_cat**2) )
153 print " Total: %.6f" % rms_error
156 chain_sensors = [[s
for s
in ms.sensors
if s.sensor_id == cur_loop[
'3d']][0]
for ms
in multisensors_pruned]
157 cam_sensors = [[s
for s
in ms.sensors
if s.sensor_id == cur_loop[
'cam']][0]
for ms
in multisensors_pruned]
158 fk_points = [s.get_measurement()
for s
in chain_sensors]
159 cb_points = [
SingleTransform(pose).transform * system_def.checkerboards[ms.checkerboard].generate_points()
for pose, ms
in zip(cb_poses_pruned,multisensors_pruned)]
161 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)]
162 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)]
165 m.header.frame_id = system_def.base_link
166 m.ns = loop_list_filename+
"_points_3d" 168 m.type = Marker.SPHERE_LIST
169 m.action = Marker.MODIFY
170 m.points = points_list_fk
178 marker_pub.publish(m)
180 m.points = points_list_guess
181 m.ns = loop_list_filename+
"_points_cam" 185 marker_pub.publish(m)
187 cam_Js = [s.compute_expected_J(fk)
for s,fk
in zip(cam_sensors, fk_points)]
188 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)]
189 fk_covs = [matrix(array(s.compute_cov(
None)) * kron(eye(s.get_residual_length()/3),ones([3,3])))
for s
in chain_sensors]
191 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)]
193 proj_points = [s.compute_expected(pts)
for (s,pts)
in zip(cam_sensors,fk_points)]
194 meas_points = [s.get_measurement()
for s
in cam_sensors]
196 r1 = numpy.concatenate(meas_points)
197 r2 = numpy.concatenate(proj_points)
198 r = numpy.concatenate((r1,r2),axis=0)
200 import matplotlib.pyplot
as plt
202 cur_scatter = plt.scatter(array(r)[:,0], array(r)[:,1], **cur_loop[
'plot_ops'])
203 scatter_list.append(cur_scatter)
205 plt.gca().invert_yaxis()
208 plt.legend(scatter_list, [x[
'name']
for x
in label_list], prop={
'size':
'x-small'})
def get_robot_description(bag_filename, use_topic=False)
def get_multisensors(bag_filename, cur_sensors, sample_skip_list=[])