Skip to content

Commit c09d17b

Browse files
committed
Remove front_steering from steering library
To Accommodate controllers that are not only steering at front or rear this change remove the `front_steering` variable from steering_controller_library, as a byproduct of that the notion of front or rear wheel radius is also removed from dependant controllers and the library has know "traction_joints_names" and "steering_joints_names" instead of "front_wheels_names" and "rear_wheels_names". Signed-off-by: Quique Llorente <ellorent@redhat.com>
1 parent b245155 commit c09d17b

28 files changed

+331
-368
lines changed

ackermann_steering_controller/src/ackermann_steering_controller.cpp

+24-12
Original file line numberDiff line numberDiff line change
@@ -30,22 +30,34 @@ void AckermannSteeringController::initialize_implementation_parameter_listener()
3030
controller_interface::CallbackReturn AckermannSteeringController::configure_odometry()
3131
{
3232
ackermann_params_ = ackermann_param_listener_->get_params();
33+
34+
if (ackermann_params_.front_wheels_radius > 0.0) {
35+
fprintf(stderr, "DEPRECATED parameter 'front_wheels_radius'\n");
36+
return controller_interface::CallbackReturn::ERROR;
37+
}
38+
39+
if (ackermann_params_.rear_wheels_radius > 0.0) {
40+
fprintf(stderr, "DEPRECATED parameter 'rear_wheels_radius'\n");
41+
return controller_interface::CallbackReturn::ERROR;
42+
}
3343

34-
const double front_wheels_radius = ackermann_params_.front_wheels_radius;
35-
const double rear_wheels_radius = ackermann_params_.rear_wheels_radius;
36-
const double front_wheel_track = ackermann_params_.front_wheel_track;
37-
const double rear_wheel_track = ackermann_params_.rear_wheel_track;
38-
const double wheelbase = ackermann_params_.wheelbase;
39-
40-
if (params_.front_steering)
41-
{
42-
odometry_.set_wheel_params(rear_wheels_radius, wheelbase, rear_wheel_track);
44+
if (ackermann_params_.front_wheel_track > 0.0) {
45+
fprintf(stderr, "DEPRECATED parameter 'front_wheel_track'\n");
46+
return controller_interface::CallbackReturn::ERROR;
4347
}
44-
else
45-
{
46-
odometry_.set_wheel_params(front_wheels_radius, wheelbase, front_wheel_track);
48+
49+
if (ackermann_params_.rear_wheel_track > 0.0) {
50+
fprintf(stderr, "DEPRECATED parameter 'rear_wheel_track'\n");
51+
return controller_interface::CallbackReturn::ERROR;
4752
}
4853

54+
55+
56+
const double traction_wheels_radius = ackermann_params_.traction_wheels_radius;
57+
const double traction_wheel_track = ackermann_params_.traction_wheel_track;
58+
const double wheelbase = ackermann_params_.wheelbase;
59+
60+
odometry_.set_wheel_params(traction_wheels_radius, wheelbase, traction_wheel_track);
4961
odometry_.set_odometry_type(steering_odometry::ACKERMANN_CONFIG);
5062

5163
set_interface_numbers(NR_STATE_ITFS, NR_CMD_ITFS, NR_REF_ITFS);
Original file line numberDiff line numberDiff line change
@@ -1,24 +1,27 @@
11
ackermann_steering_controller:
2-
front_wheel_track:
2+
traction_wheel_track:
33
{
44
type: double,
55
default_value: 0.0,
6-
description: "Front wheel track length. For details see: https://en.wikipedia.org/wiki/Wheelbase",
6+
description: "Traction wheel track length. For details see: https://en.wikipedia.org/wiki/Wheelbase",
77
read_only: false,
88
validation: {
99
gt<>: [0.0]
1010
}
1111
}
12-
12+
front_wheel_track:
13+
{
14+
type: double,
15+
default_value: 0.0,
16+
description: "DEPRECATED: use 'traction_wheel_track'",
17+
read_only: false,
18+
}
1319
rear_wheel_track:
1420
{
1521
type: double,
1622
default_value: 0.0,
17-
description: "Rear wheel track length. For details see: https://en.wikipedia.org/wiki/Wheelbase",
23+
description: "DEPRECATED: use 'traction_wheel_track'",
1824
read_only: false,
19-
validation: {
20-
gt<>: [0.0]
21-
}
2225
}
2326

2427
wheelbase:
@@ -32,24 +35,29 @@ ackermann_steering_controller:
3235
}
3336
}
3437

35-
front_wheels_radius:
38+
traction_wheels_radius:
3639
{
3740
type: double,
3841
default_value: 0.0,
39-
description: "Front wheels radius.",
42+
description: "Traction wheels radius.",
4043
read_only: false,
4144
validation: {
4245
gt<>: [0.0]
4346
}
4447
}
4548

49+
front_wheels_radius:
50+
{
51+
type: double,
52+
default_value: 0.0,
53+
description: "DEPRECATED: use 'traction_wheels_radius'",
54+
read_only: false,
55+
}
56+
4657
rear_wheels_radius:
4758
{
4859
type: double,
4960
default_value: 0.0,
50-
description: "Rear wheels radius.",
61+
description: "DEPRECATED: use 'traction_wheels_radius'",
5162
read_only: false,
52-
validation: {
53-
gt<>: [0.0]
54-
}
5563
}

ackermann_steering_controller/test/ackermann_steering_controller_params.yaml

+4-7
Original file line numberDiff line numberDiff line change
@@ -2,15 +2,12 @@ test_ackermann_steering_controller:
22
ros__parameters:
33

44
reference_timeout: 2.0
5-
front_steering: true
65
open_loop: false
76
velocity_rolling_window_size: 10
87
position_feedback: false
9-
rear_wheels_names: [rear_right_wheel_joint, rear_left_wheel_joint]
10-
front_wheels_names: [front_right_steering_joint, front_left_steering_joint]
8+
traction_joints_names: [rear_right_wheel_joint, rear_left_wheel_joint]
9+
steering_joints_names: [front_right_steering_joint, front_left_steering_joint]
1110

1211
wheelbase: 3.24644
13-
front_wheel_track: 2.12321
14-
rear_wheel_track: 1.76868
15-
front_wheels_radius: 0.45
16-
rear_wheels_radius: 0.45
12+
traction_wheel_track: 1.76868
13+
traction_wheels_radius: 0.45
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,13 @@
11
test_ackermann_steering_controller:
22
ros__parameters:
33
reference_timeout: 2.0
4-
front_steering: true
54
open_loop: false
65
velocity_rolling_window_size: 10
76
position_feedback: false
8-
rear_wheels_names: [pid_controller/rear_right_wheel_joint, pid_controller/rear_left_wheel_joint]
9-
front_wheels_names: [pid_controller/front_right_steering_joint, pid_controller/front_left_steering_joint]
10-
rear_wheels_state_names: [rear_right_wheel_joint, rear_left_wheel_joint]
11-
front_wheels_state_names: [front_right_steering_joint, front_left_steering_joint]
7+
traction_joints_names: [pid_controller/rear_right_wheel_joint, pid_controller/rear_left_wheel_joint]
8+
steering_joints_names: [pid_controller/front_right_steering_joint, pid_controller/front_left_steering_joint]
9+
traction_joints_state_names: [rear_right_wheel_joint, rear_left_wheel_joint]
10+
steering_joints_state_names: [front_right_steering_joint, front_left_steering_joint]
1211
wheelbase: 3.24644
13-
front_wheel_track: 2.12321
14-
rear_wheel_track: 1.76868
15-
front_wheels_radius: 0.45
16-
rear_wheels_radius: 0.45
12+
traction_wheel_track: 1.76868
13+
traction_wheels_radius: 0.45

ackermann_steering_controller/test/test_ackermann_steering_controller.cpp

+12-15
Original file line numberDiff line numberDiff line change
@@ -32,18 +32,15 @@ TEST_F(AckermannSteeringControllerTest, all_parameters_set_configure_success)
3232
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
3333

3434
ASSERT_THAT(
35-
controller_->params_.rear_wheels_names, testing::ElementsAreArray(rear_wheels_names_));
35+
controller_->params_.traction_joints_names, testing::ElementsAreArray(traction_joints_names_));
3636
ASSERT_THAT(
37-
controller_->params_.front_wheels_names, testing::ElementsAreArray(front_wheels_names_));
38-
ASSERT_EQ(controller_->params_.front_steering, front_steering_);
37+
controller_->params_.steering_joints_names, testing::ElementsAreArray(steering_joints_names_));
3938
ASSERT_EQ(controller_->params_.open_loop, open_loop_);
4039
ASSERT_EQ(controller_->params_.velocity_rolling_window_size, velocity_rolling_window_size_);
4140
ASSERT_EQ(controller_->params_.position_feedback, position_feedback_);
4241
ASSERT_EQ(controller_->ackermann_params_.wheelbase, wheelbase_);
43-
ASSERT_EQ(controller_->ackermann_params_.front_wheels_radius, front_wheels_radius_);
44-
ASSERT_EQ(controller_->ackermann_params_.rear_wheels_radius, rear_wheels_radius_);
45-
ASSERT_EQ(controller_->ackermann_params_.front_wheel_track, front_wheel_track_);
46-
ASSERT_EQ(controller_->ackermann_params_.rear_wheel_track, rear_wheel_track_);
42+
ASSERT_EQ(controller_->ackermann_params_.traction_wheels_radius, traction_wheels_radius_);
43+
ASSERT_EQ(controller_->ackermann_params_.traction_wheel_track, traction_wheel_track_);
4744
}
4845

