Skip to content

Commit a118def

Browse files
Cleanup deprecations in diff_drive_controller (#1653)
1 parent b75fe9e commit a118def

File tree

5 files changed

+4
-142
lines changed

5 files changed

+4
-142
lines changed

diff_drive_controller/include/diff_drive_controller/speed_limiter.hpp

Lines changed: 0 additions & 39 deletions
Original file line numberDiff line numberDiff line change
@@ -28,45 +28,6 @@ namespace diff_drive_controller
2828
class SpeedLimiter
2929
{
3030
public:
31-
/**
32-
* \brief Constructor
33-
* \param [in] has_velocity_limits if true, applies velocity limits
34-
* \param [in] has_acceleration_limits if true, applies acceleration limits
35-
* \param [in] has_jerk_limits if true, applies jerk limits
36-
* \param [in] min_velocity Minimum velocity [m/s], usually <= 0
37-
* \param [in] max_velocity Maximum velocity [m/s], usually >= 0
38-
* \param [in] max_deceleration Maximum deceleration [m/s^2], usually <= 0
39-
* \param [in] max_acceleration Maximum acceleration [m/s^2], usually >= 0
40-
* \param [in] min_jerk Minimum jerk [m/s^3], usually <= 0
41-
* \param [in] max_jerk Maximum jerk [m/s^3], usually >= 0
42-
*/
43-
[[deprecated]] explicit SpeedLimiter(
44-
bool has_velocity_limits = true, bool has_acceleration_limits = true,
45-
bool has_jerk_limits = true, double min_velocity = std::numeric_limits<double>::quiet_NaN(),
46-
double max_velocity = std::numeric_limits<double>::quiet_NaN(),
47-
double max_deceleration = std::numeric_limits<double>::quiet_NaN(),
48-
double max_acceleration = std::numeric_limits<double>::quiet_NaN(),
49-
double min_jerk = std::numeric_limits<double>::quiet_NaN(),
50-
double max_jerk = std::numeric_limits<double>::quiet_NaN())
51-
{
52-
if (!has_velocity_limits)
53-
{
54-
min_velocity = max_velocity = std::numeric_limits<double>::quiet_NaN();
55-
}
56-
if (!has_acceleration_limits)
57-
{
58-
max_deceleration = max_acceleration = std::numeric_limits<double>::quiet_NaN();
59-
}
60-
if (!has_jerk_limits)
61-
{
62-
min_jerk = max_jerk = std::numeric_limits<double>::quiet_NaN();
63-
}
64-
speed_limiter_ = control_toolbox::RateLimiter<double>(
65-
min_velocity, max_velocity, max_deceleration, max_acceleration,
66-
std::numeric_limits<double>::quiet_NaN(), std::numeric_limits<double>::quiet_NaN(), min_jerk,
67-
max_jerk);
68-
}
69-
7031
/**
7132
* \brief Constructor
7233
* \param [in] min_velocity Minimum velocity [m/s], usually <= 0

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 0 additions & 61 deletions
Original file line numberDiff line numberDiff line change
@@ -337,67 +337,6 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
337337
const int nr_ref_itfs = 2;
338338
reference_interfaces_.resize(nr_ref_itfs, std::numeric_limits<double>::quiet_NaN());
339339

340-
// TODO(christophfroehlich) remove deprecated parameters
341-
// START DEPRECATED
342-
if (!params_.linear.x.has_velocity_limits)
343-
{
344-
RCLCPP_WARN(
345-
logger,
346-
"[deprecated] has_velocity_limits parameter is deprecated, instead set the respective limits "
347-
"to NAN");
348-
params_.linear.x.min_velocity = params_.linear.x.max_velocity =
349-
std::numeric_limits<double>::quiet_NaN();
350-
}
351-
if (!params_.linear.x.has_acceleration_limits)
352-
{
353-
RCLCPP_WARN(
354-
logger,
355-
"[deprecated] has_acceleration_limits parameter is deprecated, instead set the respective "
356-
"limits to "
357-
"NAN");
358-
params_.linear.x.max_deceleration = params_.linear.x.max_acceleration =
359-
params_.linear.x.max_deceleration_reverse = params_.linear.x.max_acceleration_reverse =
360-
std::numeric_limits<double>::quiet_NaN();
361-
}
362-
if (!params_.linear.x.has_jerk_limits)
363-
{
364-
RCLCPP_WARN(
365-
logger,
366-
"[deprecated] has_jerk_limits parameter is deprecated, instead set the respective limits to "
367-
"NAN");
368-
params_.linear.x.min_jerk = params_.linear.x.max_jerk =
369-
std::numeric_limits<double>::quiet_NaN();
370-
}
371-
if (!params_.angular.z.has_velocity_limits)
372-
{
373-
RCLCPP_WARN(
374-
logger,
375-
"[deprecated] has_velocity_limits parameter is deprecated, instead set the respective limits "
376-
"to NAN");
377-
params_.angular.z.min_velocity = params_.angular.z.max_velocity =
378-
std::numeric_limits<double>::quiet_NaN();
379-
}
380-
if (!params_.angular.z.has_acceleration_limits)
381-
{
382-
RCLCPP_WARN(
383-
logger,
384-
"[deprecated] has_acceleration_limits parameter is deprecated, instead set the respective "
385-
"limits to "
386-
"NAN");
387-
params_.angular.z.max_deceleration = params_.angular.z.max_acceleration =
388-
params_.angular.z.max_deceleration_reverse = params_.angular.z.max_acceleration_reverse =
389-
std::numeric_limits<double>::quiet_NaN();
390-
}
391-
if (!params_.angular.z.has_jerk_limits)
392-
{
393-
RCLCPP_WARN(
394-
logger,
395-
"[deprecated] has_jerk_limits parameter is deprecated, instead set the respective limits to "
396-
"NAN");
397-
params_.angular.z.min_jerk = params_.angular.z.max_jerk =
398-
std::numeric_limits<double>::quiet_NaN();
399-
}
400-
// END DEPRECATED
401340
limiter_linear_ = std::make_unique<SpeedLimiter>(
402341
params_.linear.x.min_velocity, params_.linear.x.max_velocity,
403342
params_.linear.x.max_acceleration_reverse, params_.linear.x.max_acceleration,

diff_drive_controller/src/diff_drive_controller_parameter.yaml

Lines changed: 0 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -113,21 +113,6 @@ diff_drive_controller:
113113
}
114114
linear:
115115
x:
116-
has_velocity_limits: {
117-
type: bool,
118-
default_value: true,
119-
description: "deprecated, set the respective limits to ``.NAN`` for deactivation"
120-
}
121-
has_acceleration_limits: {
122-
type: bool,
123-
default_value: true,
124-
description: "deprecated, set the respective limits to ``.NAN`` for deactivation"
125-
}
126-
has_jerk_limits: {
127-
type: bool,
128-
default_value: true,
129-
description: "deprecated, set the respective limits to ``.NAN`` for deactivation"
130-
}
131116
max_velocity: {
132117
type: double,
133118
default_value: .NAN,
@@ -158,11 +143,6 @@ diff_drive_controller:
158143
"control_filters::lt_eq_or_nan<>": [0.0]
159144
}
160145
}
161-
min_acceleration: {
162-
type: double,
163-
default_value: .NAN,
164-
description: "deprecated, use max_deceleration"
165-
}
166146
max_acceleration_reverse: {
167147
type: double,
168148
default_value: .NAN,
@@ -195,21 +175,6 @@ diff_drive_controller:
195175
}
196176
angular:
197177
z:
198-
has_velocity_limits: {
199-
type: bool,
200-
default_value: true,
201-
description: "deprecated, set the respective limits to ``.NAN`` for deactivation"
202-
}
203-
has_acceleration_limits: {
204-
type: bool,
205-
default_value: true,
206-
description: "deprecated, set the respective limits to ``.NAN`` for deactivation"
207-
}
208-
has_jerk_limits: {
209-
type: bool,
210-
default_value: true,
211-
description: "deprecated, set the respective limits to ``.NAN`` for deactivation"
212-
}
213178
max_velocity: {
214179
type: double,
215180
default_value: .NAN,
@@ -240,11 +205,6 @@ diff_drive_controller:
240205
"control_filters::lt_eq_or_nan<>": [0.0]
241206
}
242207
}
243-
min_acceleration: {
244-
type: double,
245-
default_value: .NAN,
246-
description: "deprecated, use max_deceleration"
247-
}
248208
max_acceleration_reverse: {
249209
type: double,
250210
default_value: .NAN,

doc/migration.rst

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,5 +2,8 @@
22

33
Migration Guides: Jazzy to Kilted
44
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
5-
65
This list summarizes important changes between Jazzy (previous) and Kilted (current) releases, where changes to user code might be necessary.
6+
7+
diff_drive_controller
8+
*****************************
9+
* 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>`_).

doc/release_notes.rst

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,5 +2,4 @@
22

33
Release Notes: Jazzy to Kilted
44
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
5-
65
This list summarizes the changes between Jazzy (previous) and Kilted (current) releases.

0 commit comments

Comments
 (0)