51
51
#include < vector>
52
52
53
53
#include < controller_interface/controller_interface.hpp>
54
- #include < realtime_tools/realtime_buffer .hpp>
54
+ #include < realtime_tools/realtime_thread_safe_box .hpp>
55
55
#include < realtime_tools/realtime_server_goal_handle.hpp>
56
56
#include < rclcpp_action/server.hpp>
57
57
#include < rclcpp_action/create_server.hpp>
@@ -114,11 +114,11 @@ class PassthroughTrajectoryController : public controller_interface::ControllerI
114
114
using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
115
115
using RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle<FollowJTrajAction>;
116
116
using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
117
- using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer <RealtimeGoalHandlePtr>;
117
+ using RealtimeGoalHandleBuffer = realtime_tools::RealtimeThreadSafeBox <RealtimeGoalHandlePtr>;
118
118
119
119
RealtimeGoalHandleBuffer rt_active_goal_; // /< Currently active action goal, if any.
120
120
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_;
122
122
123
123
rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
124
124
@@ -147,7 +147,7 @@ class PassthroughTrajectoryController : public controller_interface::ControllerI
147
147
void goal_accepted_callback (
148
148
std::shared_ptr<rclcpp_action::ServerGoalHandle<control_msgs::action::FollowJointTrajectory>> goal_handle);
149
149
150
- realtime_tools::RealtimeBuffer <std::vector<std::string>> joint_names_;
150
+ realtime_tools::RealtimeThreadSafeBox <std::vector<std::string>> joint_names_;
151
151
std::vector<std::string> state_interface_types_;
152
152
153
153
std::vector<std::string> joint_state_interface_names_;
@@ -159,11 +159,13 @@ class PassthroughTrajectoryController : public controller_interface::ControllerI
159
159
bool check_goal_positions (std::shared_ptr<const control_msgs::action::FollowJointTrajectory::Goal> goal);
160
160
bool check_goal_velocities (std::shared_ptr<const control_msgs::action::FollowJointTrajectory::Goal> goal);
161
161
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);
162
164
163
165
trajectory_msgs::msg::JointTrajectory active_joint_traj_;
164
166
// 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 ) };
167
169
168
170
std::atomic<size_t > current_index_;
169
171
std::atomic<bool > trajectory_active_;
0 commit comments