4946
TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
@@ -56,32 +53,32 @@ TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
5653
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
5754
EXPECT_EQ(
5855
cmd_if_conf.names[CMD_TRACTION_RIGHT_WHEEL],
59-
rear_wheels_names_[0] + "/" + traction_interface_name_);
56+
traction_joints_names_[0] + "/" + traction_interface_name_);
6057
EXPECT_EQ(
6158
cmd_if_conf.names[CMD_TRACTION_LEFT_WHEEL],
62-
rear_wheels_names_[1] + "/" + traction_interface_name_);
59+
traction_joints_names_[1] + "/" + traction_interface_name_);
6360
EXPECT_EQ(
6461
cmd_if_conf.names[CMD_STEER_RIGHT_WHEEL],
65-
front_wheels_names_[0] + "/" + steering_interface_name_);
62+
steering_joints_names_[0] + "/" + steering_interface_name_);
6663
EXPECT_EQ(
6764
cmd_if_conf.names[CMD_STEER_LEFT_WHEEL],
68-
front_wheels_names_[1] + "/" + steering_interface_name_);
65+
steering_joints_names_[1] + "/" + steering_interface_name_);
6966
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
7067

7168
auto state_if_conf = controller_->state_interface_configuration();
7269
ASSERT_EQ(state_if_conf.names.size(), joint_state_values_.size());
7370
EXPECT_EQ(
7471
state_if_conf.names[STATE_TRACTION_RIGHT_WHEEL],
75-
controller_->rear_wheels_state_names_[0] + "/" + traction_interface_name_);
72+
controller_->traction_joints_state_names_[0] + "/" + traction_interface_name_);
7673
EXPECT_EQ(
7774
state_if_conf.names[STATE_TRACTION_LEFT_WHEEL],
78-
controller_->rear_wheels_state_names_[1] + "/" + traction_interface_name_);
75+
controller_->traction_joints_state_names_[1] + "/" + traction_interface_name_);
7976
EXPECT_EQ(
8077
state_if_conf.names[STATE_STEER_RIGHT_WHEEL],
81-
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
78+
controller_->steering_joints_state_names_[0] + "/" + steering_interface_name_);
8279
EXPECT_EQ(
8380
state_if_conf.names[STATE_STEER_LEFT_WHEEL],
84-
controller_->front_wheels_state_names_[1] + "/" + steering_interface_name_);
81+
controller_->steering_joints_state_names_[1] + "/" + steering_interface_name_);
8582
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
8683

