Skip to content

Commit e8c6bda

Browse files
Diff_drive: Use lock_free queue instead of RealtimeBox
1 parent 5c16eb6 commit e8c6bda

File tree

3 files changed

+24
-25
lines changed

3 files changed

+24
-25
lines changed

diff_drive_controller/include/diff_drive_controller/diff_drive_controller.hpp

Lines changed: 3 additions & 3 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_buffer.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

@@ -122,8 +122,8 @@ class DiffDriveController : public controller_interface::ChainableControllerInte
122122
bool subscriber_is_active_ = false;
123123
rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ = nullptr;
124124

125-
realtime_tools::RealtimeBuffer<std::shared_ptr<TwistStamped>> received_velocity_msg_ptr_{nullptr};
126-
125+
realtime_tools::LockFreeSPSCQueue<std::shared_ptr<TwistStamped>, 10> received_velocity_msg_ptr_;
126+
std::shared_ptr<TwistStamped> last_command_msg_;
127127
std::queue<std::array<double, 2>> previous_two_commands_;
128128
// speed limiters
129129
std::unique_ptr<SpeedLimiter> limiter_linear_;

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 18 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -111,27 +111,27 @@ controller_interface::return_type DiffDriveController::update_reference_from_sub
111111
return controller_interface::return_type::OK;
112112
}
113113

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)
117117
{
118118
RCLCPP_WARN(logger, "Velocity message received was a nullptr.");
119119
return controller_interface::return_type::ERROR;
120120
}
121121

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;
123123
// Brake if cmd_vel has timeout, override the stored command
124124
if (age_of_last_command > cmd_vel_timeout_)
125125
{
126126
reference_interfaces_[0] = 0.0;
127127
reference_interfaces_[1] = 0.0;
128128
}
129129
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))
132132
{
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;
135135
}
136136
else
137137
{
@@ -425,6 +425,13 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
425425
limited_velocity_publisher_);
426426
}
427427

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+
428435
// initialize command subscriber
429436
velocity_command_subscriber_ = get_node()->create_subscription<TwistStamped>(
430437
DEFAULT_COMMAND_TOPIC, rclcpp::SystemDefaultsQoS(),
@@ -450,7 +457,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
450457
cmd_vel_timeout_ == rclcpp::Duration::from_seconds(0.0) ||
451458
current_time_diff < cmd_vel_timeout_)
452459
{
453-
received_velocity_msg_ptr_.writeFromNonRT(msg);
460+
(void)received_velocity_msg_ptr_.bounded_push(std::move(msg));
454461
}
455462
else
456463
{
@@ -625,18 +632,8 @@ void DiffDriveController::reset_buffers()
625632
previous_two_commands_.push({{0.0, 0.0}});
626633
previous_two_commands_.push({{0.0, 0.0}});
627634

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);
640637
}
641638

642639
void DiffDriveController::halt()

diff_drive_controller/test/test_diff_drive_controller.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,9 @@ class TestableDiffDriveController : public diff_drive_controller::DiffDriveContr
4747
using DiffDriveController::DiffDriveController;
4848
std::shared_ptr<geometry_msgs::msg::TwistStamped> getLastReceivedTwist()
4949
{
50-
return *(received_velocity_msg_ptr_.readFromNonRT());
50+
std::shared_ptr<geometry_msgs::msg::TwistStamped> ret;
51+
(void)received_velocity_msg_ptr_.get_latest(ret);
52+
return ret;
5153
}
5254

5355
/**

0 commit comments

Comments
 (0)