@@ -111,7 +111,7 @@ controller_interface::return_type DiffDriveController::update(
111111 return controller_interface::return_type::OK;
112112 }
113113
114- std::shared_ptr<Twist > last_command_msg;
114+ std::shared_ptr<TwistStamped > last_command_msg;
115115 received_velocity_msg_ptr_.get (last_command_msg);
116116
117117 if (last_command_msg == nullptr )
@@ -130,7 +130,7 @@ controller_interface::return_type DiffDriveController::update(
130130
131131 // command may be limited further by SpeedLimit,
132132 // without affecting the stored twist command
133- Twist command = *last_command_msg;
133+ TwistStamped command = *last_command_msg;
134134 double & linear_command = command.twist .linear .x ;
135135 double & angular_command = command.twist .angular .z ;
136136
@@ -318,23 +318,24 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
318318
319319 if (publish_limited_velocity_)
320320 {
321- limited_velocity_publisher_ =
322- get_node ()-> create_publisher <Twist>( DEFAULT_COMMAND_OUT_TOPIC, rclcpp::SystemDefaultsQoS ());
321+ limited_velocity_publisher_ = get_node ()-> create_publisher <TwistStamped>(
322+ DEFAULT_COMMAND_OUT_TOPIC, rclcpp::SystemDefaultsQoS ());
323323 realtime_limited_velocity_publisher_ =
324- std::make_shared<realtime_tools::RealtimePublisher<Twist>>(limited_velocity_publisher_);
324+ std::make_shared<realtime_tools::RealtimePublisher<TwistStamped>>(
325+ limited_velocity_publisher_);
325326 }
326327
327- const Twist empty_twist;
328- received_velocity_msg_ptr_.set (std::make_shared<Twist >(empty_twist));
328+ const TwistStamped empty_twist;
329+ received_velocity_msg_ptr_.set (std::make_shared<TwistStamped >(empty_twist));
329330
330331 // Fill last two commands with default constructed commands
331332 previous_commands_.emplace (empty_twist);
332333 previous_commands_.emplace (empty_twist);
333334
334335 // initialize command subscriber
335- velocity_command_subscriber_ = get_node ()->create_subscription <Twist >(
336+ velocity_command_subscriber_ = get_node ()->create_subscription <TwistStamped >(
336337 DEFAULT_COMMAND_TOPIC, rclcpp::SystemDefaultsQoS (),
337- [this ](const std::shared_ptr<Twist > msg) -> void
338+ [this ](const std::shared_ptr<TwistStamped > msg) -> void
338339 {
339340 if (!subscriber_is_active_)
340341 {
@@ -475,7 +476,7 @@ controller_interface::CallbackReturn DiffDriveController::on_cleanup(
475476 return controller_interface::CallbackReturn::ERROR;
476477 }
477478
478- received_velocity_msg_ptr_.set (std::make_shared<Twist >());
479+ received_velocity_msg_ptr_.set (std::make_shared<TwistStamped >());
479480 return controller_interface::CallbackReturn::SUCCESS;
480481}
481482
@@ -493,7 +494,7 @@ bool DiffDriveController::reset()
493494 odometry_.resetOdometry ();
494495
495496 // release the old queue
496- std::queue<Twist > empty;
497+ std::queue<TwistStamped > empty;
497498 std::swap (previous_commands_, empty);
498499
499500 registered_left_wheel_handles_.clear ();
0 commit comments