Skip to content

Commit 3a96256

Browse files
Diff_drive: Use lock_free queue instead of RealtimeBox
1 parent 67096bd commit 3a96256

File tree

3 files changed

+14
-13
lines changed

3 files changed

+14
-13
lines changed

diff_drive_controller/include/diff_drive_controller/diff_drive_controller.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@
3232
#include "nav_msgs/msg/odometry.hpp"
3333
#include "odometry.hpp"
3434
#include "rclcpp_lifecycle/state.hpp"
35-
#include "realtime_tools/realtime_box.hpp"
35+
#include "realtime_tools/lock_free_queue.hpp"
3636
#include "realtime_tools/realtime_publisher.hpp"
3737
#include "tf2_msgs/msg/tf_message.hpp"
3838

@@ -41,6 +41,7 @@
4141

4242
namespace diff_drive_controller
4343
{
44+
using realtime_tools::LockFreeSPSCQueue;
4445
class DiffDriveController : public controller_interface::ControllerInterface
4546
{
4647
using TwistStamped = geometry_msgs::msg::TwistStamped;
@@ -114,7 +115,7 @@ class DiffDriveController : public controller_interface::ControllerInterface
114115
bool subscriber_is_active_ = false;
115116
rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ = nullptr;
116117

117-
realtime_tools::RealtimeBox<std::shared_ptr<TwistStamped>> received_velocity_msg_ptr_{nullptr};
118+
LockFreeSPSCQueue<std::shared_ptr<TwistStamped>, 10> received_velocity_msg_ptr_;
118119
std::shared_ptr<TwistStamped> last_command_msg_;
119120

120121
std::queue<TwistStamped> previous_commands_; // last two commands

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -118,10 +118,8 @@ controller_interface::return_type DiffDriveController::update(
118118
return controller_interface::return_type::OK;
119119
}
120120

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_);
125123
if (last_command_msg_ == nullptr)
126124
{
127125
RCLCPP_WARN(logger, "Velocity message received was a nullptr.");
@@ -395,8 +393,11 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
395393
}
396394

397395
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+
}
400401
// Fill last two commands with default constructed commands
401402
previous_commands_.emplace(*last_command_msg_);
402403
previous_commands_.emplace(*last_command_msg_);
@@ -419,8 +420,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
419420
"time, this message will only be shown once");
420421
msg->header.stamp = get_node()->get_clock()->now();
421422
}
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));
424424
});
425425

426426
// initialize odometry publisher and message
@@ -573,7 +573,8 @@ bool DiffDriveController::reset()
573573
subscriber_is_active_ = false;
574574
velocity_command_subscriber_.reset();
575575

576-
received_velocity_msg_ptr_.set(nullptr);
576+
std::shared_ptr<TwistStamped> dummy;
577+
(void)received_velocity_msg_ptr_.get_latest(dummy);
577578
is_halted = false;
578579
return true;
579580
}

diff_drive_controller/test/test_diff_drive_controller.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -48,8 +48,7 @@ class TestableDiffDriveController : public diff_drive_controller::DiffDriveContr
4848
std::shared_ptr<geometry_msgs::msg::TwistStamped> getLastReceivedTwist()
4949
{
5050
std::shared_ptr<geometry_msgs::msg::TwistStamped> ret;
51-
received_velocity_msg_ptr_.get(
52-
[&ret](const std::shared_ptr<geometry_msgs::msg::TwistStamped> & msg) { ret = msg; });
51+
(void)received_velocity_msg_ptr_.get_latest(ret);
5352
return ret;
5453
}
5554

0 commit comments

Comments
 (0)