From 132650547d9d2e4ac810ea126910bbd1f02d0db0 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Tue, 28 May 2024 19:17:17 +0000 Subject: [PATCH] Fix deprecation warning --- .../src/steering_controllers_library.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/steering_controllers_library/src/steering_controllers_library.cpp b/steering_controllers_library/src/steering_controllers_library.cpp index 9bf9fa51d6..167ee6aecf 100644 --- a/steering_controllers_library/src/steering_controllers_library.cpp +++ b/steering_controllers_library/src/steering_controllers_library.cpp @@ -116,15 +116,15 @@ 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)); } else { + RCLCPP_WARN( + get_node()->get_logger(), + "[Deprecated] Using geometry_msgs::msg::Twist instead of TwistStamped is deprecated."); ref_subscriber_unstamped_ = get_node()->create_subscription( "~/reference_unstamped", subscribers_qos, std::bind(