36 import roslib; roslib.load_manifest(
'calibration_estimation')
51 from numpy
import matrix
63 print '\n\nYou pressed Ctrl+C!\n' 66 signal.signal(signal.SIGINT, signal_handler)
70 rospy.logerr(
"Not enough arguments")
72 print " ./proto1.py [bagfile] [output_dir]" 78 Given a list of sensor definition dictionaries, merge them into a single dictionary 80 all_sensors_dict = dict()
83 for cur_sensor_type, cur_sensor_list
in sensors.items():
84 if cur_sensor_type
in [
'checkerboards']:
86 for cur_sensor_name, cur_sensor
in cur_sensor_list.items():
87 cur_sensor[
'sensor_id'] = cur_sensor_name
89 if cur_sensor[
'sensor_id']
in all_sensors_dict.keys():
90 rospy.logwarn(
"Loading a duplicate [%s]. Overwriting previous" % cur_sensor[
'sensor_id'])
91 all_sensors_dict[cur_sensor[
'sensor_id']] = cur_sensor
92 all_sensors_dict[cur_sensor[
'sensor_id']][
'sensor_type'] = cur_sensor_type
94 print "The following error sensors have been loaded:\n" 96 all_sensor_types = list(set([x[
'sensor_type']
for x
in all_sensors_dict.values()]))
98 for cur_sensor_type
in all_sensor_types:
99 print " %s sensors" % cur_sensor_type
100 cur_sensor_ids = [cur_sensor_id
for cur_sensor_id,cur_sensor
in all_sensors_dict.items()
if cur_sensor[
'sensor_type'] == cur_sensor_type]
101 cur_sensor_ids.sort()
102 for cur_sensor_id
in cur_sensor_ids:
103 print " - %s" % cur_sensor_id
106 return all_sensors_dict
110 step_keys = steps_dict.keys()
113 for step_name
in step_keys:
115 steps_dict[step_name][
"name"] = step_name
116 step_list.append(steps_dict[step_name])
117 print "Loaded the calibration steps to execute in the following order:" 118 for cur_step
in step_list:
119 print " - %s" % cur_step[
'name']
126 if not os.path.isfile(filename):
129 statinfo = os.stat(filename);
132 if (os.geteuid() == statinfo.st_uid):
133 return (os.stat(filename).st_mode & stat.S_IWUSR) > 0
136 if (os.getgid() == statinfo.st_gid):
137 return (os.stat(filename).st_mode & stat.S_IWGRP) > 0
140 return (os.stat(filename).st_mode & stat.S_IWOTH) > 0
145 Build a sensor dictionary with the subset of sensors that we request 147 all_sensor_types = list(set([x[
'sensor_type']
for x
in all_sensors_dict.values()]))
148 cur_sensors = dict([(x,[])
for x
in all_sensor_types])
149 for requested_sensor_id
in requested_sensors:
151 if requested_sensor_id
in all_sensors_dict.keys():
152 cur_sensor_type = all_sensors_dict[requested_sensor_id][
'sensor_type']
153 cur_sensors[cur_sensor_type].append(all_sensors_dict[requested_sensor_id])
155 rospy.logerr(
"Could not find [%s] in block library. Skipping this block", requested_sensor_id)
160 ''' Determine the difference in two vectors. ''' 161 if sum( [ math.fabs(x-y)
for x,y
in zip(v1, v2) ] ) <= eps:
167 for transmission
in urdf.transmissions:
168 if transmission.joint == joint:
169 transmission.mechanicalReduction = transmission.mechanicalReduction * gearing
171 print "No transmission found for:", joint
174 ''' Given urdf and calibrated robot_params, updates the URDF. ''' 178 for chain
in calibrated_params.chains.values():
179 joints += chain._active
180 axis += numpy.array(chain._axis)[0,:].tolist()
181 for joint, gearing
in zip(chain._active, chain._gearing):
184 for laser
in calibrated_params.tilting_lasers.values():
185 joints.append(laser._config[
'joint'])
187 if laser._gearing != 1.0:
190 unchanged_joints = [];
193 for joint_name
in calibrated_params.transforms.keys():
196 updated_link_params = calibrated_params.transforms[joint_name]._config.T.tolist()[0]
197 if diff(updated_link_params[0:3], urdf.joint_map[joint_name].origin.position):
198 print 'Updating xyz for', joint_name,
'\n old:', urdf.joint_map[joint_name].origin.position,
'\n new:', updated_link_params[0:3]
199 urdf.joint_map[joint_name].origin.position = updated_link_params[0:3]
202 if diff(r1, updated_link_params[3:6]):
204 if joint_name
in joints
and urdf.joint_map[joint_name].calibration !=
None:
205 cal = urdf.joint_map[joint_name].calibration
206 a = axis[joints.index(joint_name)]
208 print 'Updating calibration for', joint_name,
'by', updated_link_params[a]
209 if cal.rising !=
None:
210 urdf.joint_map[joint_name].calibration.rising += updated_link_params[a]
211 if cal.falling !=
None:
212 urdf.joint_map[joint_name].calibration.falling += updated_link_params[a]
216 print 'Updating rpy for', joint_name,
'\n old:', urdf.joint_map[joint_name].origin.rotation,
'\n new:', rot
217 urdf.joint_map[joint_name].origin.rotation = rot
220 print "Joint removed:", joint_name
221 print ' xyz:', updated_link_params[0:3]
225 unchanged_joints.append( joint_name );
227 print "The following joints weren't updated: \n",
', '.join(unchanged_joints)
230 if __name__ ==
'__main__':
232 xml_time = time.strftime(
'%Y_%m_%d_%H_%M', time.localtime())
233 calibrated_xml =
'robot_calibrated_'+xml_time+
'.xml' 234 uncalibrated_xml =
'robot_uncalibrated_'+xml_time+
'.xml' 236 rospy.init_node(
"multi_step_cov_estimator", anonymous=
True)
237 print "Starting The Multi Step [Covariance] Estimator Node\n" 239 if (len(rospy.myargv()) < 2):
241 elif (len(rospy.myargv()) < 3):
242 bag_filename = rospy.myargv()[1]
245 bag_filename = rospy.myargv()[1]
246 output_dir = rospy.myargv()[2]
248 print "Using Bagfile: %s\n" % bag_filename
249 if not os.path.isfile(bag_filename):
250 rospy.logerr(
"Bagfile does not exist. Exiting...")
253 config_param_name =
"calibration_config" 254 if not rospy.has_param(config_param_name):
255 rospy.logerr(
"Could not find parameter [%s]. Please populate this namespace with the estimation configuration.", config_param_name)
257 config = rospy.get_param(config_param_name)
260 sensors_name =
"sensors" 261 if sensors_name
not in config.keys():
262 rospy.logerr(
"Could not find namespace [%s/%s]. Please populate this namespace with sensors.", (config_param_name, sensors_name))
266 all_sensor_types = list(set([x[
'sensor_type']
for x
in all_sensors_dict.values()]))
272 sample_skip_list = rospy.get_param(
'calibration_skip_list', [])
275 if 'initial_poses' in config.keys():
276 if os.path.exists(config[
'initial_poses']):
277 with open(config[
'initial_poses'])
as f:
278 previous_pose_guesses = numpy.array(yaml.load(f))
280 rospy.logwarn(
"cannot find %s" % (config[
'initial_poses']))
281 previous_pose_guesses = numpy.zeros([msg_count,6])
283 previous_pose_guesses = numpy.zeros([msg_count,6])
287 if 'default_floating_initial_pose' in config.keys():
288 default_pose = config[
'default_floating_initial_pose']
289 if len(default_pose) != 6:
290 print "The 'default_floating_initial_pose' parameter has", len(default_pose),
"elements, but it should have 6!" 292 for p
in range(msg_count):
293 previous_pose_guesses[p,] = config[
'default_floating_initial_pose']
296 output_filenames = [calibrated_xml]
297 for suffix
in [
".yaml",
"_poses.yaml",
"_cov.txt"]:
298 output_filenames += [output_dir +
"/" + cur_step[
"output_filename"] + suffix
for cur_step
in step_list]
301 permissions_valid = all(valid_list)
302 if not permissions_valid:
303 print "Invalid file permissions. You need to be able to write to the following files:" 304 print "\n".join([
" - " + cur_file
for cur_file,cur_valid
in zip(output_filenames, valid_list)
if not cur_valid])
310 if robot_params ==
"":
311 print bag_filename,
" does not have robot_description, exitting.." 316 for cur_step
in step_list:
319 print "Beginning [%s]" % cur_step[
"name"]
328 print "Executing step with the following Sensors:" 330 for cur_sensor_type, cur_sensor_list
in cur_sensors.items():
331 print " %s Sensors:" % cur_sensor_type
332 cur_sensor_ids = [cur_sensor[
'sensor_id']
for cur_sensor
in cur_sensor_list]
333 cur_sensor_ids.sort()
334 for cur_sensor_id
in cur_sensor_ids:
335 counts = [ len([s
for s
in ms.sensors
if s.sensor_id == cur_sensor_id])
for ms
in multisensors]
337 print " - %s (%u)" % (cur_sensor_id, count)
340 print "Sensor breakdown (By Sample):" 341 for k,ms
in zip(range(len(multisensors)), multisensors):
342 print " % 2u) %s" % (k,
", ".join([s.sensor_id
for s
in ms.sensors]))
344 print "Pose Guesses:\n", previous_pose_guesses
346 if len(multisensors) == 0:
347 rospy.logwarn(
"No error blocks were generated for this optimization step. Skipping this step. This will result in a miscalibrated sensor")
348 output_dict = robot_params.params_to_config(robot_params.deflate())
349 output_poses = previous_pose_guesses
351 free_dict = yaml.load(cur_step[
"free_params"])
352 use_cov = cur_step[
'use_cov']
354 print "Executing step with covariance calculations" 356 print "Executing step without covariance calculations" 357 output_dict, output_poses, J =
opt_runner(robot_params, previous_pose_guesses, free_dict, multisensors, use_cov)
360 out_f = open(output_dir +
"/" + cur_step[
"output_filename"] +
".yaml",
'w')
361 yaml.dump(output_dict, out_f)
364 out_f = open(output_dir +
"/" + cur_step[
"output_filename"] +
"_poses.yaml",
'w')
365 yaml.dump([list([float(x)
for x
in pose])
for pose
in list(output_poses)], out_f)
368 cov_x = matrix(J).T * matrix(J)
369 numpy.savetxt(output_dir +
"/" + cur_step[
"output_filename"] +
"_cov.txt", cov_x, fmt=
"% 9.3f")
371 previous_pose_guesses = output_poses
374 rospy.loginfo(
'Writing original urdf to %s', uncalibrated_xml)
375 outfile = open(uncalibrated_xml,
'w')
376 outfile.write( robot_params.get_clean_urdf().to_xml_string() )
383 outfile = open(calibrated_xml,
'w')
384 rospy.loginfo(
'Writing updates to %s', calibrated_xml)
385 outfile.write( urdf.to_xml_string() )
388 outfile = open(
'latest_calibrated_xml',
'w')
389 outfile.write( calibrated_xml )
def build_sensor_defs(sensors)
def load_requested_sensors(all_sensors_dict, requested_sensors)
def load_calibration_steps(steps_dict)
def signal_handler(signal, frame)
def get_robot_measurement_count(bag_filename, sample_skip_list=[])
def update_transmission(urdf, joint, gearing)
def opt_runner(robot_params, pose_guess_arr, free_dict, multisensors, use_cov)
def update_urdf(urdf, calibrated_params)
def check_file_permissions(filename)
def get_robot_description(bag_filename, use_topic=False)
def get_multisensors(bag_filename, cur_sensors, sample_skip_list=[])
def diff(v1, v2, eps=1e-10)