-
Notifications
You must be signed in to change notification settings - Fork 202
Expand file tree
/
Copy pathaic_controller_parameters.yaml
More file actions
274 lines (264 loc) · 8.24 KB
/
aic_controller_parameters.yaml
File metadata and controls
274 lines (264 loc) · 8.24 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
aic_controller:
joints: {
type: string_array,
description: "Specifies which joints will be used by the controller. ",
read_only: true
}
kinematics:
plugin_name: {
type: string,
description: "Specifies the name of the kinematics plugin to load."
}
plugin_package: {
type: string,
description: "Specifies the package name that contains the kinematics plugin."
}
base: {
type: string,
description: "Specifies the base link of the robot description used by the kinematics plugin."
}
tip: {
type: string,
description: "Frame ID of tool center point"
}
alpha: {
type: double,
default_value: 0.01,
description: "Specifies the damping coefficient for the Jacobian pseudo inverse."
}
force_torque_sensor:
name: {
type: string,
description: "Name of the force torque sensor as defined in the robot description."
}
control_mode: {
type: string,
default_value: "impedance",
description: "Sets the controller used, which can be either 'impedance' or 'admittance'"
}
target_mode: {
type: string,
default_value: "joint",
description: "Sets the target mode, which controls the type of target accepted. Values are 'cartesian' or 'joint'"
}
admittance_controller_namespace: {
type: string,
default_value: "admittance_controller",
description: "Sets the namespace of the admittance controller to chain to"
}
control_frequency: {
type: double,
default_value: 0.0,
description: "Frequency of control loop in Hz"
}
clamp_to_limits:
min_translational_position: {
type: double_array,
description: "Minimum translational position in meters",
validation: {
fixed_size<>: 3
}
}
max_translational_position: {
type: double_array,
description: "Maximum translational position in meters",
validation: {
fixed_size<>: 3
}
}
min_translational_velocity: {
type: double_array,
description: "Minimum translational velocity in m/s",
validation: {
fixed_size<>: 3
}
}
max_translational_velocity: {
type: double_array,
description: "Maximum translational velocity in m/s",
validation: {
fixed_size<>: 3
}
}
min_rotation_angle: {
type: double_array,
description: "Minimum rotation angle in radians",
validation: {
fixed_size<>: 3,
element_bounds<>: [ -3.1415926535, 3.1415926535 ]
}
}
max_rotation_angle: {
type: double_array,
description: "Maximum rotation angle in radians",
validation: {
fixed_size<>: 3,
element_bounds<>: [ -3.1415926535, 3.1415926535 ]
}
}
max_rotational_velocity: {
type: double,
default_value: 0.0,
description: "Maximum rotational velocity in rad/s"
}
tracking_error:
timeout: {
type: double,
default_value: 0.0,
description: "If there is no change in the error after the timeout duration, the tracking error will be clamped to their max values."
}
min_angular_change: {
type: double,
default_value: 0.0,
description: "Mininimum change in angular error such that the robot is moving towards the target. Units in radians"
}
min_translation_change: {
type: double,
default_value: 0.0,
description: "Minimum change in translation error such that the robot is moving towards the target. Units in meters"
}
min_translation_error: {
type: double,
default_value: 0.2,
description: "Minimum translation error to trigger clamping. Make sure it is larger than min_translation_change to avoid instability. Units in meters"
}
# Cartesian impedance controller parameters
impedance:
gravity_compensation: {
type: bool,
default_value: false,
description: "If enabled, compensate for gravitational force on robot arm in joint torque output."
}
stiffness_smoothing_constant: {
type: double,
default_value: 0.0,
description: "Constant for exponential smoothing of stiffness matrix. Value ranges from 0 to 1, where 1 means no smoothing and 0 means no change in value."
}
damping_smoothing_constant: {
type: double,
default_value: 0.0,
description: "Constant for exponential smoothing of damping matrix. Value ranges from 0 to 1, where 1 means no smoothing and 0 means no change in value."
}
activation_percentage: {
type: double,
default_value: 0.0,
description: "Specifies the percentage of the range, from the minimum to the maximum joint position, where the joint limit activation potential is active. Value ranges from 0 to 1"
}
pose_error_integrator:
gain: {
type: double_array,
description: "Gains used in pose integration.",
validation: {
fixed_size<>: 6
}
}
bound: {
type: double_array,
description: "Bounds for integrator. Uses units of N for translational axes and units of Nm for rotational axes.",
validation: {
fixed_size<>: 6
}
}
maximum_wrench: {
type: double_array,
description: "Limit for the wrench magnitude resulting from the feedback control law after adding the feedforward wrench terms.",
validation: {
fixed_size<>: 6
}
}
nullspace:
target_configuration: {
type: double_array,
description: "Target configuration for the nullspace of the arm",
}
stiffness: {
type: double_array,
description: "Stiffness parameters used in computing the nullspace torque",
}
damping: {
type: double_array,
description: "Damping parameters used in computing the nullspace torque",
}
feedforward_interpolation:
min_wrench: {
type: double_array,
description: "Minimum limit of feedforward target wrench",
validation: {
fixed_size<>: 6
}
}
max_wrench: {
type: double_array,
description: "Maximum limit of feedforward target wrench",
validation: {
fixed_size<>: 6
}
}
max_wrench_dot: {
type: double_array,
description: "Maximum change in feedforward target wrench after interpolation",
validation: {
fixed_size<>: 6
}
}
default_values:
control_stiffness: {
type: double_array,
description: "Default starting values for diagonals of control stiffness matrix",
validation: {
fixed_size<>: 6
}
}
control_damping: {
type: double_array,
description: "Default starting values for diagonals of control damping matrix",
validation: {
fixed_size<>: 6
}
}
offset_wrench: {
type: double_array,
description: "Default offset values for wrench to compensate for payload weight outside of the kinematic chain. The wrench is with respect to base frame.",
validation: {
fixed_size<>: 6
}
}
# Joint impedance controller parameters
joint_impedance:
interpolator:
min_value: {
type: double_array,
description: "Minimum allowed value for feedforward torque",
validation: {
fixed_size<>: 6
}
}
max_value: {
type: double_array,
description: "Maximum allowed value for feedforward torque",
validation: {
fixed_size<>: 6
}
}
max_step_size: {
type: double_array,
description: "Maximum step size used to interpolate the feedforward torque",
validation: {
fixed_size<>: 6
}
}
default_values:
control_stiffness: {
type: double_array,
description: "Default starting values for control stiffness vector",
}
control_damping: {
type: double_array,
description: "Default starting values for control damping vector",
}
# general settings
enable_parameter_update_without_reactivation: {
type: bool,
default_value: true,
description: "If enabled, the parameters will be dynamically updated while the controller is running."
}