@@ -45,14 +45,7 @@ using hardware_interface::HW_IF_POSITION;
4545using hardware_interface::HW_IF_VELOCITY;
4646using 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
5750const 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