Skip to content

Commit a88bf0a

Browse files
Update realtime containers (#1721)
1 parent 4a42b1f commit a88bf0a

File tree

32 files changed

+734
-488
lines changed

32 files changed

+734
-488
lines changed

ackermann_steering_controller/test/test_ackermann_steering_controller.cpp

Lines changed: 17 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -103,13 +103,13 @@ TEST_F(AckermannSteeringControllerTest, activate_success)
103103
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
104104

105105
// check that the message is reset
106-
auto msg = controller_->input_ref_.readFromNonRT();
107-
EXPECT_TRUE(std::isnan((*msg)->twist.linear.x));
108-
EXPECT_TRUE(std::isnan((*msg)->twist.linear.y));
109-
EXPECT_TRUE(std::isnan((*msg)->twist.linear.z));
110-
EXPECT_TRUE(std::isnan((*msg)->twist.angular.x));
111-
EXPECT_TRUE(std::isnan((*msg)->twist.angular.y));
112-
EXPECT_TRUE(std::isnan((*msg)->twist.angular.z));
106+
auto msg = controller_->input_ref_.get();
107+
EXPECT_TRUE(std::isnan(msg.twist.linear.x));
108+
EXPECT_TRUE(std::isnan(msg.twist.linear.y));
109+
EXPECT_TRUE(std::isnan(msg.twist.linear.z));
110+
EXPECT_TRUE(std::isnan(msg.twist.angular.x));
111+
EXPECT_TRUE(std::isnan(msg.twist.angular.y));
112+
EXPECT_TRUE(std::isnan(msg.twist.angular.z));
113113
}
114114

115115
TEST_F(AckermannSteeringControllerTest, update_success)
@@ -161,11 +161,11 @@ TEST_F(AckermannSteeringControllerTest, test_update_logic)
161161
ASSERT_FALSE(controller_->is_in_chained_mode());
162162

163163
// set command statically
164-
std::shared_ptr<ControllerReferenceMsg> msg = std::make_shared<ControllerReferenceMsg>();
165-
msg->header.stamp = controller_->get_node()->now();
166-
msg->twist.linear.x = 0.1;
167-
msg->twist.angular.z = 0.2;
168-
controller_->input_ref_.writeFromNonRT(msg);
164+
ControllerReferenceMsg msg;
165+
msg.header.stamp = controller_->get_node()->now();
166+
msg.twist.linear.x = 0.1;
167+
msg.twist.angular.z = 0.2;
168+
controller_->input_ref_.set(msg);
169169

170170
ASSERT_EQ(
171171
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
@@ -185,7 +185,7 @@ TEST_F(AckermannSteeringControllerTest, test_update_logic)
185185
controller_->command_interfaces_[CMD_STEER_LEFT_WHEEL].get_value(), 1.4179821977774734,
186186
COMMON_THRESHOLD);
187187

188-
EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->twist.linear.x));
188+
EXPECT_FALSE(std::isnan(controller_->input_ref_.get().twist.linear.x));
189189
EXPECT_EQ(controller_->reference_interfaces_.size(), joint_reference_interfaces_.size());
190190
for (const auto & interface : controller_->reference_interfaces_)
191191
{
@@ -225,7 +225,7 @@ TEST_F(AckermannSteeringControllerTest, test_update_logic_chained)
225225
controller_->command_interfaces_[STATE_STEER_LEFT_WHEEL].get_value(), 1.4179821977774734,
226226
COMMON_THRESHOLD);
227227

