Skip to content

Commit 1ec176a

Browse files
Rename wheel_track to track_width
1 parent 1707c2b commit 1ec176a

11 files changed

+70
-30
lines changed

ackermann_steering_controller/src/ackermann_steering_controller.cpp

Lines changed: 21 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -55,47 +55,55 @@ controller_interface::CallbackReturn AckermannSteeringController::configure_odom
5555
{
5656
RCLCPP_WARN(
5757
get_node()->get_logger(),
58-
"DEPRECATED parameter 'front_wheel_track', set 'traction_wheel_track' or "
59-
"'steering_wheel_track' instead");
58+
"DEPRECATED parameter 'front_wheel_track', set 'traction_track_width' or "
59+
"'steering_track_width' instead");
6060
if (params_.front_steering)
6161
{
62-
ackermann_params_.steering_wheel_track = ackermann_params_.front_wheel_track;
62+
ackermann_params_.steering_track_width = ackermann_params_.front_wheel_track;
6363
}
6464
else
6565
{
66-
ackermann_params_.traction_wheel_track = ackermann_params_.front_wheel_track;
66+
ackermann_params_.traction_track_width = ackermann_params_.front_wheel_track;
6767
}
6868
}
6969

7070
if (ackermann_params_.rear_wheel_track > 0.0)
7171
{
7272
RCLCPP_WARN(
7373
get_node()->get_logger(),
74-
"DEPRECATED parameter 'rear_wheel_track', set 'traction_wheel_track' or "
75-
"'steering_wheel_track' instead");
74+
"DEPRECATED parameter 'rear_wheel_track', set 'traction_track_width' or "
75+
"'steering_track_width' instead");
7676
if (params_.front_steering)
7777
{
78-
ackermann_params_.traction_wheel_track = ackermann_params_.rear_wheel_track;
78+
ackermann_params_.traction_track_width = ackermann_params_.rear_wheel_track;
7979
}
8080
else
8181
{
82-
ackermann_params_.steering_wheel_track = ackermann_params_.rear_wheel_track;
82+
ackermann_params_.steering_track_width = ackermann_params_.rear_wheel_track;
8383
}
8484
}
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+
}
8593
// END OF DEPRECATED
8694

87-
if (ackermann_params_.steering_wheel_track <= std::numeric_limits<double>::epsilon())
95+
if (ackermann_params_.steering_track_width <= std::numeric_limits<double>::epsilon())
8896
{
89-
ackermann_params_.steering_wheel_track = ackermann_params_.traction_wheel_track;
97+
ackermann_params_.steering_track_width = ackermann_params_.traction_track_width;
9098
}
9199

92100
const double traction_wheels_radius = ackermann_params_.traction_wheels_radius;
93-
const double traction_wheel_track = ackermann_params_.traction_wheel_track;
94-
const double steering_wheel_track = ackermann_params_.steering_wheel_track;
101+
const double traction_track_width = ackermann_params_.traction_track_width;
102+
const double steering_track_width = ackermann_params_.steering_track_width;
95103
const double wheelbase = ackermann_params_.wheelbase;
96104

97105
odometry_.set_wheel_params(
98-
traction_wheels_radius, wheelbase, steering_wheel_track, traction_wheel_track);
106+
traction_wheels_radius, wheelbase, steering_track_width, traction_track_width);
99107
odometry_.set_odometry_type(steering_odometry::ACKERMANN_CONFIG);
100108

101109
set_interface_numbers(NR_STATE_ITFS, NR_CMD_ITFS, NR_REF_ITFS);

ackermann_steering_controller/src/ackermann_steering_controller.yaml

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -4,27 +4,27 @@ ackermann_steering_controller:
44
{
55
type: double,
66
default_value: 0.0,
7-
description: "DEPRECATED: use 'traction_wheel_track' or 'steering_wheel_track'",
7+
description: "DEPRECATED: use 'traction_track_width' or 'steering_track_width'",
88
read_only: false,
99
}
1010

11-
steering_wheel_track:
11+
steering_track_width:
1212
{
1313
type: double,
1414
default_value: 0.0,
15-
description: "(Optional) Steering wheel track length. If not set, 'traction_wheel_track' will be used.",
15+
description: "(Optional) Steering wheel track length. If not set, 'traction_track_width' will be used.",
1616
read_only: false,
1717
}
1818

