Skip to content

Commit

Permalink
Add proper deprecation warnings and backwards compatibility
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jan 3, 2025
1 parent 75fde5e commit 76962b5
Show file tree
Hide file tree
Showing 8 changed files with 146 additions and 37 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -33,26 +33,34 @@ controller_interface::CallbackReturn AckermannSteeringController::configure_odom

if (ackermann_params_.front_wheels_radius > 0.0)
{
fprintf(stderr, "DEPRECATED parameter 'front_wheels_radius'\n");
return controller_interface::CallbackReturn::ERROR;
RCLCPP_WARN(
get_node()->get_logger(),
"DEPRECATED parameter 'front_wheel_radius', set 'traction_wheels_radius' instead");
ackermann_params_.traction_wheels_radius = ackermann_params_.front_wheels_radius;
}

if (ackermann_params_.rear_wheels_radius > 0.0)
{
fprintf(stderr, "DEPRECATED parameter 'rear_wheels_radius'\n");
return controller_interface::CallbackReturn::ERROR;
RCLCPP_WARN(
get_node()->get_logger(),
"DEPRECATED parameter 'rear_wheel_radius', set 'traction_wheels_radius' instead");
ackermann_params_.traction_wheels_radius = ackermann_params_.rear_wheels_radius;
}

if (ackermann_params_.front_wheel_track > 0.0)
{
fprintf(stderr, "DEPRECATED parameter 'front_wheel_track'\n");
return controller_interface::CallbackReturn::ERROR;
RCLCPP_WARN(
get_node()->get_logger(),
"DEPRECATED parameter 'front_wheel_track', set 'traction_wheel_track' instead");
ackermann_params_.traction_wheel_track = ackermann_params_.front_wheel_track;
}

if (ackermann_params_.rear_wheel_track > 0.0)
{
fprintf(stderr, "DEPRECATED parameter 'rear_wheel_track'\n");
return controller_interface::CallbackReturn::ERROR;
RCLCPP_WARN(
get_node()->get_logger(),
"DEPRECATED parameter 'rear_wheel_track', set 'traction_wheel_track' instead");
ackermann_params_.traction_wheel_track = ackermann_params_.rear_wheel_track;
}

const double traction_wheels_radius = ackermann_params_.traction_wheels_radius;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,10 @@ ackermann_steering_controller:
default_value: 0.0,
description: "Traction wheel track length. For details see: https://en.wikipedia.org/wiki/Wheelbase",
read_only: false,
validation: {
gt<>: [0.0]
}
# TODO(anyone): activate validation if front/rear wheel track is removed
# validation: {
# gt<>: [0.0]
# }
}
front_wheel_track:
{
Expand Down Expand Up @@ -41,9 +42,10 @@ ackermann_steering_controller:
default_value: 0.0,
description: "Traction wheels radius.",
read_only: false,
validation: {
gt<>: [0.0]
}
# TODO(anyone): activate validation if front/rear wheel radius is removed
# validation: {
# gt<>: [0.0]
# }
}

front_wheels_radius:
Expand Down
12 changes: 8 additions & 4 deletions bicycle_steering_controller/src/bicycle_steering_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,14 +33,18 @@ controller_interface::CallbackReturn BicycleSteeringController::configure_odomet

if (bicycle_params_.front_wheel_radius > 0.0)
{
fprintf(stderr, "DEPRECATED parameter 'front_wheel_radius'\n");
return controller_interface::CallbackReturn::ERROR;
RCLCPP_WARN(
get_node()->get_logger(),
"DEPRECATED parameter 'front_wheel_radius', set 'traction_wheel_radius' instead");
bicycle_params_.traction_wheel_radius = bicycle_params_.front_wheel_radius;
}

if (bicycle_params_.rear_wheel_radius > 0.0)
{
fprintf(stderr, "DEPRECATED parameter 'rear_wheel_radius'\n");
return controller_interface::CallbackReturn::ERROR;
RCLCPP_WARN(
get_node()->get_logger(),
"DEPRECATED parameter 'rear_wheel_radius', set 'traction_wheel_radius' instead");
bicycle_params_.traction_wheel_radius = bicycle_params_.rear_wheel_radius;
}
const double wheelbase = bicycle_params_.wheelbase;
const double traction_wheel_radius = bicycle_params_.traction_wheel_radius;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,10 @@ bicycle_steering_controller:
default_value: 0.0,
description: "Traction wheel radius.",
read_only: false,
validation: {
gt<>: [0.0]
}
# TODO(anyone): activate validation if front/rear wheel radius is removed
# validation: {
# gt<>: [0.0]
# }
}