228-
EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->twist.linear.x));
228+
EXPECT_TRUE(std::isnan(controller_->input_ref_.get().twist.linear.x));
229229
EXPECT_EQ(controller_->reference_interfaces_.size(), joint_reference_interfaces_.size());
230230
for (const auto & interface : controller_->reference_interfaces_)
231231
{
@@ -249,8 +249,9 @@ TEST_F(AckermannSteeringControllerTest, receive_message_and_publish_updated_stat
249249
ControllerStateMsg msg;
250250
subscribe_and_get_messages(msg);
251251

252-
EXPECT_EQ(msg.traction_command[STATE_TRACTION_RIGHT_WHEEL], 1.1);
253-
EXPECT_EQ(msg.traction_command[STATE_TRACTION_LEFT_WHEEL], 3.3);
252+
// never received a valid command, linear velocity should have been reset
253+
EXPECT_EQ(msg.traction_command[STATE_TRACTION_RIGHT_WHEEL], 0.0);
254+
EXPECT_EQ(msg.traction_command[STATE_TRACTION_LEFT_WHEEL], 0.0);
254255
EXPECT_EQ(msg.steering_angle_command[0], 2.2);
255256
EXPECT_EQ(msg.steering_angle_command[1], 4.4);
256257

admittance_controller/include/admittance_controller/admittance_controller.hpp

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -31,8 +31,8 @@
3131
#include "rclcpp/duration.hpp"
3232
#include "rclcpp/time.hpp"
3333
#include "rclcpp_lifecycle/state.hpp"
34-
#include "realtime_tools/realtime_buffer.hpp"
3534
#include "realtime_tools/realtime_publisher.hpp"
35+
#include "realtime_tools/realtime_thread_safe_box.hpp"
3636
#include "semantic_components/force_torque_sensor.hpp"
3737

3838
namespace admittance_controller
@@ -125,15 +125,16 @@ class AdmittanceController : public controller_interface::ChainableControllerInt
125125
// admittance parameters
126126
std::shared_ptr<admittance_controller::ParamListener> parameter_handler_;
127127

128-
// ROS messages
129-
std::shared_ptr<trajectory_msgs::msg::JointTrajectoryPoint> joint_command_msg_;
130-
131-
// real-time buffer
132-
realtime_tools::RealtimeBuffer<std::shared_ptr<trajectory_msgs::msg::JointTrajectoryPoint>>
128+
// real-time boxes
129+
realtime_tools::RealtimeThreadSafeBox<trajectory_msgs::msg::JointTrajectoryPoint>
133130
input_joint_command_;
134-
realtime_tools::RealtimeBuffer<geometry_msgs::msg::WrenchStamped> input_wrench_command_;
131+
realtime_tools::RealtimeThreadSafeBox<geometry_msgs::msg::WrenchStamped> input_wrench_command_;
135132
std::unique_ptr<realtime_tools::RealtimePublisher<ControllerStateMsg>> state_publisher_;
136133

134+
// save the last commands in case of unable to get value from box
135+
trajectory_msgs::msg::JointTrajectoryPoint joint_command_msg_;
136+
geometry_msgs::msg::WrenchStamped wrench_command_msg_;
137+
137138
trajectory_msgs::msg::JointTrajectoryPoint last_commanded_;
138139
trajectory_msgs::msg::JointTrajectoryPoint last_reference_;
139140

admittance_controller/src/admittance_controller.cpp

Lines changed: 46 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,27 @@
2525
#include "geometry_msgs/msg/wrench.hpp"
2626
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
2727

28+
namespace
29+
{ // utility
30+
31+
// called from RT control loop
32+
void reset_controller_reference_msg(trajectory_msgs::msg::JointTrajectoryPoint & msg)
33+
{
34+
msg.positions.clear();
35+
msg.velocities.clear();
36+
}
37+
38+
// called from RT control loop
39+
void reset_wrench_msg(
40+
geometry_msgs::msg::WrenchStamped & msg,
41+
const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node)
42+
{
43+
msg.header.stamp = node->now();
44+
msg.wrench = geometry_msgs::msg::Wrench();
45+
}
46+
47+
} // namespace
48+
2849
namespace admittance_controller
2950
{
3051

@@ -133,7 +154,6 @@ AdmittanceController::on_export_reference_interfaces()
133154
reference_interfaces_.resize(num_chainable_interfaces, std::numeric_limits<double>::quiet_NaN());
134155
position_reference_ = {};
135156
velocity_reference_ = {};
136-
input_wrench_command_.reset();
137157

138158
// assign reference interfaces
139159
auto index = 0ul;
@@ -286,7 +306,7 @@ controller_interface::CallbackReturn AdmittanceController::on_configure(
286306
// setup subscribers and publishers
287307
auto joint_command_callback =
288308
[this](const std::shared_ptr<trajectory_msgs::msg::JointTrajectoryPoint> msg)
289-
{ input_joint_command_.writeFromNonRT(msg); };
309+
{ input_joint_command_.set(*msg); };
290310
input_joint_command_subscriber_ =
291311
get_node()->create_subscription<trajectory_msgs::msg::JointTrajectoryPoint>(
292312
"~/joint_references", rclcpp::SystemDefaultsQoS(), joint_command_callback);
@@ -307,8 +327,9 @@ controller_interface::CallbackReturn AdmittanceController::on_configure(
307327
msg.header.frame_id.c_str(), admittance_->parameters_.ft_sensor.frame.id.c_str());
308328
return;
309329
}
310-
input_wrench_command_.writeFromNonRT(msg);
330+
input_wrench_command_.set(msg);
311331
});
332+
312333
s_publisher_ = get_node()->create_publisher<control_msgs::msg::AdmittanceControllerState>(
313334
"~/status", rclcpp::SystemDefaultsQoS());
314335
state_publisher_ =
@@ -390,6 +411,8 @@ controller_interface::CallbackReturn AdmittanceController::on_activate(
390411
return controller_interface::CallbackReturn::ERROR;
391412
}
392413
}
414+
reset_controller_reference_msg(joint_command_msg_);
415+
reset_wrench_msg(wrench_command_msg_, get_node());
393416

