Skip to content

Cleanup deprecations in diff_drive_controller #1653

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 7 commits into from
May 17, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -28,45 +28,6 @@ namespace diff_drive_controller
class SpeedLimiter
{
public:
/**
* \brief Constructor
* \param [in] has_velocity_limits if true, applies velocity limits
* \param [in] has_acceleration_limits if true, applies acceleration limits
* \param [in] has_jerk_limits if true, applies jerk limits
* \param [in] min_velocity Minimum velocity [m/s], usually <= 0
* \param [in] max_velocity Maximum velocity [m/s], usually >= 0
* \param [in] max_deceleration Maximum deceleration [m/s^2], usually <= 0
* \param [in] max_acceleration Maximum acceleration [m/s^2], usually >= 0
* \param [in] min_jerk Minimum jerk [m/s^3], usually <= 0
* \param [in] max_jerk Maximum jerk [m/s^3], usually >= 0
*/
[[deprecated]] explicit SpeedLimiter(
bool has_velocity_limits = true, bool has_acceleration_limits = true,
bool has_jerk_limits = true, double min_velocity = std::numeric_limits<double>::quiet_NaN(),
double max_velocity = std::numeric_limits<double>::quiet_NaN(),
double max_deceleration = std::numeric_limits<double>::quiet_NaN(),
double max_acceleration = std::numeric_limits<double>::quiet_NaN(),
double min_jerk = std::numeric_limits<double>::quiet_NaN(),
double max_jerk = std::numeric_limits<double>::quiet_NaN())
{
if (!has_velocity_limits)
{
min_velocity = max_velocity = std::numeric_limits<double>::quiet_NaN();
}
if (!has_acceleration_limits)
{
max_deceleration = max_acceleration = std::numeric_limits<double>::quiet_NaN();
}
if (!has_jerk_limits)
{
min_jerk = max_jerk = std::numeric_limits<double>::quiet_NaN();
}
speed_limiter_ = control_toolbox::RateLimiter<double>(
min_velocity, max_velocity, max_deceleration, max_acceleration,
std::numeric_limits<double>::quiet_NaN(), std::numeric_limits<double>::quiet_NaN(), min_jerk,
max_jerk);
}

/**
* \brief Constructor
* \param [in] min_velocity Minimum velocity [m/s], usually <= 0
Expand Down
61 changes: 0 additions & 61 deletions diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -337,67 +337,6 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
const int nr_ref_itfs = 2;
reference_interfaces_.resize(nr_ref_itfs, std::numeric_limits<double>::quiet_NaN());

// TODO(christophfroehlich) remove deprecated parameters
// START DEPRECATED
if (!params_.linear.x.has_velocity_limits)
{
RCLCPP_WARN(
logger,
"[deprecated] has_velocity_limits parameter is deprecated, instead set the respective limits "
"to NAN");
params_.linear.x.min_velocity = params_.linear.x.max_velocity =
std::numeric_limits<double>::quiet_NaN();
}
if (!params_.linear.x.has_acceleration_limits)
{
RCLCPP_WARN(
logger,
"[deprecated] has_acceleration_limits parameter is deprecated, instead set the respective "
"limits to "
"NAN");
params_.linear.x.max_deceleration = params_.linear.x.max_acceleration =
params_.linear.x.max_deceleration_reverse = params_.linear.x.max_acceleration_reverse =
std::numeric_limits<double>::quiet_NaN();
}
if (!params_.linear.x.has_jerk_limits)
{
RCLCPP_WARN(
logger,
"[deprecated] has_jerk_limits parameter is deprecated, instead set the respective limits to "
"NAN");
params_.linear.x.min_jerk = params_.linear.x.max_jerk =
std::numeric_limits<double>::quiet_NaN();
}
if (!params_.angular.z.has_velocity_limits)
{
RCLCPP_WARN(
logger,
"[deprecated] has_velocity_limits parameter is deprecated, instead set the respective limits "
"to NAN");
params_.angular.z.min_velocity = params_.angular.z.max_velocity =
std::numeric_limits<double>::quiet_NaN();
}
if (!params_.angular.z.has_acceleration_limits)
{
RCLCPP_WARN(
logger,
"[deprecated] has_acceleration_limits parameter is deprecated, instead set the respective "
"limits to "
"NAN");
params_.angular.z.max_deceleration = params_.angular.z.max_acceleration =
params_.angular.z.max_deceleration_reverse = params_.angular.z.max_acceleration_reverse =
std::numeric_limits<double>::quiet_NaN();
}
if (!params_.angular.z.has_jerk_limits)
{
RCLCPP_WARN(
logger,
"[deprecated] has_jerk_limits parameter is deprecated, instead set the respective limits to "
"NAN");
params_.angular.z.min_jerk = params_.angular.z.max_jerk =
std::numeric_limits<double>::quiet_NaN();
}
// END DEPRECATED
limiter_linear_ = std::make_unique<SpeedLimiter>(
params_.linear.x.min_velocity, params_.linear.x.max_velocity,
params_.linear.x.max_acceleration_reverse, params_.linear.x.max_acceleration,
Expand Down
40 changes: 0 additions & 40 deletions diff_drive_controller/src/diff_drive_controller_parameter.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -113,21 +113,6 @@ diff_drive_controller:
}
linear:
x:
has_velocity_limits: {
type: bool,
default_value: true,
description: "deprecated, set the respective limits to ``.NAN`` for deactivation"
}
has_acceleration_limits: {
type: bool,
default_value: true,
description: "deprecated, set the respective limits to ``.NAN`` for deactivation"
}
has_jerk_limits: {
type: bool,
default_value: true,
description: "deprecated, set the respective limits to ``.NAN`` for deactivation"
}
max_velocity: {
type: double,
default_value: .NAN,
Expand Down Expand Up @@ -158,11 +143,6 @@ diff_drive_controller:
"control_filters::lt_eq_or_nan<>": [0.0]
}
}
min_acceleration: {
type: double,
default_value: .NAN,
description: "deprecated, use max_deceleration"
}
max_acceleration_reverse: {
type: double,
default_value: .NAN,
Expand Down Expand Up @@ -195,21 +175,6 @@ diff_drive_controller:
}
angular:
z:
has_velocity_limits: {
type: bool,
default_value: true,
description: "deprecated, set the respective limits to ``.NAN`` for deactivation"
}
has_acceleration_limits: {
type: bool,
default_value: true,
description: "deprecated, set the respective limits to ``.NAN`` for deactivation"
}
has_jerk_limits: {
type: bool,
default_value: true,
description: "deprecated, set the respective limits to ``.NAN`` for deactivation"
}
max_velocity: {
type: double,
default_value: .NAN,
Expand Down Expand Up @@ -240,11 +205,6 @@ diff_drive_controller:
"control_filters::lt_eq_or_nan<>": [0.0]
}
}
min_acceleration: {
type: double,
default_value: .NAN,
description: "deprecated, use max_deceleration"
}
max_acceleration_reverse: {
type: double,
default_value: .NAN,
Expand Down
5 changes: 4 additions & 1 deletion doc/migration.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,8 @@

Migration Guides: Jazzy to Kilted
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

This list summarizes important changes between Jazzy (previous) and Kilted (current) releases, where changes to user code might be necessary.

diff_drive_controller
*****************************
* Parameters ``has_velocity_limits``, ``has_acceleration_limits``, and ``has_jerk_limits`` are removed. Instead, set the respective limits to ``.NAN``. (`#1653 <https://github.com/ros-controls/ros2_controllers/pull/1653>`_).
1 change: 0 additions & 1 deletion doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,4 @@

Release Notes: Jazzy to Kilted
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

This list summarizes the changes between Jazzy (previous) and Kilted (current) releases.
Loading