From f3920d33ebb31d5461939f6f5ed25ed200c2d96f Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Thu, 4 Apr 2024 22:33:58 +0000 Subject: [PATCH] Deprecate also for steering_controllers --- steering_controllers_library/doc/userdoc.rst | 5 +---- .../src/steering_controllers_library.cpp | 3 +++ .../src/steering_controllers_library.yaml | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/steering_controllers_library/doc/userdoc.rst b/steering_controllers_library/doc/userdoc.rst index df3d1529d0..0155bc5fd8 100644 --- a/steering_controllers_library/doc/userdoc.rst +++ b/steering_controllers_library/doc/userdoc.rst @@ -13,7 +13,7 @@ Nomenclature used for the controller is used from `wikipedia /reference [geometry_msgs/msg/TwistStamped] - If parameter ``use_stamped_vel`` is ``true``. -- /reference_unstamped [geometry_msgs/msg/Twist] - If parameter ``use_stamped_vel`` is ``false``. Publishers ,,,,,,,,,,, diff --git a/steering_controllers_library/src/steering_controllers_library.cpp b/steering_controllers_library/src/steering_controllers_library.cpp index eb497ebb3d..9bf9fa51d6 100644 --- a/steering_controllers_library/src/steering_controllers_library.cpp +++ b/steering_controllers_library/src/steering_controllers_library.cpp @@ -116,6 +116,9 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( ref_timeout_ = rclcpp::Duration::from_seconds(params_.reference_timeout); if (params_.use_stamped_vel) { + RCLCPP_WARN( + get_node()->get_logger(), + "[Deprecated] Using geometry_msgs::msg::Twist instead of TwistStamped is deprecated."); ref_subscriber_twist_ = get_node()->create_subscription( "~/reference", subscribers_qos, std::bind(&SteeringControllersLibrary::reference_callback, this, std::placeholders::_1)); diff --git a/steering_controllers_library/src/steering_controllers_library.yaml b/steering_controllers_library/src/steering_controllers_library.yaml index a9f7fa75fb..b18cac5ae1 100644 --- a/steering_controllers_library/src/steering_controllers_library.yaml +++ b/steering_controllers_library/src/steering_controllers_library.yaml @@ -116,7 +116,7 @@ steering_controllers_library: use_stamped_vel: { type: bool, default_value: false, - description: "Choice of vel type, if use_stamped_vel is false then ``geometry_msgs::msg::Twist`` is taken as vel msg type, if + description: "(Deprecated) Choice of vel type, if use_stamped_vel is false then ``geometry_msgs::msg::Twist`` is taken as vel msg type, if use_stamped_vel is true then ``geometry_msgs::msg::TwistStamped`` is taken as vel msg type", read_only: false, }