8784
// check ref itfsTIME

ackermann_steering_controller/test/test_ackermann_steering_controller.hpp

+19-20
Original file line numberDiff line numberDiff line change
@@ -165,22 +165,22 @@ class AckermannSteeringControllerFixture : public ::testing::Test
165165
command_ifs.reserve(joint_command_values_.size());
166166

167167
command_itfs_.emplace_back(hardware_interface::CommandInterface(
168-
rear_wheels_names_[0], traction_interface_name_,
168+
traction_joints_names_[0], traction_interface_name_,
169169
&joint_command_values_[CMD_TRACTION_RIGHT_WHEEL]));
170170
command_ifs.emplace_back(command_itfs_.back());
171171

172172
command_itfs_.emplace_back(hardware_interface::CommandInterface(
173-
rear_wheels_names_[1], steering_interface_name_,
173+
traction_joints_names_[1], steering_interface_name_,
174174
&joint_command_values_[CMD_TRACTION_LEFT_WHEEL]));
175175
command_ifs.emplace_back(command_itfs_.back());
176176

177177
command_itfs_.emplace_back(hardware_interface::CommandInterface(
178-
front_wheels_names_[0], steering_interface_name_,
178+
steering_joints_names_[0], steering_interface_name_,
179179
&joint_command_values_[CMD_STEER_RIGHT_WHEEL]));
180180
command_ifs.emplace_back(command_itfs_.back());
181181

182182
command_itfs_.emplace_back(hardware_interface::CommandInterface(
183-
front_wheels_names_[1], steering_interface_name_,
183+
steering_joints_names_[1], steering_interface_name_,
184184
&joint_command_values_[CMD_STEER_LEFT_WHEEL]));
185185
command_ifs.emplace_back(command_itfs_.back());
186186