1919
rear_wheel_track:
2020
{
2121
type: double,
2222
default_value: 0.0,
23-
description: "DEPRECATED: use 'traction_wheel_track' or 'steering_wheel_track'",
23+
description: "DEPRECATED: use 'traction_track_width' or 'steering_track_width'",
2424
read_only: false,
2525
}
2626

27-
traction_wheel_track:
27+
traction_track_width:
2828
{
2929
type: double,
3030
default_value: 0.0,

ackermann_steering_controller/test/ackermann_steering_controller_params.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,5 +9,5 @@ test_ackermann_steering_controller:
99
steering_joints_names: [front_right_steering_joint, front_left_steering_joint]
1010

1111
wheelbase: 3.24644
12-
traction_wheel_track: 1.76868
12+
traction_track_width: 1.76868
1313
traction_wheels_radius: 0.45

ackermann_steering_controller/test/ackermann_steering_controller_preceeding_params.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,5 +9,5 @@ test_ackermann_steering_controller:
99
traction_joints_state_names: [rear_right_wheel_joint, rear_left_wheel_joint]
1010
steering_joints_state_names: [front_right_steering_joint, front_left_steering_joint]
1111
wheelbase: 3.24644
12-
traction_wheel_track: 1.76868
12+
traction_track_width: 1.76868
1313
traction_wheels_radius: 0.45

ackermann_steering_controller/test/test_ackermann_steering_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ TEST_F(AckermannSteeringControllerTest, all_parameters_set_configure_success)
3939
ASSERT_EQ(controller_->params_.position_feedback, position_feedback_);
4040
ASSERT_EQ(controller_->ackermann_params_.wheelbase, wheelbase_);
4141
ASSERT_EQ(controller_->ackermann_params_.traction_wheels_radius, traction_wheels_radius_);
42-
ASSERT_EQ(controller_->ackermann_params_.traction_wheel_track, traction_wheel_track_);
42+
ASSERT_EQ(controller_->ackermann_params_.traction_track_width, traction_track_width_);
4343
}
4444

4545
TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)

ackermann_steering_controller/test/test_ackermann_steering_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -297,7 +297,7 @@ class AckermannSteeringControllerFixture : public ::testing::Test
297297
steers_preceeding_names_[1]};
298298

299299
double wheelbase_ = 3.24644;
300-
double traction_wheel_track_ = 1.76868;
300+
double traction_track_width_ = 1.76868;
301301
double traction_wheels_radius_ = 0.45;
302302

303303
std::array<double, 4> joint_state_values_ = {{0.5, 0.5, 0.0, 0.0}};

ackermann_steering_controller/test/test_ackermann_steering_controller_preceeding.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ TEST_F(AckermannSteeringControllerTest, all_parameters_set_configure_success)
4141
ASSERT_EQ(controller_->params_.position_feedback, position_feedback_);
4242
ASSERT_EQ(controller_->ackermann_params_.wheelbase, wheelbase_);
4343
ASSERT_EQ(controller_->ackermann_params_.traction_wheels_radius, traction_wheels_radius_);
44-
ASSERT_EQ(controller_->ackermann_params_.traction_wheel_track, traction_wheel_track_);
44+
ASSERT_EQ(controller_->ackermann_params_.traction_track_width, traction_track_width_);
4545
}
4646

4747
TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)

doc/migration.rst

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,4 +29,4 @@ steering_controllers_library
2929
* *General*: Remove ``front_steering`` and use ``traction_joints_names``/``steering_joints_names`` instead of ``rear_wheels_names``/``front_wheels_names``, respectively.
3030
* *bicycle_steering_controller*: Set ``traction_wheel_radius`` instead of ``front_wheel_radius``, ``rear_wheel_radius``.
3131
* *tricycle_steering_controller*: Set ``traction_wheels_radius`` instead of ``front_wheels_radius``, ``rear_wheels_radius``.
32-
* *ackermann_steering_controller*: Set ``traction_wheels_radius`` instead of ``front_wheels_radius``, ``rear_wheels_radius``, and ``traction_wheel_track`` (and optionally ``steering_wheel_track``, if it differs) instead of ``rear_wheel_track``, ``front_wheel_track``.
32+
* *ackermann_steering_controller*: Set ``traction_wheels_radius`` instead of ``front_wheels_radius``, ``rear_wheels_radius``, and ``traction_track_width`` (and optionally ``steering_track_width``, if it differs) instead of ``rear_wheel_track``, ``front_wheel_track``.

