-
Notifications
You must be signed in to change notification settings - Fork 479
Expand file tree
/
Copy pathtricycle_controller_parameter.yaml
More file actions
150 lines (150 loc) · 4.41 KB
/
tricycle_controller_parameter.yaml
File metadata and controls
150 lines (150 loc) · 4.41 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
tricycle_controller:
traction_joint_name: {
type: string,
default_value: "",
description: "Name of the traction joint",
validation: {
not_empty<>: []
}
}
steering_joint_name: {
type: string,
default_value: "",
description: "Name of the steering joint",
validation: {
not_empty<>: []
}
}
wheelbase: {
type: double,
default_value: 0.0,
description: "Shortest distance between the front wheel and the rear axle. If this parameter is wrong, the robot will not behave correctly in curves.",
validation: {
gt<>: [0.0]
}
}
wheel_radius: {
type: double,
default_value: 0.0,
description: "Radius of a wheel, i.e., wheels size, used for transformation of linear velocity into wheel rotations. If this parameter is wrong the robot will move faster or slower then expected.",
validation: {
gt<>: [0.0]
}
}
odom_frame_id: {
type: string,
default_value: "odom",
description: "Name of the frame for odometry. This frame is parent of ``base_frame_id`` when controller publishes odometry.",
}
base_frame_id: {
type: string,
default_value: "base_link",
description: "Name of the robot's base frame that is child of the odometry frame.",
}
pose_covariance_diagonal: {
type: double_array,
default_value: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
description: "Odometry covariance for the encoder output of the robot for the pose. These values should be tuned to your robot's sample odometry data, but these values are a good place to start: ``[0.001, 0.001, 0.001, 0.001, 0.001, 0.01]``.",
}
twist_covariance_diagonal: {
type: double_array,
default_value: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
description: "Odometry covariance for the encoder output of the robot for the speed. These values should be tuned to your robot's sample odometry data, but these values are a good place to start: ``[0.001, 0.001, 0.001, 0.001, 0.001, 0.01]``.",
}
open_loop: {
type: bool,
default_value: false,
description: "If set to true the odometry of the robot will be calculated from the commanded values and not from feedback.",
}
enable_odom_tf: {
type: bool,
default_value: false,
description: "Publish transformation between ``odom_frame_id`` and ``base_frame_id``.",
}
odom_only_twist: {
type: bool,
default_value: false,
description: "for doing the pose integration in separate node.",
}
cmd_vel_timeout: {
type: double,
default_value: 0.5, # seconds
description: "Timeout in seconds, after which input command on ``cmd_vel`` topic is considered staled.",
}
publish_ackermann_command: {
type: bool,
default_value: false,
description: "Publish limited commands.",
}
velocity_rolling_window_size: {
type: int,
default_value: 10,
description: "Size of the rolling window for calculation of mean velocity use in odometry.",
validation: {
gt<>: [0]
}
}
traction:
# "The positive limit will be applied to both directions. Setting different limits for positive "
# "and negative directions is not supported. Actuators are "
# "assumed to have the same constraints in both directions"
max_velocity: {
type: double,
default_value: .NAN,
}
min_velocity: {
type: double,
default_value: .NAN,
}
max_acceleration: {
type: double,
default_value: .NAN,
}
min_acceleration: {
type: double,
default_value: .NAN,
}
max_deceleration: {
type: double,
default_value: .NAN,
}
min_deceleration: {
type: double,
default_value: .NAN,
}
max_jerk: {
type: double,
default_value: .NAN,
}
min_jerk: {
type: double,
default_value: .NAN,
}
steering:
# "The positive limit will be applied to both directions. Setting different limits for positive "
# "and negative directions is not supported. Actuators are "
# "assumed to have the same constraints in both directions"
max_position: {
type: double,
default_value: .NAN,
}
min_position: {
type: double,
default_value: .NAN,
}
max_velocity: {
type: double,
default_value: .NAN,
}
min_velocity: {
type: double,
default_value: .NAN,
}
max_acceleration: {
type: double,
default_value: .NAN,
}
min_acceleration: {
type: double,
default_value: .NAN,
}