From 89b4db34cc87766038957bea687ac58ef882d2fa Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Fri, 6 Dec 2024 19:51:37 +0100 Subject: [PATCH] Apply suggestions from code review Co-authored-by: Sai Kishor Kothakota --- .../include/diff_drive_controller/speed_limiter.hpp | 3 --- diff_drive_controller/src/diff_drive_controller.cpp | 12 ++++++------ 2 files changed, 6 insertions(+), 9 deletions(-) diff --git a/diff_drive_controller/include/diff_drive_controller/speed_limiter.hpp b/diff_drive_controller/include/diff_drive_controller/speed_limiter.hpp index 63745b1810..4fa08fcdba 100644 --- a/diff_drive_controller/include/diff_drive_controller/speed_limiter.hpp +++ b/diff_drive_controller/include/diff_drive_controller/speed_limiter.hpp @@ -69,9 +69,6 @@ class SpeedLimiter /** * \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_acceleration_reverse Maximum acceleration in reverse direction [m/s^2], usually diff --git a/diff_drive_controller/src/diff_drive_controller.cpp b/diff_drive_controller/src/diff_drive_controller.cpp index 937e8a93d9..a6620e8a25 100644 --- a/diff_drive_controller/src/diff_drive_controller.cpp +++ b/diff_drive_controller/src/diff_drive_controller.cpp @@ -310,7 +310,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure( { RCLCPP_WARN( logger, - "[deprecated] has_velocity_limits parameter is deprecated. Set the respective limits to NAN"); + "[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::quiet_NaN(); } @@ -318,7 +318,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure( { RCLCPP_WARN( logger, - "[deprecated] has_acceleration_limits parameter is deprecated. Set the respective limits to " + "[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 = @@ -328,7 +328,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure( { RCLCPP_WARN( logger, - "[deprecated] has_jerk_limits parameter is deprecated. Set the respective limits to NAN"); + "[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::quiet_NaN(); } @@ -336,7 +336,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure( { RCLCPP_WARN( logger, - "[deprecated] has_velocity_limits parameter is deprecated. Set the respective limits to NAN"); + "[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::quiet_NaN(); } @@ -344,7 +344,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure( { RCLCPP_WARN( logger, - "[deprecated] has_acceleration_limits parameter is deprecated. Set the respective limits to " + "[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 = @@ -354,7 +354,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure( { RCLCPP_WARN( logger, - "[deprecated] has_jerk_limits parameter is deprecated. Set the respective limits to NAN"); + "[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::quiet_NaN(); }