394417
// Use current joint_state as a default reference
395418
last_reference_ = joint_state_;
@@ -408,26 +431,29 @@ controller_interface::return_type AdmittanceController::update_reference_from_su
408431
{
409432
return controller_interface::return_type::ERROR;
410433
}
411-
412-
joint_command_msg_ = *input_joint_command_.readFromRT();
434+
auto joint_command_msg_op = input_joint_command_.try_get();
435+
if (joint_command_msg_op.has_value())
436+
{
437+
joint_command_msg_ = joint_command_msg_op.value();
438+
}
413439

414440
// if message exists, load values into references
415-
if (joint_command_msg_.get())
441+
if (!joint_command_msg_.positions.empty() || !joint_command_msg_.velocities.empty())
416442
{
417443
for (const auto & interface : admittance_->parameters_.chainable_command_interfaces)
418444
{
419445
if (interface == hardware_interface::HW_IF_POSITION)
420446
{
421-
for (size_t i = 0; i < joint_command_msg_->positions.size(); ++i)
447+
for (size_t i = 0; i < joint_command_msg_.positions.size(); ++i)
422448
{
423-
position_reference_[i].get() = joint_command_msg_->positions[i];
449+
position_reference_[i].get() = joint_command_msg_.positions[i];
424450
}
425451
}
426452
else if (interface == hardware_interface::HW_IF_VELOCITY)
427453
{
428-
for (size_t i = 0; i < joint_command_msg_->velocities.size(); ++i)
454+
for (size_t i = 0; i < joint_command_msg_.velocities.size(); ++i)
429455
{
430-
velocity_reference_[i].get() = joint_command_msg_->velocities[i];
456+
velocity_reference_[i].get() = joint_command_msg_.velocities[i];
431457
}
432458
}
433459
}
@@ -451,7 +477,13 @@ controller_interface::return_type AdmittanceController::update_and_write_command
451477
// get all controller inputs
452478
read_state_from_hardware(joint_state_, ft_values_);
453479

454-
auto offsetted_ft_values = add_wrenches(ft_values_, input_wrench_command_.readFromRT()->wrench);
480+
auto wrench_command_op = input_wrench_command_.try_get();
481+
if (wrench_command_op.has_value())
482+
{
483+
wrench_command_msg_ = wrench_command_op.value();
484+
}
485+
486+
auto offsetted_ft_values = add_wrenches(ft_values_, wrench_command_msg_.wrench);
455487

456488
// apply admittance control to reference to determine desired state
457489
admittance_->update(joint_state_, offsetted_ft_values, reference_, period, reference_admittance_);
@@ -498,6 +530,9 @@ controller_interface::CallbackReturn AdmittanceController::on_deactivate(
498530
release_interfaces();
499531
admittance_->reset(num_joints_);
500532

533+
reset_controller_reference_msg(joint_command_msg_);
534+
reset_wrench_msg(wrench_command_msg_, get_node());
535+
501536
return CallbackReturn::SUCCESS;
502537
}
503538

bicycle_steering_controller/test/test_bicycle_steering_controller.cpp

Lines changed: 16 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -89,13 +89,13 @@ TEST_F(BicycleSteeringControllerTest, activate_success)
8989
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
9090

9191
// check that the message is reset
92-
auto msg = controller_->input_ref_.readFromNonRT();
93-
EXPECT_TRUE(std::isnan((*msg)->twist.linear.x));
94-
EXPECT_TRUE(std::isnan((*msg)->twist.linear.y));
95-
EXPECT_TRUE(std::isnan((*msg)->twist.linear.z));
96-
EXPECT_TRUE(std::isnan((*msg)->twist.angular.x));
97-
EXPECT_TRUE(std::isnan((*msg)->twist.angular.y));
98-
EXPECT_TRUE(std::isnan((*msg)->twist.angular.z));
92+
auto msg = controller_->input_ref_.get();
93+
EXPECT_TRUE(std::isnan(msg.twist.linear.x));
94+
EXPECT_TRUE(std::isnan(msg.twist.linear.y));
95+
EXPECT_TRUE(std::isnan(msg.twist.linear.z));
96+
EXPECT_TRUE(std::isnan(msg.twist.angular.x));
97+
EXPECT_TRUE(std::isnan(msg.twist.angular.y));
98+
EXPECT_TRUE(std::isnan(msg.twist.angular.z));
9999
}
100100

