Skip to content

Commit

Permalink
Fix deprecation warning (#1155)
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jun 3, 2024
1 parent 9424a78 commit 94149be
Showing 1 changed file with 3 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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<ControllerTwistReferenceMsg>(
"~/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<geometry_msgs::msg::Twist>(
"~/reference_unstamped", subscribers_qos,
std::bind(
Expand Down

0 comments on commit 94149be

Please sign in to comment.