@@ -189,22 +189,22 @@ class AckermannSteeringControllerFixture : public ::testing::Test
189189
state_ifs.reserve(joint_state_values_.size());
190190

191191
state_itfs_.emplace_back(hardware_interface::StateInterface(
192-
rear_wheels_names_[0], traction_interface_name_,
192+
traction_joints_names_[0], traction_interface_name_,
193193
&joint_state_values_[STATE_TRACTION_RIGHT_WHEEL]));
194194
state_ifs.emplace_back(state_itfs_.back());
195195

196196
state_itfs_.emplace_back(hardware_interface::StateInterface(
197-
rear_wheels_names_[1], traction_interface_name_,
197+
traction_joints_names_[1], traction_interface_name_,
198198
&joint_state_values_[STATE_TRACTION_LEFT_WHEEL]));
199199
state_ifs.emplace_back(state_itfs_.back());
200200

201201
state_itfs_.emplace_back(hardware_interface::StateInterface(
202-
front_wheels_names_[0], steering_interface_name_,
202+
steering_joints_names_[0], steering_interface_name_,
203203
&joint_state_values_[STATE_STEER_RIGHT_WHEEL]));
204204
state_ifs.emplace_back(state_itfs_.back());
205205

206206
state_itfs_.emplace_back(hardware_interface::StateInterface(
207-
front_wheels_names_[1], steering_interface_name_,
207+
steering_joints_names_[1], steering_interface_name_,
208208
&joint_state_values_[STATE_STEER_LEFT_WHEEL]));
209209
state_ifs.emplace_back(state_itfs_.back());
210210

@@ -276,29 +276,28 @@ class AckermannSteeringControllerFixture : public ::testing::Test
276276
protected:
277277
// Controller-related parameters
278278
double reference_timeout_ = 2.0;
279-
bool front_steering_ = true;
280279
bool open_loop_ = false;
281280
unsigned int velocity_rolling_window_size_ = 10;
282281
bool position_feedback_ = false;
283-
std::vector<std::string> rear_wheels_names_ = {"rear_right_wheel_joint", "rear_left_wheel_joint"};
284-
std::vector<std::string> front_wheels_names_ = {
282+
std::vector<std::string> traction_joints_names_ = {
283+
"rear_right_wheel_joint", "rear_left_wheel_joint"};
284+
std::vector<std::string> steering_joints_names_ = {
285285
"front_right_steering_joint", "front_left_steering_joint"};
286286
std::vector<std::string> joint_names_ = {
287-
rear_wheels_names_[0], rear_wheels_names_[1], front_wheels_names_[0], front_wheels_names_[1]};
287+
traction_joints_names_[0], traction_joints_names_[1], steering_joints_names_[0],
288+
steering_joints_names_[1]};
288289

