-
Notifications
You must be signed in to change notification settings - Fork 72
Expand file tree
/
Copy pathparameters.yaml
More file actions
323 lines (304 loc) · 10.5 KB
/
parameters.yaml
File metadata and controls
323 lines (304 loc) · 10.5 KB
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
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
admittance_controller:
scientific_notation_num:
type: double
default_value: 0.00000000001
description: "Test scientific notation"
interpolation_mode:
type: string
default_value: "spline"
description: "specifies which algorithm to use for interpolation."
validation:
one_of<>: [ [ "spline", "linear" ] ]
"custom_validators::no_args_validator": null
subset_selection:
type: string_array
default_value: ["A", "B"]
description: "test subset of validator."
validation:
subset_of<>: [ [ "A", "B", "C"] ]
joints:
type: string_array
default_value: ["joint1", "joint2", "joint3"]
description: "specifies which joints will be used by the controller"
dof_names:
type: string_array
default_value: ["x", "y", "rz"]
description: "specifies which joints will be used by the controller"
additional_constraints: "Any string can be here. For example, you might want to embed JSON schema"
__map_joints:
__map_dof_names:
weight:
type: double
default_value: 1.0
description: "map parameter without struct name"
validation:
gt<>: [0.0]
limit:
type: double_array
description: "specifies limit for x, y and z axis"
default_value: [0.0, 0.0, 0.0]
validation:
fixed_size<>: 3
lower_element_bounds<>: -10.0
upper_element_bounds<>: 10.0
nested_dynamic:
__map_joints:
__map_dof_names:
nested:
type: double
default_value: 1.0
description: "test nested map params"
validation:
gt_eq<>: [ 0.0001 ]
__map_joints:
__map_dof_names:
nested_deep:
type: double
default_value: 1.0
description: "test deep nested map params"
validation:
gt_eq<>: [ 0.0001 ]
pid:
rate:
type: double
default_value: 0.005
description: "update loop period in seconds"
__map_joints:
p:
type: double
default_value: 1.0
description: "proportional gain term"
validation:
gt_eq<>: [ 0.0001 ]
i:
type: double
default_value: 1.0
description: "integral gain term"
d:
type: double
default_value: 1.0
description: "derivative gain term"
gains:
__map_dof_names:
k:
type: double
default_value: 2.0
description: "general gain"
nested_map:
entries:
type: string_array
default_value: ["entry1", "entry2"]
description: "Keys for nested mapped parameters"
__map_entries:
value:
type: double
default_value: 1.0
description: "A value in the nested map with sibling keys"
fixed_string:
type: string_fixed_25
default_value: "string_value"
description: "test code generation for fixed sized string"
fixed_array:
type: double_array_fixed_10
default_value: [1.0, 2.3, 4.0 ,5.4, 3.3]
description: "test code generation for fixed sized array"
fixed_string_no_default:
type: string_fixed_25
description: "test code generation for fixed sized string with no default"
command_interfaces:
type: string_array
description: "specifies which command interfaces to claim"
read_only: true
state_interfaces:
type: string_array
description: "specifies which state interfaces to claim"
read_only: true
chainable_command_interfaces:
type: string_array
description: "specifies which chainable interfaces to claim"
read_only: true
kinematics:
plugin_name:
type: string
description: "specifies which kinematics plugin to load"
plugin_package:
type: string
description: "specifies the package to load the kinematics plugin from"
base:
type: string
description: "specifies the base link of the robot description used by the kinematics plugin"
tip:
type: string
description: "specifies the end effector link of the robot description used by the kinematics plugin"
alpha:
type: double
default_value: 0.0005
description: "specifies the damping coefficient for the Jacobian pseudo inverse"
group_name:
type: string
description: "specifies the group name for planning with Moveit"
ft_sensor:
name:
type: string
description: "name of the force torque sensor in the robot description"
frame:
id:
type: string
description: "frame of the force torque sensor"
external:
type: bool
default_value: false
description: "specifies if the force torque sensor is contained in the kinematics chain from the base to the tip"
filter_coefficient:
type: double
default_value: 0.005
description: "specifies the coefficient for the sensor's exponential filter"
control:
frame:
id:
type: string
description: "control frame used for admittance control"
external:
type: bool
default_value: false
description: "specifies if the control frame is contained in the kinematics chain from the base to the tip"
fixed_world_frame: # Gravity points down (neg. Z) in this frame (Usually: world or base_link)
frame:
id:
type: string
description: "world frame, gravity points down (neg. Z) in this frame"
external:
type: bool
default_value: false
description: "specifies if the world frame is contained in the kinematics chain from the base to the tip"
gravity_compensation:
frame:
id:
type: string
description: "frame which center of gravity (CoG) is defined in"
external:
type: bool
default_value: false
description: "specifies if the center of gravity frame is contained in the kinematics chain from the base to the tip"
CoG: # specifies the center of gravity of the end effector
pos:
type: double_array
description: "position of the center of gravity (CoG) in its frame"
validation:
fixed_size<>: 3
force:
type: double
default_value: .NAN
description: "weight of the end effector, e.g mass * 9.81"
admittance:
selected_axes:
type: bool_array
description: "specifies if the axes x, y, z, rx, ry, and rz are enabled"
validation:
fixed_size<>: 6
# Having ".0" at the end is MUST, otherwise there is a loading error
# F = M*a + D*v + S*(x - x_d)
mass:
type: double_array
description: "specifies mass values for x, y, z, rx, ry, and rz used in the admittance calculation"
validation:
fixed_size<>: 6
element_bounds<>: [ 0.0001, 1000000.0 ]
damping_ratio:
type: double_array
description: "specifies damping ratio values for x, y, z, rx, ry, and rz used in the admittance calculation.
The values are calculated as damping can be used instead: zeta = D / (2 * sqrt( M * S ))"
validation:
fixed_size<>: 6
"custom_validators::validate_double_array_custom_func": [ 20.3, 5.0 ]
element_bounds<>: [ 0.1, 10.0 ]
stiffness:
type: double_array
description: "specifies stiffness values for x, y, z, rx, ry, and rz used in the admittance calculation"
validation:
element_bounds: [ 0.0001, 100000.0 ]
acceleration_limits:
type: double_array
description: "specifies maximum acceleration limits for x, y and z axis"
default_value: [0.0, 0.0, 0.0]
validation:
fixed_size<>: 3
lower_element_bounds<>: -10.0
upper_element_bounds<>: 10.0
# general settings
enable_parameter_update_without_reactivation:
type: bool
default_value: true
description: "if enabled, read_only parameters will be dynamically updated in the control loop"
use_feedforward_commanded_input:
type: bool
default_value: false
description: "if enabled, the velocity commanded to the admittance controller is added to its calculated admittance velocity"
lt_eq_fifteen:
type: int
default_value: 1
description: "should be a number less than or equal to 15"
validation:
lt_eq<>: [ 15 ]
gt_fifteen:
type: int
default_value: 16
description: "should be a number greater than 15"
validation:
gt<>: [ 15 ]
gt_fifteen_lt_eq_twenty:
type: int
default_value: 20
description: "should be a number greater than 15 and less than or equal to 20"
validation:
gt<>: [ 15 ]
lt_eq<>: [ 20 ]
gt_fifteen_lt_twenty:
type: int
default_value: 16
description: "should be a number greater than 15 and less than 20"
validation:
gt<>: [ 15 ]
lt<>: [ 20 ]
one_number:
type: int
default_value: 14540
read_only: true
validation:
bounds<>: [ 1024, 65535 ]
three_numbers:
type: int_array
default_value: [3,4,5]
read_only: true
three_numbers_of_five:
type: int_array_fixed_5
default_value: [3,3,3]
read_only: true
hover_override:
type: int
default_value: 1
description: "Override hover action:\n0: Hover\n1: Push\n2: Pull\n-1: Do not override"
validation:
one_of<>: [ [ 0, 1, 2, -1 ] ]
angle_wraparound:
type: bool
default_value: false
description: 'For joints that wrap around (without end stop, ie. are continuous)
where the shortest rotation to the target position is the desired motion.
If true, the position error :math:`e = normalize(s_d - s)` is normalized between :math:`-\pi, \pi`.
Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured
position :math:`s` from the state interface.'
open_loop_control:
type: bool
default_value: false
description: "Use controller in open-loop control mode
\n\n
* The controller ignores the states provided by hardware interface but using last commands as states for starting the trajectory interpolation.\n
* It deactivates the feedback control, see the ``gains`` structure.
\n\n
This is useful if hardware states are not following commands, i.e., an offset between those (typical for hydraulic manipulators).
\n\n
If this flag is set, the controller tries to read the values from the command interfaces on activation.
If they have real numeric values, those will be used instead of state interfaces.
Therefore it is important set command interfaces to NaN (i.e., ``std::numeric_limits<double>::quiet_NaN()``) or state values when the hardware is started.\n"
read_only: true