-
Notifications
You must be signed in to change notification settings - Fork 9
/
Copy pathpr2_joint_cart_control.yaml
253 lines (240 loc) · 12.2 KB
/
pr2_joint_cart_control.yaml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
#
# Copyright (C) 2015-2016 Georg Bartels <[email protected]>
#
# This file is part of giskard.
#
# giskard is free software; you can redistribute it and/or
# modify it under the terms of the GNU General Public License
# as published by the Free Software Foundation; either version 2
# of the License, or (at your option) any later version.
#
# This program is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU General Public License for more details.
#
# You should have received a copy of the GNU General Public License
# along with this program; if not, write to the Free Software
# Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
#
scope:
# definition of some nice short-cuts
- unit_x: {vector3: [1, 0, 0]}
- unit_y: {vector3: [0, 1, 0]}
- unit_z: {vector3: [0, 0, 1]}
- pi: 3.14159265359
- two_pi: {double-mul: [pi, 2.0]}
# definition of joint input variables
- torso_lift_joint: {input-var: 0}
- l_shoulder_pan_joint: {input-var: 1}
- l_shoulder_lift_joint: {input-var: 2}
- l_upper_arm_roll_joint: {input-var: 3}
- l_elbow_flex_joint: {input-var: 4}
- l_forearm_roll_joint: {input-var: 5}
- l_wrist_flex_joint: {input-var: 6}
- l_wrist_roll_joint: {input-var: 7}
- r_shoulder_pan_joint: {input-var: 8}
- r_shoulder_lift_joint: {input-var: 9}
- r_upper_arm_roll_joint: {input-var: 10}
- r_elbow_flex_joint: {input-var: 11}
- r_forearm_roll_joint: {input-var: 12}
- r_wrist_flex_joint: {input-var: 13}
- r_wrist_roll_joint: {input-var: 14}
# definition goal input variables
- l_shoulder_pan_joint_goal: {input-var: 15}
- l_shoulder_lift_joint_goal: {input-var: 16}
- l_upper_arm_roll_joint_goal: {input-var: 17}
- l_elbow_flex_joint_goal: {input-var: 18}
- l_forearm_roll_joint_goal: {input-var: 19}
- l_wrist_flex_joint_goal: {input-var: 20}
- l_wrist_roll_joint_goal: {input-var: 21}
- r_goal_x: {input-var: 22}
- r_goal_y: {input-var: 23}
- r_goal_z: {input-var: 24}
- r_goal_rot_z: {input-var: 25}
- r_goal_rot_y: {input-var: 26}
- r_goal_rot_x: {input-var: 27}
# definition of joint transforms
- torso_lift:
frame: [{axis-angle: [unit_x, 0]}, {vector3: [-0.05, 0, {double-add: [0.739675, torso_lift_joint]}]}]
- r_shoulder_pan:
frame: [{axis-angle: [unit_z, r_shoulder_pan_joint]}, {vector3: [0, -0.188, 0]}]
- r_shoulder_lift:
frame: [{axis-angle: [unit_y, r_shoulder_lift_joint]}, {vector3: [0.1, 0, 0]}]
- r_upper_arm_roll:
frame: [{axis-angle: [unit_x, r_upper_arm_roll_joint]}, {vector3: [0, 0, 0]}]
- r_elbow_flex:
frame: [{axis-angle: [unit_y, r_elbow_flex_joint]}, {vector3: [0.4, 0, 0]}]
- r_forearm_roll:
frame: [{axis-angle: [unit_x, r_forearm_roll_joint]}, {vector3: [0, 0, 0]}]
- r_wrist_flex:
frame: [{axis-angle: [unit_y, r_wrist_flex_joint]}, {vector3: [0.321, 0, 0]}]
- r_wrist_roll:
frame: [{axis-angle: [unit_x, r_wrist_roll_joint]}, {vector3: [0, 0, 0]}]
- r_gripper_offset:
frame: [{axis-angle: [unit_x, 0]}, {vector3: [0.18, 0, 0]}]
# definition of elbow FK
- right_elbow:
frame-mul:
- torso_lift
- r_shoulder_pan
- r_shoulder_lift
- r_upper_arm_roll
- r_elbow_flex
# defintion of EE FK
- right_ee:
frame-mul:
- right_elbow
- r_forearm_roll
- r_wrist_flex
- r_wrist_roll
- r_gripper_offset
# control params
- pos_p_gain: 3.0
- rot_p_gain: 3.0
- pos_thresh: 0.05
- rot_thresh: 0.1
- weight_arm_joints: 0.001
- weight_torso_joint: 0.01
- weight_pos_control: 1
- weight_rot_control: 1
- weight_elbow_control: 0
- neg_vel_limit_arm_joints: -0.6
- pos_vel_limit_arm_joints: 0.6
- neg_vel_limit_torso_joint: -0.02
- pos_vel_limit_torso_joint: 0.02
# definition EE goals and control laws
# right arm position
- r_goal_trans: {vector3: [r_goal_x, r_goal_y, r_goal_z]}
- r_trans: {origin-of: right_ee}
- r_trans_error_vector: {vector-sub: [r_goal_trans, r_trans]}
- r_trans_error: {vector-norm: r_trans_error_vector}
- r_trans_scale: {double-if: [{double-sub: [pos_thresh, r_trans_error]}, 1.0, {double-div: [pos_thresh, r_trans_error]}]}
- r_trans_scaled_error: {double-mul: [r_trans_scale, r_trans_error]}
- r_trans_control: {scale-vector: [{double-mul: [pos_p_gain, r_trans_scale]}, r_trans_error_vector]}
# right arm rotation
- r_goal_rot:
rotation-mul:
- {axis-angle: [unit_z, r_goal_rot_z]}
- {axis-angle: [unit_y, r_goal_rot_y]}
- {axis-angle: [unit_x, r_goal_rot_x]}
- r_rot: {orientation-of: right_ee}
- r_rot_error: {vector-norm: {rot-vector: {rotation-mul: [{inverse-rotation: r_rot}, r_goal_rot]}}}
- r_rot_scaling:
double-if:
- {double-sub: [rot_thresh, r_rot_error]}
- 1
- {double-div: [rot_thresh, r_rot_error]}
- r_intermediate_goal_rot:
slerp:
- r_rot
- r_goal_rot
- r_rot_scaling
- r_rot_control:
scale-vector: [rot_p_gain, {rotate-vector: [r_rot, {rot-vector: {rotation-mul: [{inverse-rotation: r_rot}, r_intermediate_goal_rot]}}]}]
# definition of joint goals and control laws
- l_shoulder_pan_error: {double-sub: [l_shoulder_pan_joint_goal, l_shoulder_pan_joint]}
- l_shoulder_lift_error: {double-sub: [l_shoulder_lift_joint_goal, l_shoulder_lift_joint]}
- l_upper_arm_roll_error: {double-sub: [l_upper_arm_roll_joint_goal, l_upper_arm_roll_joint]}
- l_elbow_flex_error: {double-sub: [l_elbow_flex_joint_goal, l_elbow_flex_joint]}
- l_forearm_roll_error_unnormalized: {double-sub: [l_forearm_roll_joint_goal, l_forearm_roll_joint]}
- l_forearm_roll_error_normalized:
fmod:
- {double-add: [{fmod: [l_forearm_roll_error_unnormalized, two_pi]}, two_pi]}
- two_pi
- l_forearm_roll_error:
double-if:
- {double-sub: [l_forearm_roll_error_normalized, pi]}
- {double-sub: [l_forearm_roll_error_normalized, two_pi]}
- l_forearm_roll_error_normalized
- l_wrist_flex_error: {double-sub: [l_wrist_flex_joint_goal, l_wrist_flex_joint]}
- l_wrist_roll_error_unnormalized: {double-sub: [l_wrist_roll_joint_goal, l_wrist_roll_joint]}
- l_wrist_roll_error_normalized:
fmod:
- {double-add: [{fmod: [l_wrist_roll_error_unnormalized, two_pi]}, two_pi]}
- two_pi
- l_wrist_roll_error:
double-if:
- {double-sub: [l_wrist_roll_error_normalized, pi]}
- {double-sub: [l_wrist_roll_error_normalized, two_pi]}
- l_wrist_roll_error_normalized
controllable-constraints:
# torso joint
- controllable-constraint: [neg_vel_limit_torso_joint, pos_vel_limit_torso_joint, weight_torso_joint, 0, torso_lift_joint]
# left arm joints
- controllable-constraint: [neg_vel_limit_arm_joints, pos_vel_limit_arm_joints, weight_arm_joints, 1, l_shoulder_pan_joint]
- controllable-constraint: [neg_vel_limit_arm_joints, pos_vel_limit_arm_joints, weight_arm_joints, 2, l_shoulder_lift_joint]
- controllable-constraint: [neg_vel_limit_arm_joints, pos_vel_limit_arm_joints, weight_arm_joints, 3, l_upper_arm_roll_joint]
- controllable-constraint: [neg_vel_limit_arm_joints, pos_vel_limit_arm_joints, weight_arm_joints, 4, l_elbow_flex_joint]
- controllable-constraint: [neg_vel_limit_arm_joints, pos_vel_limit_arm_joints, weight_arm_joints, 5, l_forearm_roll_joint]
- controllable-constraint: [neg_vel_limit_arm_joints, pos_vel_limit_arm_joints, weight_arm_joints, 6, l_wrist_flex_joint]
- controllable-constraint: [neg_vel_limit_arm_joints, pos_vel_limit_arm_joints, weight_arm_joints, 7, l_wrist_roll_joint]
# right arm joints
- controllable-constraint: [neg_vel_limit_arm_joints, pos_vel_limit_arm_joints, weight_arm_joints, 8, r_shoulder_pan_joint]
- controllable-constraint: [neg_vel_limit_arm_joints, pos_vel_limit_arm_joints, weight_arm_joints, 9, r_shoulder_lift_joint]
- controllable-constraint: [neg_vel_limit_arm_joints, pos_vel_limit_arm_joints, weight_arm_joints, 10, r_upper_arm_roll_joint]
- controllable-constraint: [neg_vel_limit_arm_joints, pos_vel_limit_arm_joints, weight_arm_joints, 11, r_elbow_flex_joint]
- controllable-constraint: [neg_vel_limit_arm_joints, pos_vel_limit_arm_joints, weight_arm_joints, 12, r_forearm_roll_joint]
- controllable-constraint: [neg_vel_limit_arm_joints, pos_vel_limit_arm_joints, weight_arm_joints, 13, r_wrist_flex_joint]
- controllable-constraint: [neg_vel_limit_arm_joints, pos_vel_limit_arm_joints, weight_arm_joints, 14, r_wrist_roll_joint]
soft-constraints:
- soft-constraint: [{x-coord: r_trans_control}, {x-coord: r_trans_control}, weight_pos_control, {x-coord: r_trans}, right EE x-pos control slack]
- soft-constraint: [{y-coord: r_trans_control}, {y-coord: r_trans_control}, weight_pos_control, {y-coord: r_trans}, right EE y-pos control slack]
- soft-constraint: [{z-coord: r_trans_control}, {z-coord: r_trans_control}, weight_pos_control, {z-coord: r_trans}, right EE z-pos control slack]
- soft-constraint: [{x-coord: r_rot_control}, {x-coord: r_rot_control}, weight_rot_control, {x-coord: {rot-vector: r_rot}}, right EE x-rot control slack]
- soft-constraint: [{y-coord: r_rot_control}, {y-coord: r_rot_control}, weight_rot_control, {y-coord: {rot-vector: r_rot}}, right EE y-rot control slack]
- soft-constraint: [{z-coord: r_rot_control}, {z-coord: r_rot_control}, weight_rot_control, {z-coord: {rot-vector: r_rot}}, right EE z-rot control slack]
- soft-constraint: [-0.01, -0.01, weight_elbow_control, {y-coord: {origin-of: right_elbow}}, right elbow out control slack]
- soft-constraint: [0.01, 0.01, weight_elbow_control, {z-coord: {origin-of: right_elbow}}, right elbow up control slack]
- soft-constraint: [l_shoulder_pan_error, l_shoulder_pan_error , weight_pos_control, l_shoulder_pan_joint, l_shoulder_pan_joint control slack]
- soft-constraint: [l_shoulder_lift_error, l_shoulder_lift_error , weight_pos_control, l_shoulder_lift_joint, l_shoulder_lift_joint control slack]
- soft-constraint: [l_upper_arm_roll_error, l_upper_arm_roll_error , weight_pos_control, l_upper_arm_roll_joint, l_upper_arm_roll_joint control slack]
- soft-constraint: [l_elbow_flex_error, l_elbow_flex_error , weight_pos_control, l_elbow_flex_joint, l_elbow_flex_joint control slack]
- soft-constraint: [l_forearm_roll_error, l_forearm_roll_error , weight_pos_control, l_forearm_roll_joint, l_forearm_roll_joint control slack]
- soft-constraint: [l_wrist_flex_error, l_wrist_flex_error , weight_pos_control, l_wrist_flex_joint, l_wrist_flex_joint control slack]
- soft-constraint: [l_wrist_roll_error, l_wrist_roll_error , weight_pos_control, l_wrist_roll_joint, l_wrist_roll_joint control slack]
hard-constraints:
- hard-constraint:
- {double-sub: [0.0115, torso_lift_joint]}
- {double-sub: [0.325, torso_lift_joint]}
- torso_lift_joint
- hard-constraint:
- {double-sub: [-0.5646, l_shoulder_pan_joint]}
- {double-sub: [2.1353, l_shoulder_pan_joint]}
- l_shoulder_pan_joint
- hard-constraint:
- {double-sub: [-0.3536, l_shoulder_lift_joint]}
- {double-sub: [1.2963, l_shoulder_lift_joint]}
- l_shoulder_lift_joint
- hard-constraint:
- {double-sub: [-0.65, l_upper_arm_roll_joint]}
- {double-sub: [3.75, l_upper_arm_roll_joint]}
- l_upper_arm_roll_joint
- hard-constraint:
- {double-sub: [-2.1213, l_elbow_flex_joint]}
- {double-sub: [-0.15, l_elbow_flex_joint]}
- l_elbow_flex_joint
- hard-constraint:
- {double-sub: [-2.0, l_wrist_flex_joint]}
- {double-sub: [-0.1, l_wrist_flex_joint]}
- l_wrist_flex_joint
- hard-constraint:
- {double-sub: [-2.1353, r_shoulder_pan_joint]}
- {double-sub: [0.5646, r_shoulder_pan_joint]}
- r_shoulder_pan_joint
- hard-constraint:
- {double-sub: [-0.3536, r_shoulder_lift_joint]}
- {double-sub: [1.2963, r_shoulder_lift_joint]}
- r_shoulder_lift_joint
- hard-constraint:
- {double-sub: [-3.75, r_upper_arm_roll_joint]}
- {double-sub: [0.65, r_upper_arm_roll_joint]}
- r_upper_arm_roll_joint
- hard-constraint:
- {double-sub: [-2.1213, r_elbow_flex_joint]}
- {double-sub: [-0.15, r_elbow_flex_joint]}
- r_elbow_flex_joint
- hard-constraint:
- {double-sub: [-2.0, r_wrist_flex_joint]}
- {double-sub: [-0.1, r_wrist_flex_joint]}
- r_wrist_flex_joint