289-
std::vector<std::string> rear_wheels_preceeding_names_ = {
290+
std::vector<std::string> wheels_preceeding_names_ = {
290291
"pid_controller/rear_right_wheel_joint", "pid_controller/rear_left_wheel_joint"};
291-
std::vector<std::string> front_wheels_preceeding_names_ = {
292+
std::vector<std::string> steers_preceeding_names_ = {
292293
"pid_controller/front_right_steering_joint", "pid_controller/front_left_steering_joint"};
293294
std::vector<std::string> preceeding_joint_names_ = {
294-
rear_wheels_preceeding_names_[0], rear_wheels_preceeding_names_[1],
295-
front_wheels_preceeding_names_[0], front_wheels_preceeding_names_[1]};
295+
wheels_preceeding_names_[0], wheels_preceeding_names_[1], steers_preceeding_names_[0],
296+
steers_preceeding_names_[1]};
296297

297298
double wheelbase_ = 3.24644;
298-
double front_wheel_track_ = 2.12321;
299-
double rear_wheel_track_ = 1.76868;
300-
double front_wheels_radius_ = 0.45;
301-
double rear_wheels_radius_ = 0.45;
299+
double traction_wheel_track_ = 1.76868;
300+
double traction_wheels_radius_ = 0.45;
302301

303302
std::array<double, 4> joint_state_values_ = {0.5, 0.5, 0.0, 0.0};
304303
std::array<double, 4> joint_command_values_ = {1.1, 3.3, 2.2, 4.4};

ackermann_steering_controller/test/test_ackermann_steering_controller_preceeding.cpp

+14-17
Original file line numberDiff line numberDiff line change
@@ -32,20 +32,17 @@ TEST_F(AckermannSteeringControllerTest, all_parameters_set_configure_success)
3232
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
3333

3434
ASSERT_THAT(
35-
controller_->params_.rear_wheels_names,
36-
testing::ElementsAreArray(rear_wheels_preceeding_names_));
35+
controller_->params_.traction_joints_names,
36+
testing::ElementsAreArray(wheels_preceeding_names_));
3737
ASSERT_THAT(
38-
controller_->params_.front_wheels_names,
39-
testing::ElementsAreArray(front_wheels_preceeding_names_));
40-
ASSERT_EQ(controller_->params_.front_steering, front_steering_);
38+
controller_->params_.steering_joints_names,
39+
testing::ElementsAreArray(steers_preceeding_names_));
4140
ASSERT_EQ(controller_->params_.open_loop, open_loop_);
4241
ASSERT_EQ(controller_->params_.velocity_rolling_window_size, velocity_rolling_window_size_);
4342
ASSERT_EQ(controller_->params_.position_feedback, position_feedback_);
4443
ASSERT_EQ(controller_->ackermann_params_.wheelbase, wheelbase_);
45-
ASSERT_EQ(controller_->ackermann_params_.front_wheels_radius, front_wheels_radius_);
46-
ASSERT_EQ(controller_->ackermann_params_.rear_wheels_radius, rear_wheels_radius_);
47-
ASSERT_EQ(controller_->ackermann_params_.front_wheel_track, front_wheel_track_);
48-
ASSERT_EQ(controller_->ackermann_params_.rear_wheel_track, rear_wheel_track_);
44+
ASSERT_EQ(controller_->ackermann_params_.traction_wheels_radius, traction_wheels_radius_);
45+
ASSERT_EQ(controller_->ackermann_params_.traction_wheel_track, traction_wheel_track_);
4946
}
5047

5148
TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
@@ -58,32 +55,32 @@ TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
5855
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
5956
EXPECT_EQ(
6057
cmd_if_conf.names[CMD_TRACTION_RIGHT_WHEEL],
61-
preceeding_prefix_ + "/" + rear_wheels_names_[0] + "/" + traction_interface_name_);
58+
preceeding_prefix_ + "/" + traction_joints_names_[0] + "/" + traction_interface_name_);
6259
EXPECT_EQ(
6360
cmd_if_conf.names[CMD_TRACTION_LEFT_WHEEL],
64-
preceeding_prefix_ + "/" + rear_wheels_names_[1] + "/" + traction_interface_name_);
61+
preceeding_prefix_ + "/" + traction_joints_names_[1] + "/" + traction_interface_name_);
6562
EXPECT_EQ(
6663
cmd_if_conf.names[CMD_STEER_RIGHT_WHEEL],
67-
preceeding_prefix_ + "/" + front_wheels_names_[0] + "/" + steering_interface_name_);
64+
preceeding_prefix_ + "/" + steering_joints_names_[0] + "/" + steering_interface_name_);
6865
EXPECT_EQ(
6966
cmd_if_conf.names[CMD_STEER_LEFT_WHEEL],
70-
preceeding_prefix_ + "/" + front_wheels_names_[1] + "/" + steering_interface_name_);
67+
preceeding_prefix_ + "/" + steering_joints_names_[1] + "/" + steering_interface_name_);
7168
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
7269

7370
auto state_if_conf = controller_->state_interface_configuration();
7471
ASSERT_EQ(state_if_conf.names.size(), joint_state_values_.size());
7572
EXPECT_EQ(
7673
state_if_conf.names[STATE_TRACTION_RIGHT_WHEEL],
77-
controller_->rear_wheels_state_names_[0] + "/" + traction_interface_name_);
74+
controller_->traction_joints_state_names_[0] + "/" + traction_interface_name_);
7875
EXPECT_EQ(
7976
state_if_conf.names[STATE_TRACTION_LEFT_WHEEL],
80-
controller_->rear_wheels_state_names_[1] + "/" + traction_interface_name_);
77+
controller_->traction_joints_state_names_[1] + "/" + traction_interface_name_);
8178
EXPECT_EQ(
8279
state_if_conf.names[STATE_STEER_RIGHT_WHEEL],
83-
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
80+
controller_->steering_joints_state_names_[0] + "/" + steering_interface_name_);
8481
EXPECT_EQ(
8582
state_if_conf.names[STATE_STEER_LEFT_WHEEL],
86-
controller_->front_wheels_state_names_[1] + "/" + steering_interface_name_);
83+
controller_->steering_joints_state_names_[1] + "/" + steering_interface_name_);
8784
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
8885

8986
// check ref itfs

0 commit comments

Comments
 (0)