update_pr2_se_urdf.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2008, Willow Garage, Inc.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of Willow Garage, Inc. nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 
35 # author: Vijay Pradeep
36 
37 # TODO This file has not actually been checked for any PR2 SE compatability.
38 
39 import pr2_calibration_propagation.update_joint as update_joint
40 import pr2_calibration_propagation.process_changelist as process_changelist
41 import tf.transformations as transformations
42 import math
43 
44 def update_urdf(initial_system, calibrated_system, xml_in):
45  #find dh_param offsets for all requested dh chains
46  dh_offsets = {"right_arm_chain":[],
47  "left_arm_chain":[],
48  "head_chain":[]}
49 
50  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'],
51  "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'],
52  "head_chain" : ['head_pan_joint', 'head_tilt_joint'] }
53 
54  # Check that the chains are in fact in the yaml system config
55  chains_to_remove = [x for x in list(dh_offsets.keys()) if x not in list(initial_system['dh_chains'].keys())];
56  print("Need to ignore the following chains:", chains_to_remove)
57  for chain_to_remove in chains_to_remove:
58  del dh_offsets[chain_to_remove]
59 
60  print("Computing All dh chain offsets")
61  for chain_name in list(dh_offsets.keys()):
62  dh_offsets[chain_name] = find_dh_param_offsets(chain_name, initial_system, calibrated_system)
63  print("%s offsets:" % chain_name, pplist(dh_offsets[chain_name]))
64 
65  # Need to be able to lookup the joint offset for each joint
66  joint_offsets_list = []
67  for chain_name in list(dh_offsets.keys()):
68  joint_offsets_list.extend(list(zip(dh_joint_names[chain_name], dh_offsets[chain_name])))
69  joint_offsets = dict(joint_offsets_list)
70 
71  #convert transforms to rpy
72  transformdict = dict()
73  for(name, rotvect) in calibrated_system['transforms'].items():
74  floatvect = [mixed_to_float(x) for x in rotvect]
75  #print name, pplist(floatvect), angle_axis_to_RPY(floatvect[3:6])
76  transformdict[name] = [floatvect[0:3], angle_axis_to_RPY(floatvect[3:6])]
77 
78  # Hack in transforms for tilting laser
79 
80  # PR2 Lite doesn't have a tilt laser
81  #floatvect = [mixed_to_float(x) for x in calibrated_system['tilting_lasers']['tilt_laser']['before_joint'] ]
82  #transformdict['laser_tilt_mount_joint'] = [floatvect[0:3], angle_axis_to_RPY(floatvect[3:6])]
83 
84  #print "Floatvec: ", floatvec
85  #print "tuple: ", transformdict['laser_tilt_mount_joint']
86  #import code; code.interact(local=locals())
87  #assert(False)
88 
89  #floatvect = [mixed_to_float(x) for x in calibrated_system['tilting_lasers']['tilt_laser']['after_joint'] ]
90  #transformdict['laser_tilt_joint'] = [floatvect[0:3], angle_axis_to_RPY(floatvect[3:6])]
91 
92 
93  # Combine the transforms and joint offsets into a single dict
94  joints_dict = dict([(joint_name, [None, None, None]) for joint_name in list(transformdict.keys()) + list(joint_offsets.keys())])
95  for joint_name, val in list(transformdict.items()):
96  joints_dict[joint_name][0] = val[0]
97  joints_dict[joint_name][1] = val[1]
98 
99  for joint_name, offset in list(joint_offsets.items()):
100  joints_dict[joint_name][2] = offset
101 
102  not_found = list(joints_dict.keys())
103  changelist = []
104 
105  for joint_name, val in list(joints_dict.items()):
106  cur_cl = update_joint.update_joint(xml_in, joint_name, xyz=val[0], rpy=val[1], ref_shift=val[2])
107  if cur_cl is not None:
108  not_found.remove(joint_name)
109  changelist.extend(cur_cl)
110 
111  # Hack to change laser gearing. Assumes that the laser reference position is 0
112 
113  # PR2 Lite Doesn't have a tilt laser
114  #reduction_scale = 1.0 / calibrated_system['tilting_lasers']['tilt_laser']['gearing']
115  #cur_cl = update_joint.update_transmission(xml_in, 'laser_tilt_mount_trans', reduction_scale)
116  #changelist.extend(cur_cl)
117 
118  print("jointnames never found: ", not_found)
119 
120  for span, result in changelist:
121  print("\"%s\" -> \"%s\"" % (xml_in[span[0]:span[1]], result))
122 
123  xml_out = process_changelist.process_changelist(changelist, xml_in)
124 
125  return xml_out
126 
127 #pretty-print list to string
128 def pplist(list):
129  zeroed = []
130  for x in list:
131  if x is None:
132  zeroed.append(0.)
133  else:
134  zeroed.append(x)
135  return ' '.join(['%2.3f'%x for x in zeroed])
136 
137 
138 #return 1 if value1 and value2 are within eps of each other, 0 otherwise
139 def epsEq(value1, value2, eps = 1e-10):
140  if math.fabs(value1-value2) <= eps:
141  return 1
142  return 0
143 
144 
145 #convert a float/int/string containing 'pi' to just float
146 def mixed_to_float(mixed):
147  pi = math.pi
148  if type(mixed) == str:
149  try:
150  val = eval(mixed)
151  except:
152  print("bad value:", mixed, "substituting zero!!\n\n", file=sys.stderr)
153  val = 0.
154  else:
155  val = float(mixed)
156  return val
157 
158 
159 #calculate calibration offsets (whicharm = 'left' or 'right')
160 def find_dh_param_offsets(chain_name, system_default, system_calibrated):
161  offsets = []
162  for (default_params, calib_params) in zip(system_default['dh_chains'][chain_name]['dh'], system_calibrated['dh_chains'][chain_name]['dh']):
163  #print "default_params[0]:", default_params[0], "calib_params[0]:", calib_params[0]
164  diff = mixed_to_float(calib_params[0]) - mixed_to_float(default_params[0])
165  if epsEq(diff, 0):
166  diff = None
167  offsets.append(diff)
168 
169  return offsets
170 
171 
172 
173 #convert from rotation-axis-with-angle-as-magnitude representation to Euler RPY
175  angle = math.sqrt(sum([vec[i]**2 for i in range(3)]))
176  hsa = math.sin(angle/2.)
177  if epsEq(angle, 0):
178  return (0.,0.,0.)
179  quat = [vec[0]/angle*hsa, vec[1]/angle*hsa, vec[2]/angle*hsa, math.cos(angle/2.)]
180  rpy = quat_to_rpy(quat)
181  return rpy
182 
183 def rpy_to_quat(rpy):
184  return transformations.quaternion_from_euler(rpy[0], rpy[1], rpy[2], 'sxyz')
185 
186 def quat_to_rpy(q):
187  rpy = transformations.euler_from_quaternion(q, 'sxyz')
188  return rpy
189 
190 def parse_rpy(line):
191  return [float(x) for x in line.split("rpy=\"")[1].split("\"")[0].split()]
192 
193 def parse_xyz(line):
194  return [float(x) for x in line.split("xyz=\"")[1].split("\"")[0].split()]
def update_urdf(initial_system, calibrated_system, xml_in)
def epsEq(value1, value2, eps=1e-10)
def find_dh_param_offsets(chain_name, system_default, system_calibrated)


pr2_se_calibration_launch
Author(s): Adam Leeper, Vijay Pradeep
autogenerated on Tue Jun 1 2021 02:51:02