@@ -45,7 +45,7 @@ using hardware_interface::HW_IF_POSITION;
4545using  hardware_interface::HW_IF_VELOCITY;
4646using  lifecycle_msgs::msg::State;
4747
48- DiffDriveController::DiffDriveController () : controller_interface::ControllerInterface () {}
48+ DiffDriveController::DiffDriveController () : controller_interface::ChainableControllerInterface () {}
4949
5050const  char  * DiffDriveController::feedback_type () const 
5151{
@@ -97,8 +97,8 @@ InterfaceConfiguration DiffDriveController::state_interface_configuration() cons
9797  return  {interface_configuration_type::INDIVIDUAL, conf_names};
9898}
9999
100- controller_interface::return_type DiffDriveController::update  (
101-   const  rclcpp::Time & time, const  rclcpp::Duration & period)
100+ controller_interface::return_type DiffDriveController::update_reference_from_subscribers  (
101+   const  rclcpp::Time & time, const  rclcpp::Duration & /* period*/ 
102102{
103103  auto  logger = get_node ()->get_logger ();
104104  if  (get_lifecycle_state ().id () == State::PRIMARY_STATE_INACTIVE)
@@ -111,31 +111,64 @@ controller_interface::return_type DiffDriveController::update(
111111    return  controller_interface::return_type::OK;
112112  }
113113
114-   //  if the mutex is unable to lock, last_command_msg_ won't be updated
115-   received_velocity_msg_ptr_.try_get ([this ](const  std::shared_ptr<TwistStamped> & msg)
116-                                      { last_command_msg_ = msg; });
114+   const  std::shared_ptr<TwistStamped> command_msg_ptr = *(received_velocity_msg_ptr_.readFromRT ());
117115
118-   if  (last_command_msg_  == nullptr )
116+   if  (command_msg_ptr  == nullptr )
119117  {
120118    RCLCPP_WARN (logger, " Velocity message received was a nullptr." 
121119    return  controller_interface::return_type::ERROR;
122120  }
123121
124-   const  auto  age_of_last_command = time - last_command_msg_ ->header .stamp ;
122+   const  auto  age_of_last_command = time - command_msg_ptr ->header .stamp ;
125123  //  Brake if cmd_vel has timeout, override the stored command
126124  if  (age_of_last_command > cmd_vel_timeout_)
127125  {
128-     last_command_msg_->twist .linear .x  = 0.0 ;
129-     last_command_msg_->twist .angular .z  = 0.0 ;
126+     reference_interfaces_[0 ] = 0.0 ;
127+     reference_interfaces_[1 ] = 0.0 ;
128+   }
129+   else  if  (
130+     std::isfinite (command_msg_ptr->twist .linear .x ) &&
131+     std::isfinite (command_msg_ptr->twist .angular .z ))
132+   {
133+     reference_interfaces_[0 ] = command_msg_ptr->twist .linear .x ;
134+     reference_interfaces_[1 ] = command_msg_ptr->twist .angular .z ;
135+   }
136+   else 
137+   {
138+     RCLCPP_WARN_SKIPFIRST_THROTTLE (
139+       logger, *get_node ()->get_clock (), cmd_vel_timeout_.seconds () * 1000 ,
140+       " Command message contains NaNs. Not updating reference interfaces." 
141+   }
142+ 
143+   previous_update_timestamp_ = time;
144+ 
145+   return  controller_interface::return_type::OK;
146+ }
147+ 
148+ controller_interface::return_type DiffDriveController::update_and_write_commands (
149+   const  rclcpp::Time & time, const  rclcpp::Duration & period)
150+ {
151+   auto  logger = get_node ()->get_logger ();
152+   if  (get_lifecycle_state ().id () == State::PRIMARY_STATE_INACTIVE)
153+   {
154+     if  (!is_halted)
155+     {
156+       halt ();
157+       is_halted = true ;
158+     }
159+     return  controller_interface::return_type::OK;
130160  }
131161
132162  //  command may be limited further by SpeedLimit,
133163  //  without affecting the stored twist command
134-   TwistStamped command = *last_command_msg_;
135-   double  & linear_command = command.twist .linear .x ;
136-   double  & angular_command = command.twist .angular .z ;
164+   double  linear_command = reference_interfaces_[0 ];
165+   double  angular_command = reference_interfaces_[1 ];
137166
138-   previous_update_timestamp_ = time;
167+   if  (!std::isfinite (linear_command) || !std::isfinite (angular_command))
168+   {
169+     //  NaNs occur on initialization when the reference interfaces are not yet set
170+     return  controller_interface::return_type::OK;
171+   }
139172
140173  //  Apply (possibly new) multipliers:
141174  const  double  wheel_separation = params_.wheel_separation_multiplier  * params_.wheel_separation ;
@@ -232,22 +265,27 @@ controller_interface::return_type DiffDriveController::update(
232265    }
233266  }
234267
235-   auto  & last_command = previous_commands_.back ().twist ;
236-   auto  & second_to_last_command = previous_commands_.front ().twist ;
237-   limiter_linear_->limit (
238-     linear_command, last_command.linear .x , second_to_last_command.linear .x , period.seconds ());
239-   limiter_angular_->limit (
240-     angular_command, last_command.angular .z , second_to_last_command.angular .z , period.seconds ());
268+   double  & last_linear = previous_two_commands_.back ()[0 ];
269+   double  & second_to_last_linear = previous_two_commands_.front ()[0 ];
270+   double  & last_angular = previous_two_commands_.back ()[1 ];
271+   double  & second_to_last_angular = previous_two_commands_.front ()[1 ];
241272
242-   previous_commands_.pop ();
243-   previous_commands_.emplace (command);
273+   limiter_linear_->limit (linear_command, last_linear, second_to_last_linear, period.seconds ());
274+   limiter_angular_->limit (angular_command, last_angular, second_to_last_angular, period.seconds ());
275+   previous_two_commands_.pop ();
276+   previous_two_commands_.push ({{linear_command, angular_command}});
244277
245278  //     Publish limited velocity
246279  if  (publish_limited_velocity_ && realtime_limited_velocity_publisher_->trylock ())
247280  {
248281    auto  & limited_velocity_command = realtime_limited_velocity_publisher_->msg_ ;
249282    limited_velocity_command.header .stamp  = time;
250-     limited_velocity_command.twist  = command.twist ;
283+     limited_velocity_command.twist .linear .x  = linear_command;
284+     limited_velocity_command.twist .linear .y  = 0.0 ;
285+     limited_velocity_command.twist .linear .z  = 0.0 ;
286+     limited_velocity_command.twist .angular .x  = 0.0 ;
287+     limited_velocity_command.twist .angular .y  = 0.0 ;
288+     limited_velocity_command.twist .angular .z  = angular_command;
251289    realtime_limited_velocity_publisher_->unlockAndPublish ();
252290  }
253291
@@ -294,7 +332,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
294332  odometry_.setWheelParams (wheel_separation, left_wheel_radius, right_wheel_radius);
295333  odometry_.setVelocityRollingWindowSize (static_cast <size_t >(params_.velocity_rolling_window_size ));
296334
297-   cmd_vel_timeout_ = std::chrono::milliseconds{ static_cast < int > (params_.cmd_vel_timeout  *  1000.0 )} ;
335+   cmd_vel_timeout_ = rclcpp::Duration::from_seconds (params_.cmd_vel_timeout ) ;
298336  publish_limited_velocity_ = params_.publish_limited_velocity ;
299337
300338  //  TODO(christophfroehlich) remove deprecated parameters
@@ -387,13 +425,6 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
387425        limited_velocity_publisher_);
388426  }
389427
390-   last_command_msg_ = std::make_shared<TwistStamped>();
391-   received_velocity_msg_ptr_.set ([this ](std::shared_ptr<TwistStamped> & stored_value)
392-                                  { stored_value = last_command_msg_; });
393-   //  Fill last two commands with default constructed commands
394-   previous_commands_.emplace (*last_command_msg_);
395-   previous_commands_.emplace (*last_command_msg_);
396- 
397428  //  initialize command subscriber
398429  velocity_command_subscriber_ = get_node ()->create_subscription <TwistStamped>(
399430    DEFAULT_COMMAND_TOPIC, rclcpp::SystemDefaultsQoS (),
@@ -410,10 +441,26 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
410441          get_node ()->get_logger (),
411442          " Received TwistStamped with zero timestamp, setting it to current " 
412443          " time, this message will only be shown once" 
413-         msg->header .stamp  = get_node ()->get_clock ()->now ();
444+         msg->header .stamp  = get_node ()->now ();
445+       }
446+ 
447+       const  auto  current_time_diff = get_node ()->now () - msg->header .stamp ;
448+ 
449+       if  (
450+         cmd_vel_timeout_ == rclcpp::Duration::from_seconds (0.0 ) ||
451+         current_time_diff < cmd_vel_timeout_)
452+       {
453+         received_velocity_msg_ptr_.writeFromNonRT (msg);
454+       }
455+       else 
456+       {
457+         RCLCPP_WARN (
458+           get_node ()->get_logger (),
459+           " Ignoring the received message (timestamp %.10f) because it is older than " 
460+           " the current time by %.10f seconds, which exceeds the allowed timeout (%.4f)" 
461+           rclcpp::Time (msg->header .stamp ).seconds (), current_time_diff.seconds (),
462+           cmd_vel_timeout_.seconds ());
414463      }
415-       received_velocity_msg_ptr_.set ([msg](std::shared_ptr<TwistStamped> & stored_value)
416-                                      { stored_value = std::move (msg); });
417464    });
418465
419466  //  initialize odometry publisher and message
@@ -527,6 +574,7 @@ controller_interface::CallbackReturn DiffDriveController::on_deactivate(
527574    halt ();
528575    is_halted = true ;
529576  }
577+   reset_buffers ();
530578  registered_left_wheel_handles_.clear ();
531579  registered_right_wheel_handles_.clear ();
532580  return  controller_interface::CallbackReturn::SUCCESS;
@@ -556,21 +604,41 @@ bool DiffDriveController::reset()
556604{
557605  odometry_.resetOdometry ();
558606
559-   //  release the old queue
560-   std::queue<TwistStamped> empty;
561-   std::swap (previous_commands_, empty);
607+   reset_buffers ();
562608
563609  registered_left_wheel_handles_.clear ();
564610  registered_right_wheel_handles_.clear ();
565611
566612  subscriber_is_active_ = false ;
567613  velocity_command_subscriber_.reset ();
568614
569-   received_velocity_msg_ptr_.set (nullptr );
570615  is_halted = false ;
571616  return  true ;
572617}
573618
619+ void  DiffDriveController::reset_buffers ()
620+ {
621+   reference_interfaces_ = std::vector<double >(2 , std::numeric_limits<double >::quiet_NaN ());
622+   //  Empty out the old queue. Fill with zeros (not NaN) to catch early accelerations.
623+   std::queue<std::array<double , 2 >> empty;
624+   std::swap (previous_two_commands_, empty);
625+   previous_two_commands_.push ({{0.0 , 0.0 }});
626+   previous_two_commands_.push ({{0.0 , 0.0 }});
627+ 
628+   //  Fill RealtimeBuffer with NaNs so it will contain a known value
629+   //  but still indicate that no command has yet been sent.
630+   received_velocity_msg_ptr_.reset ();
631+   std::shared_ptr<TwistStamped> empty_msg_ptr = std::make_shared<TwistStamped>();
632+   empty_msg_ptr->header .stamp  = get_node ()->now ();
633+   empty_msg_ptr->twist .linear .x  = std::numeric_limits<double >::quiet_NaN ();
634+   empty_msg_ptr->twist .linear .y  = std::numeric_limits<double >::quiet_NaN ();
635+   empty_msg_ptr->twist .linear .z  = std::numeric_limits<double >::quiet_NaN ();
636+   empty_msg_ptr->twist .angular .x  = std::numeric_limits<double >::quiet_NaN ();
637+   empty_msg_ptr->twist .angular .y  = std::numeric_limits<double >::quiet_NaN ();
638+   empty_msg_ptr->twist .angular .z  = std::numeric_limits<double >::quiet_NaN ();
639+   received_velocity_msg_ptr_.writeFromNonRT (empty_msg_ptr);
640+ }
641+ 
574642void  DiffDriveController::halt ()
575643{
576644  const  auto  halt_wheels = [](auto  & wheel_handles)
@@ -636,9 +704,35 @@ controller_interface::CallbackReturn DiffDriveController::configure_side(
636704
637705  return  controller_interface::CallbackReturn::SUCCESS;
638706}
707+ 
708+ bool  DiffDriveController::on_set_chained_mode (bool  chained_mode)
709+ {
710+   //  Always accept switch to/from chained mode (without linting type-cast error)
711+   return  true  || chained_mode;
712+ }
713+ 
714+ std::vector<hardware_interface::CommandInterface>
715+ DiffDriveController::on_export_reference_interfaces ()
716+ {
717+   const  int  nr_ref_itfs = 2 ;
718+   reference_interfaces_.resize (nr_ref_itfs, std::numeric_limits<double >::quiet_NaN ());
719+   std::vector<hardware_interface::CommandInterface> reference_interfaces;
720+   reference_interfaces.reserve (nr_ref_itfs);
721+ 
722+   reference_interfaces.push_back (hardware_interface::CommandInterface (
723+     get_node ()->get_name (), std::string (" linear/" 
724+     &reference_interfaces_[0 ]));
725+ 
726+   reference_interfaces.push_back (hardware_interface::CommandInterface (
727+     get_node ()->get_name (), std::string (" angular/" 
728+     &reference_interfaces_[1 ]));
729+ 
730+   return  reference_interfaces;
731+ }
732+ 
639733}  //  namespace diff_drive_controller
640734
641735#include  " class_loader/register_macro.hpp" 
642736
643737CLASS_LOADER_REGISTER_CLASS (
644-   diff_drive_controller::DiffDriveController, controller_interface::ControllerInterface )
738+   diff_drive_controller::DiffDriveController, controller_interface::ChainableControllerInterface )
0 commit comments