@@ -111,27 +111,27 @@ controller_interface::return_type DiffDriveController::update_reference_from_sub
111
111
return controller_interface::return_type::OK;
112
112
}
113
113
114
- const std::shared_ptr<TwistStamped> command_msg_ptr = *(received_velocity_msg_ptr_. readFromRT ());
115
-
116
- if (command_msg_ptr == nullptr )
114
+ // last_command_msg_ won't be updated if the queue is empty
115
+ ( void )received_velocity_msg_ptr_. get_latest (last_command_msg_);
116
+ if (last_command_msg_ == nullptr )
117
117
{
118
118
RCLCPP_WARN (logger, " Velocity message received was a nullptr." );
119
119
return controller_interface::return_type::ERROR;
120
120
}
121
121
122
- const auto age_of_last_command = time - command_msg_ptr ->header .stamp ;
122
+ const auto age_of_last_command = time - last_command_msg_ ->header .stamp ;
123
123
// Brake if cmd_vel has timeout, override the stored command
124
124
if (age_of_last_command > cmd_vel_timeout_)
125
125
{
126
126
reference_interfaces_[0 ] = 0.0 ;
127
127
reference_interfaces_[1 ] = 0.0 ;
128
128
}
129
129
else if (
130
- std::isfinite (command_msg_ptr ->twist .linear .x ) &&
131
- std::isfinite (command_msg_ptr ->twist .angular .z ))
130
+ std::isfinite (last_command_msg_ ->twist .linear .x ) &&
131
+ std::isfinite (last_command_msg_ ->twist .angular .z ))
132
132
{
133
- reference_interfaces_[0 ] = command_msg_ptr ->twist .linear .x ;
134
- reference_interfaces_[1 ] = command_msg_ptr ->twist .angular .z ;
133
+ reference_interfaces_[0 ] = last_command_msg_ ->twist .linear .x ;
134
+ reference_interfaces_[1 ] = last_command_msg_ ->twist .angular .z ;
135
135
}
136
136
else
137
137
{
@@ -425,6 +425,13 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
425
425
limited_velocity_publisher_);
426
426
}
427
427
428
+ last_command_msg_ = std::make_shared<TwistStamped>();
429
+ if (!received_velocity_msg_ptr_.bounded_push (last_command_msg_))
430
+ {
431
+ RCLCPP_ERROR (logger, " Failed to push anything to the command queue" );
432
+ return controller_interface::CallbackReturn::ERROR;
433
+ }
434
+
428
435
// initialize command subscriber
429
436
velocity_command_subscriber_ = get_node ()->create_subscription <TwistStamped>(
430
437
DEFAULT_COMMAND_TOPIC, rclcpp::SystemDefaultsQoS (),
@@ -450,7 +457,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
450
457
cmd_vel_timeout_ == rclcpp::Duration::from_seconds (0.0 ) ||
451
458
current_time_diff < cmd_vel_timeout_)
452
459
{
453
- received_velocity_msg_ptr_.writeFromNonRT ( msg);
460
+ ( void ) received_velocity_msg_ptr_.bounded_push ( std::move ( msg) );
454
461
}
455
462
else
456
463
{
@@ -625,18 +632,8 @@ void DiffDriveController::reset_buffers()
625
632
previous_two_commands_.push ({{0.0 , 0.0 }});
626
633
previous_two_commands_.push ({{0.0 , 0.0 }});
627
634
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);
635
+ std::shared_ptr<TwistStamped> dummy;
636
+ (void )received_velocity_msg_ptr_.get_latest (dummy);
640
637
}
641
638
642
639
void DiffDriveController::halt ()
0 commit comments