101101
TEST_F(BicycleSteeringControllerTest, update_success)
@@ -147,11 +147,11 @@ TEST_F(BicycleSteeringControllerTest, test_update_logic)
147147
ASSERT_FALSE(controller_->is_in_chained_mode());
148148

149149
// set command statically
150-
std::shared_ptr<ControllerReferenceMsg> msg = std::make_shared<ControllerReferenceMsg>();
151-
msg->header.stamp = controller_->get_node()->now();
152-
msg->twist.linear.x = 0.1;
153-
msg->twist.angular.z = 0.2;
154-
controller_->input_ref_.writeFromNonRT(msg);
150+
ControllerReferenceMsg msg;
151+
msg.header.stamp = controller_->get_node()->now();
152+
msg.twist.linear.x = 0.1;
153+
msg.twist.angular.z = 0.2;
154+
controller_->input_ref_.set(msg);
155155

156156
ASSERT_EQ(
157157
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
@@ -163,7 +163,7 @@ TEST_F(BicycleSteeringControllerTest, test_update_logic)
163163
controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734,
164164
COMMON_THRESHOLD);
165165

166-
EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->twist.linear.x));
166+
EXPECT_FALSE(std::isnan(controller_->input_ref_.get().twist.linear.x));
167167
EXPECT_EQ(controller_->reference_interfaces_.size(), joint_reference_interfaces_.size());
168168
for (const auto & interface : controller_->reference_interfaces_)
169169
{
@@ -195,7 +195,7 @@ TEST_F(BicycleSteeringControllerTest, test_update_logic_chained)
195195
controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734,
196196
COMMON_THRESHOLD);
197197

