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 pr2_calibration_propagation.update_joint as update_joint
00038 import pr2_calibration_propagation.process_changelist as process_changelist
00039 import tf.transformations as transformations
00040 import math
00041
00042 def update_urdf(initial_system, calibrated_system, xml_in):
00043
00044 dh_offsets = {"right_arm_chain":[],
00045 "left_arm_chain":[],
00046 "head_chain":[]}
00047
00048 dh_joint_names = {"right_arm_chain" : ['r_shoulder_pan_joint', 'r_shoulder_lift_joint', 'r_upper_arm_roll_joint', 'r_elbow_flex_joint', 'r_forearm_roll_joint', 'r_wrist_flex_joint', 'r_wrist_roll_joint'],
00049 "left_arm_chain" : ['l_shoulder_pan_joint', 'l_shoulder_lift_joint', 'l_upper_arm_roll_joint', 'l_elbow_flex_joint', 'l_forearm_roll_joint', 'l_wrist_flex_joint', 'l_wrist_roll_joint'],
00050 "head_chain" : ['head_pan_joint', 'head_tilt_joint'] }
00051
00052
00053 chains_to_remove = [x for x in dh_offsets.keys() if x not in initial_system['dh_chains'].keys()];
00054 print "Need to ignore the following chains:", chains_to_remove
00055 for chain_to_remove in chains_to_remove:
00056 del dh_offsets[chain_to_remove]
00057
00058 print "Computing All dh chain offsets"
00059 for chain_name in dh_offsets.keys():
00060 dh_offsets[chain_name] = find_dh_param_offsets(chain_name, initial_system, calibrated_system)
00061 print "%s offsets:" % chain_name, pplist(dh_offsets[chain_name])
00062
00063
00064 joint_offsets_list = []
00065 for chain_name in dh_offsets.keys():
00066 joint_offsets_list.extend(zip(dh_joint_names[chain_name], dh_offsets[chain_name]))
00067 joint_offsets = dict(joint_offsets_list)
00068
00069
00070 transformdict = dict()
00071 for(name, rotvect) in calibrated_system['transforms'].iteritems():
00072 floatvect = [mixed_to_float(x) for x in rotvect]
00073
00074 transformdict[name] = [floatvect[0:3], angle_axis_to_RPY(floatvect[3:6])]
00075
00076
00077 floatvect = [mixed_to_float(x) for x in calibrated_system['tilting_lasers']['tilt_laser']['before_joint'] ]
00078 transformdict['laser_tilt_mount_joint'] = [floatvect[0:3], angle_axis_to_RPY(floatvect[3:6])]
00079
00080
00081
00082
00083
00084
00085 floatvect = [mixed_to_float(x) for x in calibrated_system['tilting_lasers']['tilt_laser']['after_joint'] ]
00086 transformdict['laser_tilt_joint'] = [floatvect[0:3], angle_axis_to_RPY(floatvect[3:6])]
00087
00088
00089
00090 joints_dict = dict([(joint_name, [None, None, None]) for joint_name in transformdict.keys() + joint_offsets.keys()])
00091 for joint_name, val in transformdict.items():
00092 joints_dict[joint_name][0] = val[0]
00093 joints_dict[joint_name][1] = val[1]
00094
00095 for joint_name, offset in joint_offsets.items():
00096 joints_dict[joint_name][2] = offset
00097
00098 not_found = joints_dict.keys()
00099 changelist = []
00100
00101 for joint_name, val in joints_dict.items():
00102 cur_cl = update_joint.update_joint(xml_in, joint_name, xyz=val[0], rpy=val[1], ref_shift=val[2])
00103 if cur_cl is not None:
00104 not_found.remove(joint_name)
00105 changelist.extend(cur_cl)
00106
00107
00108 reduction_scale = 1.0 / calibrated_system['tilting_lasers']['tilt_laser']['gearing']
00109 cur_cl = update_joint.update_transmission(xml_in, 'laser_tilt_mount_trans', reduction_scale)
00110 changelist.extend(cur_cl)
00111
00112 print "jointnames never found: ", not_found
00113
00114 for span, result in changelist:
00115 print "\"%s\" -> \"%s\"" % (xml_in[span[0]:span[1]], result)
00116
00117 xml_out = process_changelist.process_changelist(changelist, xml_in)
00118
00119 return xml_out
00120
00121
00122 def pplist(list):
00123 zeroed = []
00124 for x in list:
00125 if x is None:
00126 zeroed.append(0.)
00127 else:
00128 zeroed.append(x)
00129 return ' '.join(['%2.3f'%x for x in zeroed])
00130
00131
00132
00133 def epsEq(value1, value2, eps = 1e-10):
00134 if math.fabs(value1-value2) <= eps:
00135 return 1
00136 return 0
00137
00138
00139
00140 def mixed_to_float(mixed):
00141 pi = math.pi
00142 if type(mixed) == str:
00143 try:
00144 val = eval(mixed)
00145 except:
00146 print >> sys.stderr, "bad value:", mixed, "substituting zero!!\n\n"
00147 val = 0.
00148 else:
00149 val = float(mixed)
00150 return val
00151
00152
00153
00154 def find_dh_param_offsets(chain_name, system_default, system_calibrated):
00155 offsets = []
00156 for (default_params, calib_params) in zip(system_default['dh_chains'][chain_name]['dh'], system_calibrated['dh_chains'][chain_name]['dh']):
00157
00158 diff = mixed_to_float(calib_params[0]) - mixed_to_float(default_params[0])
00159 if epsEq(diff, 0):
00160 diff = None
00161 offsets.append(diff)
00162
00163 return offsets
00164
00165
00166
00167
00168 def angle_axis_to_RPY(vec):
00169 angle = math.sqrt(sum([vec[i]**2 for i in range(3)]))
00170 hsa = math.sin(angle/2.)
00171 if epsEq(angle, 0):
00172 return (0.,0.,0.)
00173 quat = [vec[0]/angle*hsa, vec[1]/angle*hsa, vec[2]/angle*hsa, math.cos(angle/2.)]
00174 rpy = quat_to_rpy(quat)
00175 return rpy
00176
00177 def rpy_to_quat(rpy):
00178 return transformations.quaternion_from_euler(rpy[0], rpy[1], rpy[2], 'sxyz')
00179
00180 def quat_to_rpy(q):
00181 rpy = transformations.euler_from_quaternion(q, 'sxyz')
00182 return rpy
00183
00184 def parse_rpy(line):
00185 return [float(x) for x in line.split("rpy=\"")[1].split("\"")[0].split()]
00186
00187 def parse_xyz(line):
00188 return [float(x) for x in line.split("xyz=\"")[1].split("\"")[0].split()]