@@ -118,10 +118,8 @@ controller_interface::return_type DiffDriveController::update(
118
118
return controller_interface::return_type::OK;
119
119
}
120
120
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; });
124
-
121
+ // last_command_msg_ won't be updated if the queue is empty
122
+ (void )received_velocity_msg_ptr_.get_latest (last_command_msg_);
125
123
if (last_command_msg_ == nullptr )
126
124
{
127
125
RCLCPP_WARN (logger, " Velocity message received was a nullptr." );
@@ -395,8 +393,11 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
395
393
}
396
394
397
395
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_; });
396
+ if (!received_velocity_msg_ptr_.bounded_push (last_command_msg_))
397
+ {
398
+ RCLCPP_ERROR (logger, " Failed to push anything to the command queue" );
399
+ return controller_interface::CallbackReturn::ERROR;
400
+ }
400
401
// Fill last two commands with default constructed commands
401
402
previous_commands_.emplace (*last_command_msg_);
402
403
previous_commands_.emplace (*last_command_msg_);
@@ -419,8 +420,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
419
420
" time, this message will only be shown once" );
420
421
msg->header .stamp = get_node ()->get_clock ()->now ();
421
422
}
422
- received_velocity_msg_ptr_.set ([msg](std::shared_ptr<TwistStamped> & stored_value)
423
- { stored_value = std::move (msg); });
423
+ (void )received_velocity_msg_ptr_.bounded_push (std::move (msg));
424
424
});
425
425
426
426
// initialize odometry publisher and message
@@ -573,7 +573,8 @@ bool DiffDriveController::reset()
573
573
subscriber_is_active_ = false ;
574
574
velocity_command_subscriber_.reset ();
575
575
576
- received_velocity_msg_ptr_.set (nullptr );
576
+ std::shared_ptr<TwistStamped> dummy;
577
+ (void )received_velocity_msg_ptr_.get_latest (dummy);
577
578
is_halted = false ;
578
579
return true ;
579
580
}
0 commit comments