198-
EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->twist.linear.x));
198+
EXPECT_TRUE(std::isnan(controller_->input_ref_.get().twist.linear.x));
199199
EXPECT_EQ(controller_->reference_interfaces_.size(), joint_reference_interfaces_.size());
200200
for (const auto & interface : controller_->reference_interfaces_)
201201
{
@@ -234,7 +234,8 @@ TEST_F(BicycleSteeringControllerTest, receive_message_and_publish_updated_status
234234
ControllerStateMsg msg;
235235
subscribe_and_get_messages(msg);
236236

237-
EXPECT_EQ(msg.traction_command[0], 1.1);
237+
// never received a valid command, linear velocity should have been reset
238+
EXPECT_EQ(msg.traction_command[0], 0.0);
238239
EXPECT_EQ(msg.steering_angle_command[0], 2.2);
239240

240241
publish_commands(0.1, 0.2);

diff_drive_controller/include/diff_drive_controller/diff_drive_controller.hpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,8 +32,8 @@
3232
#include "nav_msgs/msg/odometry.hpp"
3333
#include "odometry.hpp"
3434
#include "rclcpp_lifecycle/state.hpp"
35-
#include "realtime_tools/realtime_buffer.hpp"
3635
#include "realtime_tools/realtime_publisher.hpp"
36+
#include "realtime_tools/realtime_thread_safe_box.hpp"
3737
#include "tf2_msgs/msg/tf_message.hpp"
3838

3939
// auto-generated by generate_parameter_library
@@ -122,7 +122,10 @@ 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};
125+
// the realtime container to exchange the reference from subscriber
126+
realtime_tools::RealtimeThreadSafeBox<TwistStamped> received_velocity_msg_;
127+
// save the last reference in case of unable to get value from box
128+
TwistStamped command_msg_;
126129

127130
std::queue<std::array<double, 2>> previous_two_commands_;
128131
// speed limiters

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 17 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -107,27 +107,24 @@ controller_interface::return_type DiffDriveController::update_reference_from_sub
107107
{
108108
auto logger = get_node()->get_logger();
109109

110-
const std::shared_ptr<TwistStamped> command_msg_ptr = *(received_velocity_msg_ptr_.readFromRT());
111-
112-
if (command_msg_ptr == nullptr)
110+
auto current_ref_op = received_velocity_msg_.try_get();
111+
if (current_ref_op.has_value())
113112
{
114-
RCLCPP_WARN(logger, "Velocity message received was a nullptr.");
115-
return controller_interface::return_type::ERROR;
113+
command_msg_ = current_ref_op.value();
116114
}
117115

118-
const auto age_of_last_command = time - command_msg_ptr->header.stamp;
116+
const auto age_of_last_command = time - command_msg_.header.stamp;
119117
// Brake if cmd_vel has timeout, override the stored command
120118
if (age_of_last_command > cmd_vel_timeout_)
121119
{
122120
reference_interfaces_[0] = 0.0;
123121
reference_interfaces_[1] = 0.0;
124122
}
125123
else if (
126-
std::isfinite(command_msg_ptr->twist.linear.x) &&
127-
std::isfinite(command_msg_ptr->twist.angular.z))
124+
std::isfinite(command_msg_.twist.linear.x) && std::isfinite(command_msg_.twist.angular.z))
128125
{
129-
reference_interfaces_[0] = command_msg_ptr->twist.linear.x;
130-
reference_interfaces_[1] = command_msg_ptr->twist.angular.z;
126+
reference_interfaces_[0] = command_msg_.twist.linear.x;
127+
reference_interfaces_[1] = command_msg_.twist.angular.z;
131128
}
132129
else
133130
{
@@ -396,7 +393,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
396393
cmd_vel_timeout_ == rclcpp::Duration::from_seconds(0.0) ||
397394
current_time_diff < cmd_vel_timeout_)
398395
{
399-
received_velocity_msg_ptr_.writeFromNonRT(msg);
396+
received_velocity_msg_.set(*msg);
400397
}
401398
else
402399
{
@@ -567,18 +564,16 @@ void DiffDriveController::reset_buffers()
567564
previous_two_commands_.push({{0.0, 0.0}});
568565
previous_two_commands_.push({{0.0, 0.0}});
569566

570-
// Fill RealtimeBuffer with NaNs so it will contain a known value
567+
// Fill RealtimeBox with NaNs so it will contain a known value
571568
// but still indicate that no command has yet been sent.
572-
received_velocity_msg_ptr_.reset();
573-
std::shared_ptr<TwistStamped> empty_msg_ptr = std::make_shared<TwistStamped>();
574-
empty_msg_ptr->header.stamp = get_node()->now();
575-
empty_msg_ptr->twist.linear.x = std::numeric_limits<double>::quiet_NaN();
576-
empty_msg_ptr->twist.linear.y = std::numeric_limits<double>::quiet_NaN();
577-
empty_msg_ptr->twist.linear.z = std::numeric_limits<double>::quiet_NaN();
578-
empty_msg_ptr->twist.angular.x = std::numeric_limits<double>::quiet_NaN();
579-
empty_msg_ptr->twist.angular.y = std::numeric_limits<double>::quiet_NaN();
580-
empty_msg_ptr->twist.angular.z = std::numeric_limits<double>::quiet_NaN();
581-
received_velocity_msg_ptr_.writeFromNonRT(empty_msg_ptr);
569+
command_msg_.header.stamp = get_node()->now();
570+
command_msg_.twist.linear.x = std::numeric_limits<double>::quiet_NaN();
571+
command_msg_.twist.linear.y = std::numeric_limits<double>::quiet_NaN();
572+
command_msg_.twist.linear.z = std::numeric_limits<double>::quiet_NaN();
573+
command_msg_.twist.angular.x = std::numeric_limits<double>::quiet_NaN();
574+
command_msg_.twist.angular.y = std::numeric_limits<double>::quiet_NaN();
575+
command_msg_.twist.angular.z = std::numeric_limits<double>::quiet_NaN();
576+
received_velocity_msg_.set(command_msg_);
582577
}
583578

584579
void DiffDriveController::halt()

diff_drive_controller/test/test_diff_drive_controller.cpp

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -45,10 +45,6 @@ class TestableDiffDriveController : public diff_drive_controller::DiffDriveContr
4545
{
4646
public:
4747
using DiffDriveController::DiffDriveController;
48-
std::shared_ptr<geometry_msgs::msg::TwistStamped> getLastReceivedTwist()
49-
{
50-
return *(received_velocity_msg_ptr_.readFromNonRT());
51-
}
5248

5349
/**
5450
* @brief wait_for_twist block until a new twist is received.

0 commit comments

Comments
 (0)