Skip to content

Commit 9f2d9e6

Browse files
Remove deprecated parameters from steering_controllers_library (#1684)
1 parent 7991176 commit 9f2d9e6

13 files changed

+22
-340
lines changed

ackermann_steering_controller/src/ackermann_steering_controller.cpp

Lines changed: 0 additions & 59 deletions
Original file line numberDiff line numberDiff line change
@@ -33,65 +33,6 @@ controller_interface::CallbackReturn AckermannSteeringController::configure_odom
3333
{
3434
ackermann_params_ = ackermann_param_listener_->get_params();
3535

36-
// TODO(anyone): Remove deprecated parameters
37-
// START OF DEPRECATED
38-
if (ackermann_params_.front_wheels_radius > 0.0)
39-
{
40-
RCLCPP_WARN(
41-
get_node()->get_logger(),
42-
"DEPRECATED parameter 'front_wheel_radius', set 'traction_wheels_radius' instead");
43-
ackermann_params_.traction_wheels_radius = ackermann_params_.front_wheels_radius;
44-
}
45-
46-
if (ackermann_params_.rear_wheels_radius > 0.0)
47-
{
48-
RCLCPP_WARN(
49-
get_node()->get_logger(),
50-
"DEPRECATED parameter 'rear_wheel_radius', set 'traction_wheels_radius' instead");
51-
ackermann_params_.traction_wheels_radius = ackermann_params_.rear_wheels_radius;
52-
}
53-
54-
if (ackermann_params_.front_wheel_track > 0.0)
55-
{
56-
RCLCPP_WARN(
57-
get_node()->get_logger(),
58-
"DEPRECATED parameter 'front_wheel_track', set 'traction_track_width' or "
59-
"'steering_track_width' instead");
60-
if (params_.front_steering)
61-
{
62-
ackermann_params_.steering_track_width = ackermann_params_.front_wheel_track;
63-
}
64-
else
65-
{
66-
ackermann_params_.traction_track_width = ackermann_params_.front_wheel_track;
67-
}
68-
}
69-
70-
if (ackermann_params_.rear_wheel_track > 0.0)
71-
{
72-
RCLCPP_WARN(
73-
get_node()->get_logger(),
74-
"DEPRECATED parameter 'rear_wheel_track', set 'traction_track_width' or "
75-
"'steering_track_width' instead");
76-
if (params_.front_steering)
77-
{
78-
ackermann_params_.traction_track_width = ackermann_params_.rear_wheel_track;
79-
}
80-
else
81-
{
82-
ackermann_params_.steering_track_width = ackermann_params_.rear_wheel_track;
83-
}
84-
}
85-
86-
if (ackermann_params_.traction_wheels_radius <= std::numeric_limits<double>::epsilon())
87-
{
88-
RCLCPP_FATAL(
89-
get_node()->get_logger(),
90-
"parameter 'traction_wheels_radius' is not set, cannot configure odometry");
91-
return controller_interface::CallbackReturn::ERROR;
92-
}
93-
// END OF DEPRECATED
94-
9536
if (ackermann_params_.steering_track_width <= std::numeric_limits<double>::epsilon())
9637
{
9738
ackermann_params_.steering_track_width = ackermann_params_.traction_track_width;
Lines changed: 6 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,5 @@
11
ackermann_steering_controller:
22

3-
front_wheel_track:
4-
{
5-
type: double,
6-
default_value: 0.0,
7-
description: "DEPRECATED: use 'traction_track_width' or 'steering_track_width'",
8-
read_only: false,
9-
}
10-
113
steering_track_width:
124
{
135
type: double,
@@ -16,24 +8,15 @@ ackermann_steering_controller:
168
read_only: false,
179
}
1810

19-
rear_wheel_track:
20-
{
21-
type: double,
22-
default_value: 0.0,
23-
description: "DEPRECATED: use 'traction_track_width' or 'steering_track_width'",
24-
read_only: false,
25-
}
26-
2711
traction_track_width:
2812
{
2913
type: double,
3014
default_value: 0.0,
3115
description: "Traction wheel track length. For details see: https://en.wikipedia.org/wiki/Wheelbase",
3216
read_only: false,
33-
# TODO(anyone): activate validation if front/rear wheel track is removed
34-
# validation: {
35-
# gt<>: [0.0]
36-
# }
17+
validation: {
18+
gt<>: [0.0]
19+
}
3720
}
3821

3922
wheelbase:
@@ -53,24 +36,7 @@ ackermann_steering_controller:
5336
default_value: 0.0,
5437
description: "Traction wheels radius.",
5538
read_only: false,
56-
# TODO(anyone): activate validation if front/rear wheel radius is removed
57-
# validation: {
58-
# gt<>: [0.0]
59-
# }
60-
}
61-
62-
front_wheels_radius:
63-
{
64-
type: double,
65-
default_value: 0.0,
66-
description: "DEPRECATED: use 'traction_wheels_radius'",
67-
read_only: false,
68-
}
69-
70-
rear_wheels_radius:
71-
{
72-
type: double,
73-
default_value: 0.0,
74-
description: "DEPRECATED: use 'traction_wheels_radius'",
75-
read_only: false,
39+
validation: {
40+
gt<>: [0.0]
41+
}
7642
}

bicycle_steering_controller/src/bicycle_steering_controller.cpp

Lines changed: 0 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -31,25 +31,6 @@ controller_interface::CallbackReturn BicycleSteeringController::configure_odomet
3131
{
3232
bicycle_params_ = bicycle_param_listener_->get_params();
3333

34-
// TODO(anyone): Remove deprecated parameters
35-
// START OF DEPRECATED
36-
if (bicycle_params_.front_wheel_radius > 0.0)
37-
{
38-
RCLCPP_WARN(
39-
get_node()->get_logger(),
40-
"DEPRECATED parameter 'front_wheel_radius', set 'traction_wheel_radius' instead");
41-
bicycle_params_.traction_wheel_radius = bicycle_params_.front_wheel_radius;
42-
}
43-
44-
if (bicycle_params_.rear_wheel_radius > 0.0)
45-
{
46-
RCLCPP_WARN(
47-
get_node()->get_logger(),
48-
"DEPRECATED parameter 'rear_wheel_radius', set 'traction_wheel_radius' instead");
49-
bicycle_params_.traction_wheel_radius = bicycle_params_.rear_wheel_radius;
50-
}
51-
// END OF DEPRECATED
52-
5334
const double wheelbase = bicycle_params_.wheelbase;
5435
const double traction_wheel_radius = bicycle_params_.traction_wheel_radius;
5536

bicycle_steering_controller/src/bicycle_steering_controller.yaml

Lines changed: 3 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -16,24 +16,7 @@ bicycle_steering_controller:
1616
default_value: 0.0,
1717
description: "Traction wheel radius.",
1818
read_only: false,
19-
# TODO(anyone): activate validation if front/rear wheel radius is removed
20-
# validation: {
21-
# gt<>: [0.0]
22-
# }
23-
}
24-
25-
front_wheel_radius:
26-
{
27-
type: double,
28-
default_value: 0.0,
29-
description: "DEPRECATED: Use 'traction_wheel_radius'",
30-
read_only: true,
31-
}
32-
33-
rear_wheel_radius:
34-
{
35-
type: double,
36-
default_value: 0.0,
37-
description: "DEPRECATED: Use 'traction_wheel_radius'",
38-
read_only: true,
19+
validation: {
20+
gt<>: [0.0]
21+
}
3922
}

steering_controllers_library/src/steering_controllers_library.cpp

Lines changed: 0 additions & 75 deletions
Original file line numberDiff line numberDiff line change
@@ -82,81 +82,6 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure(
8282
{
8383
params_ = param_listener_->get_params();
8484

85-
// TODO(anyone): Remove deprecated parameters
86-
// START OF DEPRECATED
87-
if (!params_.front_steering)
88-
{
89-
RCLCPP_WARN(
90-
get_node()->get_logger(),
91-
"DEPRECATED parameter 'front_steering'. Instead, set 'traction_joints_names' or "
92-
"'steering_joints_names'");
93-
}
94-
95-
if (params_.front_wheels_names.size() > 0)
96-
{
97-
RCLCPP_WARN(
98-
get_node()->get_logger(),
99-
"DEPRECATED parameter 'front_wheels_names', set 'traction_joints_names' or "
100-
"'steering_joints_names' instead");
101-
if (params_.front_steering)
102-
{
103-
params_.steering_joints_names = params_.front_wheels_names;
104-
}
105-
else
106-
{
107-
params_.traction_joints_names = params_.front_wheels_names;
108-
}
109-
}
110-
111-
if (params_.rear_wheels_names.size() > 0)
112-
{
113-
RCLCPP_WARN(
114-
get_node()->get_logger(),
115-
"DEPRECATED parameter 'rear_wheels_names', set 'traction_joints_names' or "
116-
"'steering_joints_names' instead");
117-
if (params_.front_steering)
118-
{
119-
params_.traction_joints_names = params_.rear_wheels_names;
120-
}
121-
else
122-
{
123-
params_.steering_joints_names = params_.rear_wheels_names;
124-
}
125-
}
126-
127-
if (params_.front_wheels_state_names.size() > 0)
128-
{
129-
RCLCPP_WARN(
130-
get_node()->get_logger(),
131-
"DEPRECATED parameter 'front_wheels_state_names', set 'traction_joints_state_names' or "
132-
"'steering_joints_state_names' instead");
133-
if (params_.front_steering)
134-
{
135-
params_.steering_joints_state_names = params_.front_wheels_state_names;
136-
}
137-
else
138-
{
139-
params_.traction_joints_state_names = params_.front_wheels_state_names;
140-
}
141-
}
142-
143-
if (params_.rear_wheels_state_names.size() > 0)
144-
{
145-
RCLCPP_WARN(
146-
get_node()->get_logger(),
147-
"DEPRECATED parameter 'rear_wheels_state_names', set 'traction_joints_state_names' or "
148-
"'steering_joints_state_names' instead");
149-
if (params_.front_steering)
150-
{
151-
params_.traction_joints_state_names = params_.rear_wheels_state_names;
152-
}
153-
else
154-
{
155-
params_.steering_joints_state_names = params_.rear_wheels_state_names;
156-
}
157-
}
158-
// END OF DEPRECATED
159-
16085
// call method from implementations, sets odometry type
16186
configure_odometry();
16287

steering_controllers_library/src/steering_controllers_library.yaml

Lines changed: 2 additions & 55 deletions
Original file line numberDiff line numberDiff line change
@@ -5,24 +5,6 @@ steering_controllers_library:
55
description: "Timeout for controller references after which they will be reset. This is especially useful for controllers that can cause unwanted and dangerous behavior if reference is not reset, e.g., velocity controllers. If value is 0 the reference is reset after each run.",
66
}
77

8-
front_steering: {
9-
type: bool,
10-
read_only: true,
11-
default_value: true,
12-
description: "DEPRECATED: Use 'traction_joints_names' or 'steering_joints_names' instead"
13-
}
14-
15-
rear_wheels_names: {
16-
type: string_array,
17-
description: "DEPRECATED: Use 'traction_joints_names' or 'steering_joints_names' instead",
18-
read_only: true,
19-
default_value: [],
20-
validation: {
21-
size_lt<>: [5],
22-
unique<>: null,
23-
}
24-
}
25-
268
traction_joints_names: {
279
type: string_array,
2810
description: "Names of traction wheel joints. For kinematic configurations with two traction joints, the expected order is: right joint, left joint.",
@@ -31,19 +13,7 @@ steering_controllers_library:
3113
validation: {
3214
size_lt<>: [5],
3315
unique<>: null,
34-
# TODO(anyone): activate validation if front/rear wheel radius is removed
35-
# not_empty<>: null,
36-
}
37-
}
38-
39-
front_wheels_names: {
40-
type: string_array,
41-
description: "DEPRECATED: Use 'traction_joints_names' or 'steering_joints_names'' instead",
42-
read_only: true,
43-
default_value: [],
44-
validation: {
45-
size_lt<>: [5],
46-
unique<>: null,
16+
not_empty<>: null,
4717
}
4818
}
4919

@@ -55,8 +25,7 @@ steering_controllers_library:
5525
validation: {
5626
size_lt<>: [5],
5727
unique<>: null,
58-
# TODO(anyone): activate validation if front/rear wheel radius is removed
59-
# not_empty<>: null,
28+
not_empty<>: null,
6029
}
6130
}
6231

@@ -71,17 +40,6 @@ steering_controllers_library:
7140
}
7241
}
7342

74-
rear_wheels_state_names: {
75-
type: string_array,
76-
description: "DEPRECATED: Use 'traction_joints_state_names' or 'steering_joints_state_names' instead",
77-
default_value: [],
78-
read_only: true,
79-
validation: {
80-
size_lt<>: [5],
81-
unique<>: null,
82-
}
83-
}
84-
8543
steering_joints_state_names: {
8644
type: string_array,
8745
description: "(Optional) Names of steering joints to read states from. If not set joint names from 'steering_joints_names' will be used.",
@@ -93,17 +51,6 @@ steering_controllers_library:
9351
}
9452
}
9553

96-
front_wheels_state_names: {
97-
type: string_array,
98-
description: "DEPRECATED: Use 'traction_joints_state_names' or 'steering_joints_state_names' instead",
99-
default_value: [],
100-
read_only: true,
101-
validation: {
102-
size_lt<>: [5],
103-
unique<>: null,
104-
}
105-
}
106-
10754
open_loop: {
10855
type: bool,
10956
default_value: false,

0 commit comments

Comments
 (0)