-
Notifications
You must be signed in to change notification settings - Fork 469
Expand file tree
/
Copy pathpid_controller.yaml
More file actions
137 lines (137 loc) · 4.46 KB
/
pid_controller.yaml
File metadata and controls
137 lines (137 loc) · 4.46 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
pid_controller:
dof_names: {
type: string_array,
default_value: [],
description: "Specifies dof_names or axes used by the controller. If 'reference_and_state_dof_names' parameter is defined, then only command dof names are defined with this parameter.",
read_only: true,
validation: {
unique<>: null,
not_empty<>: null,
}
}
reference_and_state_dof_names: {
type: string_array,
default_value: [],
description: "(optional) Specifies dof_names or axes for getting reference and reading states. This parameter is only relevant when state dof names are different then command dof names, i.e., when a following controller is used.",
read_only: true,
validation: {
unique<>: null,
}
}
command_interface: {
type: string,
default_value: "",
description: "Name of the interface used by the controller for writing commands to the hardware.",
read_only: true,
validation: {
not_empty<>: null,
}
}
reference_and_state_interfaces: {
type: string_array,
default_value: [],
description: "Name of the interfaces used by the controller getting hardware states and reference commands. The second interface should be the derivative of the first.",
read_only: true,
validation: {
not_empty<>: null,
size_gt<>: 0,
size_lt<>: 3,
}
}
use_external_measured_states: {
type: bool,
default_value: false,
description: "Use external states from a topic instead from state interfaces."
}
enable_feedforward: {
type: bool,
default_value: false,
description: "Enables feedforward gain. (Will be deprecated in favour of setting feedforward_gain to a non-zero value.)"
}
gains:
__map_dof_names:
p: {
type: double,
default_value: 0.0,
description: "Proportional gain for PID"
}
i: {
type: double,
default_value: 0.0,
description: "Integral gain for PID"
}
d: {
type: double,
default_value: 0.0,
description: "Derivative gain for PID"
}
u_clamp_max: {
type: double,
default_value: .inf,
description: "Upper output clamp."
}
u_clamp_min: {
type: double,
default_value: -.inf,
description: "Lower output clamp."
}
antiwindup: {
type: bool,
default_value: false,
description: "[Deprecated, see antiwindup_strategy] Anti-windup functionality. When set to true, limits
the integral error to prevent windup; otherwise, constrains the
integral contribution to the control output. i_clamp_max and
i_clamp_min are applied in both scenarios."
}
i_clamp_max: {
type: double,
default_value: 0.0,
description: "[Deprecated, see antiwindup_strategy] Upper integral clamp."
}
i_clamp_min: {
type: double,
default_value: 0.0,
description: "[Deprecated, see antiwindup_strategy] Lower integral clamp."
}
antiwindup_strategy: {
type: string,
default_value: "legacy",
description: "Specifies the anti-windup strategy. Options: 'back_calculation',
'conditional_integration', 'legacy' or 'none'. Note that the 'back_calculation' strategy use the
tracking_time_constant parameter to tune the anti-windup behavior.",
validation: {
one_of<>: [[
"back_calculation",
"conditional_integration",
"legacy",
"none"
]]
}
}
tracking_time_constant: {
type: double,
default_value: 0.0,
description: "Specifies the tracking time constant for the 'back_calculation' strategy. If
set to 0.0 when this strategy is selected, a recommended default value will be applied."
}
error_deadband: {
type: double,
default_value: 1.e-16,
description: "Is used to stop integration when the error is within the given range."
}
feedforward_gain: {
type: double,
default_value: 0.0,
description: "Gain for the feed-forward part."
}
angle_wraparound: {
type: bool,
default_value: false,
description: "For joints that wrap around (i.e., are continuous).
Normalizes position-error to -pi to pi."
}
save_i_term: {
type: bool,
default_value: true,
description: "Indicating if integral term is retained after re-activation"
}