Skip to content

Commit ea76f8e

Browse files
authored
Use RealtimeThreadSafeBox instead of RealTimeBuffer (backport #1474) (#1501)
Use RealtimeThreadSafeBox instead of RealTimeBuffer. Also made it so that any reading or writing done outside of real-time threads will retry 10 times before failing in non-RT contexts.
1 parent fc33a0a commit ea76f8e

8 files changed

+336
-52
lines changed

ur_controllers/include/ur_controllers/force_mode_controller.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -42,8 +42,8 @@
4242

4343
#include <controller_interface/controller_interface.hpp>
4444
#include <geometry_msgs/msg/pose_stamped.hpp>
45-
#include <realtime_tools/realtime_buffer.hpp>
4645
#include <rclcpp/rclcpp.hpp>
46+
#include <realtime_tools/realtime_thread_safe_box.hpp>
4747
#include <std_srvs/srv/trigger.hpp>
4848
#include <ur_msgs/srv/set_force_mode.hpp>
4949

@@ -93,7 +93,7 @@ struct ForceModeParameters
9393
std::array<double, 6> task_frame;
9494
std::array<double, 6> selection_vec;
9595
std::array<double, 6> limits;
96-
geometry_msgs::msg::Wrench wrench;
96+
geometry_msgs::msg::Wrench wrench{};
9797
double type;
9898
double damping_factor;
9999
double gain_scaling;
@@ -132,7 +132,7 @@ class ForceModeController : public controller_interface::ControllerInterface
132132
std::shared_ptr<force_mode_controller::ParamListener> param_listener_;
133133
force_mode_controller::Params params_;
134134

135-
realtime_tools::RealtimeBuffer<ForceModeParameters> force_mode_params_buffer_;
135+
realtime_tools::RealtimeThreadSafeBox<ForceModeParameters> force_mode_params_buffer_;
136136
std::atomic<bool> force_mode_active_;
137137
std::atomic<bool> change_requested_;
138138
std::atomic<double> async_state_;

ur_controllers/include/ur_controllers/passthrough_trajectory_controller.hpp

Lines changed: 8 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@
5151
#include <vector>
5252

5353
#include <controller_interface/controller_interface.hpp>
54-
#include <realtime_tools/realtime_buffer.hpp>
54+
#include <realtime_tools/realtime_thread_safe_box.hpp>
5555
#include <realtime_tools/realtime_server_goal_handle.hpp>
5656
#include <rclcpp_action/server.hpp>
5757
#include <rclcpp_action/create_server.hpp>
@@ -114,11 +114,11 @@ class PassthroughTrajectoryController : public controller_interface::ControllerI
114114
using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
115115
using RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle<FollowJTrajAction>;
116116
using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
117-
using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>;
117+
using RealtimeGoalHandleBuffer = realtime_tools::RealtimeThreadSafeBox<RealtimeGoalHandlePtr>;
118118

119119
RealtimeGoalHandleBuffer rt_active_goal_; ///< Currently active action goal, if any.
120120
rclcpp::TimerBase::SharedPtr goal_handle_timer_; ///< Timer to frequently check on the running goal
121-
realtime_tools::RealtimeBuffer<std::unordered_map<std::string, size_t>> joint_trajectory_mapping_;
121+
realtime_tools::RealtimeThreadSafeBox<std::unordered_map<std::string, size_t>> joint_trajectory_mapping_;
122122

123123
rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
124124

@@ -147,7 +147,7 @@ class PassthroughTrajectoryController : public controller_interface::ControllerI
147147
void goal_accepted_callback(
148148
std::shared_ptr<rclcpp_action::ServerGoalHandle<control_msgs::action::FollowJointTrajectory>> goal_handle);
149149

150-
realtime_tools::RealtimeBuffer<std::vector<std::string>> joint_names_;
150+
realtime_tools::RealtimeThreadSafeBox<std::vector<std::string>> joint_names_;
151151
std::vector<std::string> state_interface_types_;
152152

153153
std::vector<std::string> joint_state_interface_names_;
@@ -159,11 +159,13 @@ class PassthroughTrajectoryController : public controller_interface::ControllerI
159159
bool check_goal_positions(std::shared_ptr<const control_msgs::action::FollowJointTrajectory::Goal> goal);
160160
bool check_goal_velocities(std::shared_ptr<const control_msgs::action::FollowJointTrajectory::Goal> goal);
161161
bool check_goal_accelerations(std::shared_ptr<const control_msgs::action::FollowJointTrajectory::Goal> goal);
162+
std::optional<RealtimeGoalHandlePtr> get_rt_goal_from_non_rt();
163+
bool set_rt_goal_from_non_rt(RealtimeGoalHandlePtr& rt_goal);
162164

163165
trajectory_msgs::msg::JointTrajectory active_joint_traj_;
164166
// std::vector<control_msgs::msg::JointTolerance> path_tolerance_;
165-
realtime_tools::RealtimeBuffer<std::vector<control_msgs::msg::JointTolerance>> goal_tolerance_;
166-
realtime_tools::RealtimeBuffer<rclcpp::Duration> goal_time_tolerance_{ rclcpp::Duration(0, 0) };
167+
realtime_tools::RealtimeThreadSafeBox<std::vector<control_msgs::msg::JointTolerance>> goal_tolerance_;
168+
realtime_tools::RealtimeThreadSafeBox<rclcpp::Duration> goal_time_tolerance_{ rclcpp::Duration(0, 0) };
167169

168170
std::atomic<size_t> current_index_;
169171
std::atomic<bool> trajectory_active_;

ur_controllers/include/ur_controllers/tool_contact_controller.hpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -53,8 +53,9 @@
5353
#include <rclcpp_action/server_goal_handle.hpp>
5454
#include <rclcpp/duration.hpp>
5555

56-
#include <realtime_tools/realtime_buffer.hpp>
56+
#include <realtime_tools/realtime_thread_safe_box.hpp>
5757
#include <realtime_tools/realtime_server_goal_handle.hpp>
58+
#include <realtime_tools/lock_free_queue.hpp>
5859

5960
#include <ur_msgs/action/tool_contact.hpp>
6061
#include "ur_controllers/tool_contact_controller_parameters.hpp"
@@ -86,11 +87,13 @@ class ToolContactController : public controller_interface::ControllerInterface
8687
private:
8788
using RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle<ur_msgs::action::ToolContact>;
8889
using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
89-
using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>;
90+
using RealtimeGoalHandleBuffer = realtime_tools::RealtimeThreadSafeBox<RealtimeGoalHandlePtr>;
9091

9192
RealtimeGoalHandleBuffer rt_active_goal_; ///< Currently active action goal, if any.
9293
ur_msgs::action::ToolContact::Feedback::SharedPtr feedback_; ///< preallocated feedback
9394
rclcpp::TimerBase::SharedPtr goal_handle_timer_; ///< Timer to frequently check on the running goal
95+
std::optional<RealtimeGoalHandlePtr> get_rt_goal_from_non_rt();
96+
bool set_rt_goal_from_non_rt(const RealtimeGoalHandlePtr& goal_handle);
9497

9598
// non-rt function that will be called with action_monitor_period to monitor the rt action
9699
rclcpp::Duration action_monitor_period_ = rclcpp::Duration::from_seconds(0.05);

ur_controllers/include/ur_controllers/ur_configuration_controller.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@
4444
#include <memory>
4545

4646
#include <controller_interface/controller_interface.hpp>
47-
#include <realtime_tools/realtime_box.hpp>
47+
#include <realtime_tools/realtime_thread_safe_box.hpp>
4848

4949
#include "ur_msgs/srv/get_robot_software_version.hpp"
5050
#include "ur_controllers/ur_configuration_controller_parameters.hpp"
@@ -85,7 +85,7 @@ class URConfigurationController : public controller_interface::ControllerInterfa
8585
CallbackReturn on_init() override;
8686

8787
private:
88-
realtime_tools::RealtimeBox<std::shared_ptr<VersionInformation>> robot_software_version_{
88+
realtime_tools::RealtimeThreadSafeBox<std::shared_ptr<VersionInformation>> robot_software_version_{
8989
std::make_shared<VersionInformation>()
9090
};
9191
std::atomic<bool> robot_software_version_set_{ false };

ur_controllers/src/force_mode_controller.cpp

Lines changed: 17 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -180,7 +180,12 @@ controller_interface::return_type ur_controllers::ForceModeController::update(co
180180
if (change_requested_) {
181181
bool write_successful = true;
182182
if (force_mode_active_) {
183-
const auto force_mode_parameters = force_mode_params_buffer_.readFromRT();
183+
const auto force_mode_parameters = force_mode_params_buffer_.try_get();
184+
if (!force_mode_parameters) {
185+
RCLCPP_WARN(get_node()->get_logger(), "Could not get force mode parameters from realtime buffer. Retrying in "
186+
"next update cycle.");
187+
return controller_interface::return_type::OK;
188+
}
184189
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_X].set_value(
185190
force_mode_parameters->task_frame[0]);
186191
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Y].set_value(
@@ -357,7 +362,17 @@ bool ForceModeController::setForceMode(const ur_msgs::srv::SetForceMode::Request
357362
}
358363
force_mode_parameters.gain_scaling = req->gain_scaling;
359364

360-
force_mode_params_buffer_.writeFromNonRT(force_mode_parameters);
365+
int tries = 0;
366+
while (!force_mode_params_buffer_.try_set(force_mode_parameters)) {
367+
if (tries > 10) {
368+
RCLCPP_ERROR(get_node()->get_logger(), "Could not set force mode parameters in realtime buffer.");
369+
resp->success = false;
370+
return false;
371+
}
372+
rclcpp::sleep_for(std::chrono::milliseconds(50));
373+
tries++;
374+
}
375+
361376
force_mode_active_ = true;
362377
change_requested_ = true;
363378

0 commit comments

Comments
 (0)