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
46 dh_offsets = {
"right_arm_chain":[],
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'] }
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]
60 print(
"Computing All dh chain offsets")
61 for chain_name
in list(dh_offsets.keys()):
63 print(
"%s offsets:" % chain_name,
pplist(dh_offsets[chain_name]))
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)
72 transformdict = dict()
73 for(name, rotvect)
in calibrated_system[
'transforms'].items():
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]
99 for joint_name, offset
in list(joint_offsets.items()):
100 joints_dict[joint_name][2] = offset
102 not_found = list(joints_dict.keys())
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)
118 print(
"jointnames never found: ", not_found)
120 for span, result
in changelist:
121 print(
"\"%s\" -> \"%s\"" % (xml_in[span[0]:span[1]], result))
123 xml_out = process_changelist.process_changelist(changelist, xml_in)
135 return ' '.join([
'%2.3f'%x
for x
in zeroed])
139 def epsEq(value1, value2, eps = 1e-10):
140 if math.fabs(value1-value2) <= eps:
148 if type(mixed) == str:
152 print(
"bad value:", mixed,
"substituting zero!!\n\n", file=sys.stderr)
162 for (default_params, calib_params)
in zip(system_default[
'dh_chains'][chain_name][
'dh'], system_calibrated[
'dh_chains'][chain_name][
'dh']):
175 angle = math.sqrt(sum([vec[i]**2
for i
in range(3)]))
176 hsa = math.sin(angle/2.)
179 quat = [vec[0]/angle*hsa, vec[1]/angle*hsa, vec[2]/angle*hsa, math.cos(angle/2.)]
184 return transformations.quaternion_from_euler(rpy[0], rpy[1], rpy[2],
'sxyz')
187 rpy = transformations.euler_from_quaternion(q,
'sxyz')
191 return [float(x)
for x
in line.split(
"rpy=\"")[1].split(
"\"")[0].split()]
194 return [float(x)
for x
in line.split(
"xyz=\"")[1].split(
"\"")[0].split()]
def update_urdf(initial_system, calibrated_system, xml_in)
def mixed_to_float(mixed)
def epsEq(value1, value2, eps=1e-10)
def find_dh_param_offsets(chain_name, system_default, system_calibrated)
def angle_axis_to_RPY(vec)