-
Notifications
You must be signed in to change notification settings - Fork 49
/
Copy pathparameters.yaml
166 lines (154 loc) · 4.85 KB
/
parameters.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
admittance_controller:
joints: {
type: string_array,
description: "specifies which joints will be used by the controller",
read_only: true
}
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,
fixed_size: 3,
description: "position of the center of gravity (CoG) in its frame"
}
force: {
type: double,
default_value: .NAN,
description: "weight of the end effector, e.g mass * 9.81"
}
admittance:
selected_axes:
{
type: bool_array,
fixed_size: 6,
description: "specifies if the axes x, y, z, rx, ry, and rz are enabled"
}
# 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,
fixed_size: 6,
description: "specifies mass values for x, y, z, rx, ry, and rz used in the admittance calculation",
bounds: [ 0.0001, 1000000.0]
}
damping_ratio: {
type: double_array,
fixed_size: 6,
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 ))",
bounds: [ 0.1, 10.0 ],
validation:
[validate_double_array_custom_func, 20.3, 5.0]
}
stiffness: {
type: double_array,
description: "specifies stiffness values for x, y, z, rx, ry, and rz used in the admittance calculation",
bounds: [ 0.0001, 100000.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: true,
description: "if enabled, the velocity commanded to the admittance controller is added to its calculated admittance velocity"
}