front_wheel_radius:
Expand Down
71 changes: 67 additions & 4 deletions steering_controllers_library/src/steering_controllers_library.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,17 +82,80 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure(
{
params_ = param_listener_->get_params();

// TODO(anyone): Remove deprecated parameters
// START OF DEPRECATED
if (!params_.front_steering)
{
RCLCPP_WARN(
get_node()->get_logger(),
"DEPRECATED parameter 'front_steering', set 'traction_joint_names' or 'steering_joint_names' "
"instead");
}

if (params_.front_wheels_names.size() > 0)
{
fprintf(stderr, "DEPRECATED parameter 'front_wheels_names'\n");
return controller_interface::CallbackReturn::ERROR;
RCLCPP_WARN(
get_node()->get_logger(),
"DEPRECATED parameter 'front_wheels_names', set 'traction_joint_names' or "
"'steering_joint_names' instead");
if (params_.front_steering)
{
params_.steering_joints_names = params_.front_wheels_names;
}
else
{
params_.traction_joints_names = params_.front_wheels_names;
}
}

if (params_.rear_wheels_names.size() > 0)
{
fprintf(stderr, "DEPRECATED parameter 'rear_wheels_names'\n");
return controller_interface::CallbackReturn::ERROR;
RCLCPP_WARN(
get_node()->get_logger(),
"DEPRECATED parameter 'rear_wheels_names', set 'traction_joint_names' or "
"'steering_joint_names' instead");
if (params_.front_steering)
{
params_.traction_joints_names = params_.rear_wheels_names;
}
else
{
params_.steering_joints_names = params_.rear_wheels_names;
}
}

if (params_.front_wheels_state_names.size() > 0)
{
RCLCPP_WARN(
get_node()->get_logger(),
"DEPRECATED parameter 'front_wheels_state_names', set 'traction_joints_state_names' or "
"'steering_joints_state_names' instead");
if (params_.front_steering)
{
params_.steering_joints_state_names = params_.front_wheels_state_names;
}
else
{
params_.traction_joints_state_names = params_.front_wheels_state_names;
}
}

if (params_.rear_wheels_state_names.size() > 0)
{
RCLCPP_WARN(
get_node()->get_logger(),
"DEPRECATED parameter 'rear_wheels_state_names', set 'traction_joints_state_names' or "
"'steering_joints_state_names' instead");
if (params_.front_steering)
{
params_.traction_joints_state_names = params_.rear_wheels_state_names;
}
else
{
params_.steering_joints_state_names = params_.rear_wheels_state_names;
}
}
// END OF DEPRECATED

odometry_.set_velocity_rolling_window_size(
static_cast<size_t>(params_.velocity_rolling_window_size));
Expand Down
36 changes: 31 additions & 5 deletions steering_controllers_library/src/steering_controllers_library.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,13 @@ steering_controllers_library:
reference_timeout: {
type: double,
default_value: 1.0,
description: "Timeout for controller references after which they will be reset. This is especially useful for controllers that can cause unwanted and dangerous behaviour if reference is not reset, e.g., velocity controllers. If value is 0 the reference is reset after each run.",
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.",
}
front_steering: {
type: bool,
read_only: true,
default_value: false,
description: "DEPRECATED: Use 'traction_joint_names' or 'steering_joint_names'"
default_value: true,
description: "DEPRECATED: Use 'traction_joint_names' or 'steering_joint_names' instead"
}

front_wheels_names: {
Expand All @@ -28,22 +28,26 @@ steering_controllers_library:
traction_joints_names: {
type: string_array,
description: "Names of wheel joints.",
default_value: [],
read_only: true,
validation: {
size_lt<>: [5],
unique<>: null,
not_empty<>: null,
# TODO(anyone): activate validation if front/rear wheel radius is removed
# not_empty<>: null,
}
}

steering_joints_names: {
type: string_array,
description: "Names of steering joints.",
default_value: [],
read_only: true,
validation: {
size_lt<>: [5],
unique<>: null,
not_empty<>: null,
# TODO(anyone): activate validation if front/rear wheel radius is removed
# not_empty<>: null,
}
}

Expand All @@ -58,6 +62,17 @@ steering_controllers_library:
}
}

rear_wheels_state_names: {
type: string_array,
description: "DEPRECATED: Use 'traction_joints_state_names' or 'steering_joints_state_names'",
default_value: [],
read_only: true,
validation: {
size_lt<>: [5],
unique<>: null,
}
}

steering_joints_state_names: {
type: string_array,
description: "(Optional) Names of steering joints to read states from. If not set joint names from 'steering_joints_names' will be used.",
Expand All @@ -69,6 +84,17 @@ steering_controllers_library:
}
}

front_wheels_state_names: {
type: string_array,
description: "DEPRECATED: Use 'traction_joints_state_names' or 'steering_joints_state_names'",
default_value: [],
read_only: true,
validation: {
size_lt<>: [5],
unique<>: null,
}
}

open_loop: {
type: bool,
default_value: false,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,14 +32,18 @@ controller_interface::CallbackReturn TricycleSteeringController::configure_odome

if (tricycle_params_.front_wheel_radius > 0.0)
{
fprintf(stderr, "DEPRECATED parameter 'front_wheel_radius'\n");
return controller_interface::CallbackReturn::ERROR;
RCLCPP_WARN(
get_node()->get_logger(),
"DEPRECATED parameter 'front_wheel_radius', set 'traction_wheels_radius' instead");
tricycle_params_.traction_wheels_radius = tricycle_params_.front_wheel_radius;
}

if (tricycle_params_.rear_wheel_radius > 0.0)
{
fprintf(stderr, "DEPRECATED parameter 'rear_wheel_radius'\n");
return controller_interface::CallbackReturn::ERROR;
RCLCPP_WARN(
get_node()->get_logger(),
"DEPRECATED parameter 'rear_wheel_radius', set 'traction_wheels_radius' instead");
tricycle_params_.traction_wheels_radius = tricycle_params_.rear_wheel_radius;
}

const double traction_wheels_radius = tricycle_params_.traction_wheels_radius;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,10 @@ tricycle_steering_controller:
default_value: 0.0,
description: "Traction wheels radius.",
read_only: false,
validation: {
gt<>: [0.0]
}
# TODO(anyone): activate validation if front/rear wheel radius is removed
# validation: {
# gt<>: [0.0]
# }
}

front_wheel_radius:
Expand Down

0 comments on commit 76962b5

Please sign in to comment.