$search
00001 #! /usr/bin/env python 00002 00003 import roslib; roslib.load_manifest('pr2_calibration_propagation') 00004 import tf.transformations as transformations 00005 import rospy 00006 00007 import math 00008 import pdb 00009 import sys 00010 00011 try: 00012 import yaml 00013 except ImportError, e: 00014 print >> sys.stderr, "Cannot import yaml. Please make sure the pyyaml system dependency is installed" 00015 raise e 00016 00017 #pretty-print list to string 00018 def pplist(list): 00019 return ' '.join(['%2.3f'%x for x in list]) 00020 00021 00022 #return 1 if value1 and value2 are within eps of each other, 0 otherwise 00023 def epsEq(value1, value2, eps = 1e-10): 00024 if math.fabs(value1-value2) <= eps: 00025 return 1 00026 return 0 00027 00028 00029 #convert a float/int/string containing 'pi' to just float 00030 def mixed_to_float(mixed): 00031 pi = math.pi 00032 if type(mixed) == str: 00033 try: 00034 val = eval(mixed) 00035 except: 00036 print >> sys.stderr, "bad value:", mixed, "substituting zero!!\n\n" 00037 val = 0. 00038 else: 00039 val = float(mixed) 00040 return val 00041 00042 00043 #calculate calibration offsets (whicharm = 'left' or 'right') 00044 def find_dh_param_offsets(chain_name): 00045 offsets = [] 00046 for (default_params, calib_params) in zip(system_default['dh_chains'][chain_name]['dh'], system_calibrated['dh_chains'][chain_name]['dh']): 00047 #print "default_params[0]:", default_params[0], "calib_params[0]:", calib_params[0] 00048 diff = mixed_to_float(calib_params[0]) - mixed_to_float(default_params[0]) 00049 if epsEq(diff, 0): 00050 diff = 0. 00051 offsets.append(diff) 00052 00053 return offsets 00054 00055 00056 00057 #convert from rotation-axis-with-angle-as-magnitude representation to Euler RPY 00058 def angle_axis_to_RPY(vec): 00059 angle = math.sqrt(sum([vec[i]**2 for i in range(3)])) 00060 hsa = math.sin(angle/2.) 00061 if epsEq(angle, 0): 00062 return (0.,0.,0.) 00063 quat = [vec[0]/angle*hsa, vec[1]/angle*hsa, vec[2]/angle*hsa, math.cos(angle/2.)] 00064 rpy = quat_to_rpy(quat) 00065 return rpy 00066 00067 def rpy_to_quat(rpy): 00068 return transformations.quaternion_from_euler(rpy[0], rpy[1], rpy[2], 'sxyz') 00069 00070 def quat_to_rpy(q): 00071 rpy = transformations.euler_from_quaternion(q, 'sxyz') 00072 return rpy 00073 00074 def parse_rpy(line): 00075 return [float(x) for x in line.split("rpy=\"")[1].split("\"")[0].split()] 00076 00077 def parse_xyz(line): 00078 return [float(x) for x in line.split("xyz=\"")[1].split("\"")[0].split()] 00079 00080 if __name__ == '__main__': 00081 00082 rospy.init_node("propagate_config") 00083 00084 if len(rospy.myargv()) < 5: 00085 print "Usage: ./propagate_config [initial.yaml] [calibrated.yaml] [initial.xml] [cal_output.xml]" 00086 sys.exit(0) 00087 00088 #filenames 00089 initial_yaml_filename = rospy.myargv()[1] 00090 calibrated_yaml_filename = rospy.myargv()[2] 00091 robot_xml_filename = rospy.myargv()[3] 00092 output_filename = rospy.myargv()[4] 00093 00094 #read in files 00095 system_default = yaml.load(file(initial_yaml_filename, 'r')) 00096 system_calibrated = yaml.load(file(calibrated_yaml_filename, 'r')) 00097 00098 00099 #find dh_param offsets for all requested dh chains 00100 dh_offsets = {"right_arm_chain":[], 00101 "left_arm_chain":[], 00102 "head_chain":[]} 00103 00104 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'], 00105 "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'], 00106 "head_chain" : ['head_pan_joint', 'head_tilt_joint'] } 00107 00108 # Check that the chains are in fact in the yaml system config 00109 chains_to_remove = [x for x in dh_offsets.keys() if x not in system_default['dh_chains'].keys()]; 00110 print "Need to ignore the following chains:", chains_to_remove 00111 for chain_to_remove in chains_to_remove: 00112 del dh_offsets[chain_to_remove] 00113 00114 print "Computing All dh chain offsets" 00115 for chain_name in dh_offsets.keys(): 00116 dh_offsets[chain_name] = find_dh_param_offsets(chain_name) 00117 print "%s offsets:" % chain_name, pplist(dh_offsets[chain_name]) 00118 00119 # Need to be able to lookup the joint offset for each joint 00120 joint_offsets_list = [] 00121 for chain_name in dh_offsets.keys(): 00122 joint_offsets_list.extend(zip(dh_joint_names[chain_name], dh_offsets[chain_name])) 00123 joint_offsets = dict(joint_offsets_list) 00124 foundjointnames = [] 00125 00126 #convert transforms to rpy 00127 transformdict = dict() 00128 for(name, rotvect) in system_calibrated['transforms'].iteritems(): 00129 floatvect = [mixed_to_float(x) for x in rotvect] 00130 #print name, pplist(floatvect), angle_axis_to_RPY(floatvect[3:6]) 00131 transformdict[name] = tuple(list(angle_axis_to_RPY(floatvect[3:6])) + floatvect[0:3]) 00132 00133 # Hack in transforms for tilting laser 00134 floatvect = [mixed_to_float(x) for x in system_calibrated['tilting_lasers']['tilt_laser']['before_joint'] ] 00135 transformdict['laser_tilt_mount_joint'] = tuple(list(angle_axis_to_RPY(floatvect[3:6])) + floatvect[0:3]) 00136 00137 #print "Floatvec: ", floatvec 00138 #print "tuple: ", transformdict['laser_tilt_mount_joint'] 00139 #import code; code.interact(local=locals()) 00140 #assert(False) 00141 00142 floatvect = [mixed_to_float(x) for x in system_calibrated['tilting_lasers']['tilt_laser']['after_joint'] ] 00143 transformdict['laser_tilt_joint'] = tuple(list(angle_axis_to_RPY(floatvect[3:6])) + floatvect[0:3]) 00144 00145 foundtransforms = [] 00146 00147 #go through xml, converting values as they come up 00148 xmllines = file(robot_xml_filename, 'r').readlines() 00149 outfile = file(output_filename, 'w') 00150 lineind = 0 00151 while(lineind < len(xmllines)): 00152 looking_for_calibration_pos = 0 00153 looking_for_origin = 0 00154 #check for dh_param_search_strings 00155 for joint_name in joint_offsets.keys(): 00156 search_string = joint_name + "\" type=" 00157 if search_string in xmllines[lineind]: 00158 #found one: start looking for the calibration reference position 00159 print "Found joint: ", joint_name 00160 foundjointnames.append(joint_name) 00161 looking_for_calibration_pos = 1 00162 break 00163 00164 #check for transform joint name 00165 for (transform_name, rpy_trans) in transformdict.iteritems(): 00166 if transform_name+"\" type=" in xmllines[lineind]: 00167 00168 #found one: start looking for the origin 00169 print "found transform for", transform_name 00170 foundtransforms.append(transform_name) 00171 looking_for_origin = 1 00172 break 00173 00174 if looking_for_calibration_pos or looking_for_origin: 00175 # Extract the entire joint tag 00176 searchind = 0 00177 joint_lines = [] 00178 while(searchind < 50): 00179 joint_lines.append(xmllines[searchind+lineind]) 00180 if "</joint>" in xmllines[searchind+lineind]: 00181 lineind += searchind 00182 break 00183 searchind += 1 00184 else: 00185 print >> sys.stderr, "looked for 50 lines and didn't find what we were looking for. Is the joint description more than 50 lines? Go change this script, if so.\n\n\n" 00186 00187 print "Extracted joint:" 00188 print "------" 00189 for joint_line_ind, cur_line in zip(range(len(joint_lines)), joint_lines): 00190 print "% 2u)" % joint_line_ind, cur_line 00191 print "------" 00192 00193 # Now that we have all the lines for the joint, figure out which parts of useful 00194 axis_xyz = None 00195 origin_rpy = None 00196 origin_xyz = None 00197 origin_ind = None 00198 for joint_line_ind in range(len(joint_lines)): 00199 if "<axis " in joint_lines[joint_line_ind]: 00200 print " Found axis tag at line %u" % joint_line_ind 00201 axis_xyz = parse_xyz(joint_lines[joint_line_ind]) 00202 print " xyz: %s" % axis_xyz 00203 if "<origin " in joint_lines[joint_line_ind]: 00204 print " Found origin tag at line %u" % joint_line_ind 00205 origin_ind = joint_line_ind 00206 00207 # Get floats for important fields 00208 origin_xyz = parse_xyz(joint_lines[joint_line_ind]) 00209 origin_rpy = parse_rpy(joint_lines[joint_line_ind]) 00210 print " xyz: %s" % origin_xyz 00211 print " rpy: %s" % origin_rpy 00212 00213 # Do the update for this joint 00214 if looking_for_origin and not looking_for_calibration_pos: 00215 print " Need to only do a transform update" 00216 tag_split = joint_lines[origin_ind].split('/>') 00217 if len(tag_split) == 1: 00218 oldlineending = "" 00219 else: 00220 oldlineending = tag_split[1] 00221 newline = "\t<origin rpy=\"%.10f %.10f %.10f\" xyz=\"%.10f %.10f %.10f\"/>"%rpy_trans + oldlineending 00222 print " transform old line:", joint_lines[origin_ind].strip() 00223 print " transform new line:", newline.strip() 00224 joint_lines[origin_ind] = newline 00225 elif (not looking_for_origin) and looking_for_calibration_pos: 00226 print " Need to only do a calibration position update" 00227 00228 # Do the math 00229 print " Applying a joint offset of %f" % joint_offsets[joint_name] 00230 origin_q = rpy_to_quat(origin_rpy) 00231 offset_q = transformations.quaternion_about_axis(joint_offsets[joint_name], axis_xyz) 00232 total_q = transformations.quaternion_multiply(origin_q, offset_q) 00233 next_origin_rpy = quat_to_rpy(total_q) 00234 00235 # Do the text stuff 00236 tag_split = joint_lines[origin_ind].split('/>') 00237 if len(tag_split) == 1: 00238 oldlineending = "" 00239 else: 00240 oldlineending = tag_split[1] 00241 00242 newline = "\t<origin rpy=\"%.10f %.10f %.10f\" xyz=\"%.10f %.10f %.10f\"/>"% (next_origin_rpy + tuple(origin_xyz)) + oldlineending 00243 print " transform old line:", joint_lines[origin_ind].strip() 00244 print " transform new line:", newline.strip() 00245 joint_lines[origin_ind] = newline 00246 else: 00247 print " Need to update both" 00248 00249 # Do the math 00250 print " Applying a joint offset of %f" % joint_offsets[joint_name] 00251 origin_q = rpy_to_quat(rpy_trans[0:3]) 00252 offset_q = transformations.quaternion_about_axis(joint_offsets[joint_name], axis_xyz) 00253 total_q = transformations.quaternion_multiply(origin_q, offset_q) 00254 next_origin_rpy = quat_to_rpy(total_q) 00255 00256 # Do the text stuff 00257 tag_split = joint_lines[origin_ind].split('/>') 00258 if len(tag_split) == 1: 00259 oldlineending = "" 00260 else: 00261 oldlineending = tag_split[1] 00262 00263 print " Old Line Ending: %s" % oldlineending 00264 newline = ("\t<origin rpy=\"%.10f %.10f %.10f\" xyz=\"%.10f %.10f %.10f\"/>"% (next_origin_rpy + tuple(origin_xyz)) ) + oldlineending 00265 print " transform old line:", joint_lines[origin_ind].strip() 00266 print " transform new line:", newline.strip() 00267 joint_lines[origin_ind] = newline 00268 00269 for cur_line in joint_lines: 00270 outfile.write(cur_line) 00271 00272 else: 00273 #just pass the line on unchanged 00274 outfile.write(xmllines[lineind]) 00275 lineind += 1 00276 00277 outfile.close() 00278 00279 #check to see that we found everything we wanted 00280 notfoundtransforms = transformdict.keys() 00281 for transform in foundtransforms: 00282 try: 00283 notfoundtransforms.remove(transform) 00284 except: 00285 print >> sys.stderr, "transform", transform, "found and changed twice, oops!!!\n\n" 00286 print "transforms never found:", notfoundtransforms 00287 00288 notfoundjointnames = joint_offsets.keys() 00289 for jointname in foundjointnames: 00290 try: 00291 notfoundjointnames.remove(jointname) 00292 except: 00293 print >> sys.stderr, "jointname", jointname, "found and changed twice, oops!!!\n\n" 00294 print "jointnames never found:", notfoundjointnames