steering_controllers_library/src/steering_odometry.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include "steering_controllers_library/steering_odometry.hpp"
2323

2424
#include <cmath>
25+
#include <iostream>
2526
#include <limits>
2627

2728
namespace steering_odometry
@@ -338,6 +339,10 @@ std::tuple<std::vector<double>, std::vector<double>> SteeringOdometry::get_comma
338339
std::atan2(numerator, denominator_first_member - denominator_second_member);
339340
steering_commands = {alpha_r, alpha_l};
340341
}
342+
std::cout << "traction_commands: " << traction_commands[0] << ", " << traction_commands[1]
343+
<< " steering_commands: " << steering_commands[0] << ", " << steering_commands[1]
344+
<< " phi: " << phi << " phi_IK: " << phi_IK << " Ws: " << Ws << std::endl
345+
<< std::endl;
341346
return std::make_tuple(traction_commands, steering_commands);
342347
}
343348
else

tricycle_steering_controller/src/tricycle_steering_controller.cpp

Lines changed: 21 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,8 @@ controller_interface::CallbackReturn TricycleSteeringController::configure_odome
3030
{
3131
tricycle_params_ = tricycle_param_listener_->get_params();
3232

33+
// TODO(anyone): Remove deprecated parameters
34+
// START OF DEPRECATED
3335
if (tricycle_params_.front_wheels_radius > 0.0)
3436
{
3537
RCLCPP_WARN(
@@ -46,11 +48,28 @@ controller_interface::CallbackReturn TricycleSteeringController::configure_odome
4648
tricycle_params_.traction_wheels_radius = tricycle_params_.rear_wheels_radius;
4749
}
4850

51+
if (tricycle_params_.wheel_track > 0.0)
52+
{
53+
RCLCPP_WARN(
54+
get_node()->get_logger(),
55+
"DEPRECATED parameter 'wheel_track', set 'traction_track_width' instead");
56+
tricycle_params_.traction_track_width = tricycle_params_.wheel_track;
57+
}
58+
59+
if (tricycle_params_.traction_track_width <= std::numeric_limits<double>::epsilon())
60+
{
61+
RCLCPP_FATAL(
62+
get_node()->get_logger(),
63+
"parameter 'traction_track_width' is not set, cannot configure odometry");
64+
return controller_interface::CallbackReturn::ERROR;
65+
}
66+
// END OF DEPRECATED
67+
4968
const double traction_wheels_radius = tricycle_params_.traction_wheels_radius;
50-
const double wheel_track = tricycle_params_.wheel_track;
69+
const double traction_track_width = tricycle_params_.traction_track_width;
5170
const double wheelbase = tricycle_params_.wheelbase;
5271

53-
odometry_.set_wheel_params(traction_wheels_radius, wheelbase, wheel_track);
72+
odometry_.set_wheel_params(traction_wheels_radius, wheelbase, traction_track_width);
5473
odometry_.set_odometry_type(steering_odometry::TRICYCLE_CONFIG);
5574

5675
set_interface_numbers(NR_STATE_ITFS, NR_CMD_ITFS, NR_REF_ITFS);

tricycle_steering_controller/src/tricycle_steering_controller.yaml

Lines changed: 12 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -3,11 +3,19 @@ tricycle_steering_controller:
33
{
44
type: double,
55
default_value: 0.0,
6-
description: "Wheel track length. For details see: https://en.wikipedia.org/wiki/Wheelbase",
6+
description: "(deprecated) Axle track, use 'traction_track_width' instead",
77
read_only: false,
8-
validation: {
9-
gt<>: [0.0]
10-
}
8+
}
9+
traction_track_width:
10+
{
11+
type: double,
12+
default_value: 0.0,
13+
description: "Axle track",
14+
read_only: false,
15+
# TODO(anyone): activate validation if wheel_track is removed
16+
# validation: {
17+
# gt<>: [0.0]
18+
# }
1119
}
1220

1321
wheelbase:

0 commit comments

Comments
 (0)