@@ -36,6 +36,25 @@ constexpr auto DEFAULT_ODOMETRY_TOPIC = "~/odom";
3636constexpr auto DEFAULT_TRANSFORM_TOPIC = " /tf" ;
3737} // namespace
3838
39+ namespace
40+ { // utility
41+
42+ // called from RT control loop
43+ void reset_controller_reference_msg (
44+ const std::shared_ptr<geometry_msgs::msg::TwistStamped> & msg,
45+ const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node)
46+ {
47+ msg->header .stamp = node->now ();
48+ msg->twist .linear .x = std::numeric_limits<double >::quiet_NaN ();
49+ msg->twist .linear .y = std::numeric_limits<double >::quiet_NaN ();
50+ msg->twist .linear .z = std::numeric_limits<double >::quiet_NaN ();
51+ msg->twist .angular .x = std::numeric_limits<double >::quiet_NaN ();
52+ msg->twist .angular .y = std::numeric_limits<double >::quiet_NaN ();
53+ msg->twist .angular .z = std::numeric_limits<double >::quiet_NaN ();
54+ }
55+
56+ } // namespace
57+
3958namespace diff_drive_controller
4059{
4160using namespace std ::chrono_literals;
@@ -46,11 +65,11 @@ using hardware_interface::HW_IF_VELOCITY;
4665using lifecycle_msgs::msg::State;
4766
4867DiffDriveController::DiffDriveController ()
49- : controller_interface::ControllerInterface (),
68+ : controller_interface::ChainableControllerInterface (),
5069 // dummy limiter, will be created in on_configure
5170 // could be done with shared_ptr instead -> but will break ABI
52- limiter_angular_ (std::numeric_limits<double >::quiet_NaN()),
53- limiter_linear_ (std::numeric_limits<double >::quiet_NaN())
71+ limiter_linear_ (std::numeric_limits<double >::quiet_NaN()),
72+ limiter_angular_ (std::numeric_limits<double >::quiet_NaN())
5473{
5574}
5675
@@ -104,8 +123,8 @@ InterfaceConfiguration DiffDriveController::state_interface_configuration() cons
104123 return {interface_configuration_type::INDIVIDUAL, conf_names};
105124}
106125
107- controller_interface::return_type DiffDriveController::update (
108- const rclcpp::Time & time, const rclcpp::Duration & period)
126+ controller_interface::return_type DiffDriveController::update_reference_from_subscribers (
127+ const rclcpp::Time & time, const rclcpp::Duration & /* period*/ )
109128{
110129 auto logger = get_node ()->get_logger ();
111130 if (get_lifecycle_state ().id () == State::PRIMARY_STATE_INACTIVE)
@@ -118,31 +137,61 @@ controller_interface::return_type DiffDriveController::update(
118137 return controller_interface::return_type::OK;
119138 }
120139
121- // if the mutex is unable to lock, last_command_msg_ won't be updated
122- received_velocity_msg_ptr_.try_get ([this ](const std::shared_ptr<TwistStamped> & msg)
123- { last_command_msg_ = msg; });
140+ const std::shared_ptr<TwistStamped> command_msg_ptr = *(received_velocity_msg_ptr_.readFromRT ());
124141
125- if (last_command_msg_ == nullptr )
142+ if (command_msg_ptr == nullptr )
126143 {
127144 RCLCPP_WARN (logger, " Velocity message received was a nullptr." );
128145 return controller_interface::return_type::ERROR;
129146 }
130147
131- const auto age_of_last_command = time - last_command_msg_ ->header .stamp ;
148+ const auto age_of_last_command = time - command_msg_ptr ->header .stamp ;
132149 // Brake if cmd_vel has timeout, override the stored command
133150 if (age_of_last_command > cmd_vel_timeout_)
134151 {
135- last_command_msg_->twist .linear .x = 0.0 ;
136- last_command_msg_->twist .angular .z = 0.0 ;
152+ reference_interfaces_[0 ] = 0.0 ;
153+ reference_interfaces_[1 ] = 0.0 ;
154+ }
155+ else if (
156+ !std::isnan (command_msg_ptr->twist .linear .x ) && !std::isnan (command_msg_ptr->twist .angular .z ))
157+ {
158+ reference_interfaces_[0 ] = command_msg_ptr->twist .linear .x ;
159+ reference_interfaces_[1 ] = command_msg_ptr->twist .angular .z ;
160+ }
161+ else
162+ {
163+ RCLCPP_WARN (logger, " Command message contains NaNs. Not updating reference interfaces." );
164+ }
165+
166+ previous_update_timestamp_ = time;
167+
168+ return controller_interface::return_type::OK;
169+ }
170+
171+ controller_interface::return_type DiffDriveController::update_and_write_commands (
172+ const rclcpp::Time & time, const rclcpp::Duration & period)
173+ {
174+ auto logger = get_node ()->get_logger ();
175+ if (get_lifecycle_state ().id () == State::PRIMARY_STATE_INACTIVE)
176+ {
177+ if (!is_halted)
178+ {
179+ halt ();
180+ is_halted = true ;
181+ }
182+ return controller_interface::return_type::OK;
137183 }
138184
139185 // command may be limited further by SpeedLimit,
140186 // without affecting the stored twist command
141- TwistStamped command = *last_command_msg_;
142- double & linear_command = command.twist .linear .x ;
143- double & angular_command = command.twist .angular .z ;
187+ double linear_command = reference_interfaces_[0 ];
188+ double angular_command = reference_interfaces_[1 ];
144189
145- previous_update_timestamp_ = time;
190+ if (std::isnan (linear_command) || std::isnan (angular_command))
191+ {
192+ // NaNs occur on initialization when the reference interfaces are not yet set
193+ return controller_interface::return_type::OK;
194+ }
146195
147196 // Apply (possibly new) multipliers:
148197 const double wheel_separation = params_.wheel_separation_multiplier * params_.wheel_separation ;
@@ -239,22 +288,27 @@ controller_interface::return_type DiffDriveController::update(
239288 }
240289 }
241290
242- auto & last_command = previous_commands_.back ().twist ;
243- auto & second_to_last_command = previous_commands_.front ().twist ;
244- limiter_linear_.limit (
245- linear_command, last_command.linear .x , second_to_last_command.linear .x , period.seconds ());
246- limiter_angular_.limit (
247- angular_command, last_command.angular .z , second_to_last_command.angular .z , period.seconds ());
291+ double & last_linear = previous_two_commands_.back ()[0 ];
292+ double & second_to_last_linear = previous_two_commands_.front ()[0 ];
293+ double & last_angular = previous_two_commands_.back ()[1 ];
294+ double & second_to_last_angular = previous_two_commands_.front ()[1 ];
248295
249- previous_commands_.pop ();
250- previous_commands_.emplace (command);
296+ limiter_linear_.limit (linear_command, last_linear, second_to_last_linear, period.seconds ());
297+ limiter_angular_.limit (angular_command, last_angular, second_to_last_angular, period.seconds ());
298+ previous_two_commands_.pop ();
299+ previous_two_commands_.push ({{linear_command, angular_command}});
251300
252301 // Publish limited velocity
253302 if (publish_limited_velocity_ && realtime_limited_velocity_publisher_->trylock ())
254303 {
255304 auto & limited_velocity_command = realtime_limited_velocity_publisher_->msg_ ;
256305 limited_velocity_command.header .stamp = time;
257- limited_velocity_command.twist = command.twist ;
306+ limited_velocity_command.twist .linear .x = linear_command;
307+ limited_velocity_command.twist .linear .y = 0.0 ;
308+ limited_velocity_command.twist .linear .z = 0.0 ;
309+ limited_velocity_command.twist .angular .x = 0.0 ;
310+ limited_velocity_command.twist .angular .y = 0.0 ;
311+ limited_velocity_command.twist .angular .z = angular_command;
258312 realtime_limited_velocity_publisher_->unlockAndPublish ();
259313 }
260314
@@ -301,7 +355,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
301355 odometry_.setWheelParams (wheel_separation, left_wheel_radius, right_wheel_radius);
302356 odometry_.setVelocityRollingWindowSize (static_cast <size_t >(params_.velocity_rolling_window_size ));
303357
304- cmd_vel_timeout_ = std::chrono::milliseconds{ static_cast < int > (params_.cmd_vel_timeout * 1000.0 )} ;
358+ cmd_vel_timeout_ = rclcpp::Duration::from_seconds (params_.cmd_vel_timeout ) ;
305359 publish_limited_velocity_ = params_.publish_limited_velocity ;
306360
307361 // TODO(christophfroehlich) remove deprecated parameters
@@ -394,12 +448,15 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
394448 limited_velocity_publisher_);
395449 }
396450
397- last_command_msg_ = std::make_shared<TwistStamped>();
398- received_velocity_msg_ptr_.set ([this ](std::shared_ptr<TwistStamped> & stored_value)
399- { stored_value = last_command_msg_; });
400- // Fill last two commands with default constructed commands
401- previous_commands_.emplace (*last_command_msg_);
402- previous_commands_.emplace (*last_command_msg_);
451+ const int nr_ref_itfs = 2 ;
452+ reference_interfaces_.resize (nr_ref_itfs, std::numeric_limits<double >::quiet_NaN ());
453+ previous_two_commands_.push ({{0.0 , 0.0 }}); // needs zeros (not NaN) to catch early accelerations
454+ previous_two_commands_.push ({{0.0 , 0.0 }});
455+
456+ std::shared_ptr<TwistStamped> empty_msg_ptr = std::make_shared<TwistStamped>();
457+ reset_controller_reference_msg (empty_msg_ptr, get_node ());
458+ received_velocity_msg_ptr_.reset ();
459+ received_velocity_msg_ptr_.writeFromNonRT (empty_msg_ptr);
403460
404461 // initialize command subscriber
405462 velocity_command_subscriber_ = get_node ()->create_subscription <TwistStamped>(
@@ -419,8 +476,24 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
419476 " time, this message will only be shown once" );
420477 msg->header .stamp = get_node ()->get_clock ()->now ();
421478 }
422- received_velocity_msg_ptr_.set ([msg](std::shared_ptr<TwistStamped> & stored_value)
423- { stored_value = std::move (msg); });
479+
480+ const auto current_time_diff = get_node ()->now () - msg->header .stamp ;
481+
482+ if (
483+ cmd_vel_timeout_ == rclcpp::Duration::from_seconds (0.0 ) ||
484+ current_time_diff < cmd_vel_timeout_)
485+ {
486+ received_velocity_msg_ptr_.writeFromNonRT (msg);
487+ }
488+ else
489+ {
490+ RCLCPP_WARN (
491+ get_node ()->get_logger (),
492+ " Ignoring the received message (timestamp %.10f) because it is older than "
493+ " the current time by %.10f seconds, which exceeds the allowed timeout (%.4f)" ,
494+ rclcpp::Time (msg->header .stamp ).seconds (), current_time_diff.seconds (),
495+ cmd_vel_timeout_.seconds ());
496+ }
424497 });
425498
426499 // initialize odometry publisher and message
@@ -498,6 +571,9 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
498571controller_interface::CallbackReturn DiffDriveController::on_activate (
499572 const rclcpp_lifecycle::State &)
500573{
574+ // Set default value in command
575+ reset_controller_reference_msg (*(received_velocity_msg_ptr_.readFromRT ()), get_node ());
576+
501577 const auto left_result =
502578 configure_side (" left" , params_.left_wheel_names , registered_left_wheel_handles_);
503579 const auto right_result =
@@ -546,6 +622,7 @@ controller_interface::CallbackReturn DiffDriveController::on_cleanup(
546622 {
547623 return controller_interface::CallbackReturn::ERROR;
548624 }
625+ received_velocity_msg_ptr_.reset ();
549626
550627 return controller_interface::CallbackReturn::SUCCESS;
551628}
@@ -564,16 +641,16 @@ bool DiffDriveController::reset()
564641 odometry_.resetOdometry ();
565642
566643 // release the old queue
567- std::queue<TwistStamped > empty;
568- std::swap (previous_commands_ , empty);
644+ std::queue<std::array< double , 2 > > empty;
645+ std::swap (previous_two_commands_ , empty);
569646
570647 registered_left_wheel_handles_.clear ();
571648 registered_right_wheel_handles_.clear ();
572649
573650 subscriber_is_active_ = false ;
574651 velocity_command_subscriber_.reset ();
575652
576- received_velocity_msg_ptr_.set ( nullptr );
653+ received_velocity_msg_ptr_.reset ( );
577654 is_halted = false ;
578655 return true ;
579656}
@@ -643,9 +720,35 @@ controller_interface::CallbackReturn DiffDriveController::configure_side(
643720
644721 return controller_interface::CallbackReturn::SUCCESS;
645722}
723+
724+ bool DiffDriveController::on_set_chained_mode (bool chained_mode)
725+ {
726+ // Always accept switch to/from chained mode
727+ return true || chained_mode;
728+ }
729+
730+ std::vector<hardware_interface::CommandInterface>
731+ DiffDriveController::on_export_reference_interfaces ()
732+ {
733+ const int nr_ref_itfs = 2 ;
734+ reference_interfaces_.resize (nr_ref_itfs, std::numeric_limits<double >::quiet_NaN ());
735+ std::vector<hardware_interface::CommandInterface> reference_interfaces;
736+ reference_interfaces.reserve (nr_ref_itfs);
737+
738+ reference_interfaces.push_back (hardware_interface::CommandInterface (
739+ get_node ()->get_name (), std::string (" linear/" ) + hardware_interface::HW_IF_VELOCITY,
740+ &reference_interfaces_[0 ]));
741+
742+ reference_interfaces.push_back (hardware_interface::CommandInterface (
743+ get_node ()->get_name (), std::string (" angular/" ) + hardware_interface::HW_IF_VELOCITY,
744+ &reference_interfaces_[1 ]));
745+
746+ return reference_interfaces;
747+ }
748+
646749} // namespace diff_drive_controller
647750
648751#include " class_loader/register_macro.hpp"
649752
650753CLASS_LOADER_REGISTER_CLASS (
651- diff_drive_controller::DiffDriveController, controller_interface::ControllerInterface )
754+ diff_drive_controller::DiffDriveController, controller_interface::ChainableControllerInterface )
0 commit comments