Skip to content

Commit e0b929b

Browse files
authored
Fix SpeedLimiter Constructor regression (#1478)
1 parent ba7c1dd commit e0b929b

File tree

3 files changed

+17
-24
lines changed

3 files changed

+17
-24
lines changed

diff_drive_controller/include/diff_drive_controller/diff_drive_controller.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -120,8 +120,8 @@ class DiffDriveController : public controller_interface::ControllerInterface
120120
std::queue<TwistStamped> previous_commands_; // last two commands
121121

122122
// speed limiters
123-
SpeedLimiter limiter_linear_;
124-
SpeedLimiter limiter_angular_;
123+
std::unique_ptr<SpeedLimiter> limiter_linear_;
124+
std::unique_ptr<SpeedLimiter> limiter_angular_;
125125

126126
bool publish_limited_velocity_ = false;
127127
std::shared_ptr<rclcpp::Publisher<TwistStamped>> limited_velocity_publisher_ = nullptr;

diff_drive_controller/include/diff_drive_controller/speed_limiter.hpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ class SpeedLimiter
4040
* \param [in] min_jerk Minimum jerk [m/s^3], usually <= 0
4141
* \param [in] max_jerk Maximum jerk [m/s^3], usually >= 0
4242
*/
43-
[[deprecated]] SpeedLimiter(
43+
[[deprecated]] explicit SpeedLimiter(
4444
bool has_velocity_limits = true, bool has_acceleration_limits = true,
4545
bool has_jerk_limits = true, double min_velocity = std::numeric_limits<double>::quiet_NaN(),
4646
double max_velocity = std::numeric_limits<double>::quiet_NaN(),
@@ -79,16 +79,16 @@ class SpeedLimiter
7979
* >= 0
8080
* \param [in] min_jerk Minimum jerk [m/s^3], usually <= 0
8181
* \param [in] max_jerk Maximum jerk [m/s^3], usually >= 0
82+
*
83+
* \note
84+
* If max_* values are NAN, the respective limit is deactivated
85+
* If min_* values are NAN (unspecified), defaults to -max
86+
* If min_first_derivative_pos/max_first_derivative_neg values are NAN, symmetric limits are used
8287
*/
83-
SpeedLimiter(
84-
double min_velocity = std::numeric_limits<double>::quiet_NaN(),
85-
double max_velocity = std::numeric_limits<double>::quiet_NaN(),
86-
double max_acceleration_reverse = std::numeric_limits<double>::quiet_NaN(),
87-
double max_acceleration = std::numeric_limits<double>::quiet_NaN(),
88-
double max_deceleration = std::numeric_limits<double>::quiet_NaN(),
89-
double max_deceleration_reverse = std::numeric_limits<double>::quiet_NaN(),
90-
double min_jerk = std::numeric_limits<double>::quiet_NaN(),
91-
double max_jerk = std::numeric_limits<double>::quiet_NaN())
88+
explicit SpeedLimiter(
89+
double min_velocity, double max_velocity, double max_acceleration_reverse,
90+
double max_acceleration, double max_deceleration, double max_deceleration_reverse,
91+
double min_jerk, double max_jerk)
9292
{
9393
speed_limiter_ = control_toolbox::RateLimiter<double>(
9494
min_velocity, max_velocity, max_acceleration_reverse, max_acceleration, max_deceleration,

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 5 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -45,14 +45,7 @@ using hardware_interface::HW_IF_POSITION;
4545
using hardware_interface::HW_IF_VELOCITY;
4646
using lifecycle_msgs::msg::State;
4747

48-
DiffDriveController::DiffDriveController()
49-
: controller_interface::ControllerInterface(),
50-
// dummy limiter, will be created in on_configure
51-
// could be done with shared_ptr instead -> but will break ABI
52-
limiter_angular_(std::numeric_limits<double>::quiet_NaN()),
53-
limiter_linear_(std::numeric_limits<double>::quiet_NaN())
54-
{
55-
}
48+
DiffDriveController::DiffDriveController() : controller_interface::ControllerInterface() {}
5649

5750
const char * DiffDriveController::feedback_type() const
5851
{
@@ -241,9 +234,9 @@ controller_interface::return_type DiffDriveController::update(
241234

242235
auto & last_command = previous_commands_.back().twist;
243236
auto & second_to_last_command = previous_commands_.front().twist;
244-
limiter_linear_.limit(
237+
limiter_linear_->limit(
245238
linear_command, last_command.linear.x, second_to_last_command.linear.x, period.seconds());
246-
limiter_angular_.limit(
239+
limiter_angular_->limit(
247240
angular_command, last_command.angular.z, second_to_last_command.angular.z, period.seconds());
248241

249242
previous_commands_.pop();
@@ -365,13 +358,13 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
365358
std::numeric_limits<double>::quiet_NaN();
366359
}
367360
// END DEPRECATED
368-
limiter_linear_ = SpeedLimiter(
361+
limiter_linear_ = std::make_unique<SpeedLimiter>(
369362
params_.linear.x.min_velocity, params_.linear.x.max_velocity,
370363
params_.linear.x.max_acceleration_reverse, params_.linear.x.max_acceleration,
371364
params_.linear.x.max_deceleration, params_.linear.x.max_deceleration_reverse,
372365
params_.linear.x.min_jerk, params_.linear.x.max_jerk);
373366

374-
limiter_angular_ = SpeedLimiter(
367+
limiter_angular_ = std::make_unique<SpeedLimiter>(
375368
params_.angular.z.min_velocity, params_.angular.z.max_velocity,
376369
params_.angular.z.max_acceleration_reverse, params_.angular.z.max_acceleration,
377370
params_.angular.z.max_deceleration, params_.angular.z.max_deceleration_reverse,

0 commit comments

Comments
 (0)