4343
4444#include < stdint.h>
4545
46- #include < realtime_tools/realtime_box_best_effort.h>
47-
4846#include < functional>
4947#include < limits>
5048#include < memory>
6664
6765#include " passthrough_trajectory_controller_parameters.hpp"
6866
67+ #include " realtime_tools/realtime_buffer.h"
68+ #include " realtime_tools/realtime_server_goal_handle.h"
69+
6970namespace ur_controllers
7071{
7172
@@ -75,6 +76,7 @@ const double TRANSFER_STATE_TRANSFERRING = 2.0;
7576const double TRANSFER_STATE_TRANSFER_DONE = 3.0 ;
7677const double TRANSFER_STATE_IN_MOTION = 4.0 ;
7778const double TRANSFER_STATE_DONE = 5.0 ;
79+ using namespace std ::chrono_literals; // NOLINT
7880
7981enum CommandInterfaces
8082{
@@ -134,6 +136,16 @@ class PassthroughTrajectoryController : public controller_interface::ControllerI
134136 controller_interface::return_type update (const rclcpp::Time& time, const rclcpp::Duration& period) override ;
135137
136138private:
139+ using FollowJTrajAction = control_msgs::action::FollowJointTrajectory;
140+ using RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle<FollowJTrajAction>;
141+ using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
142+ using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>;
143+
144+ RealtimeGoalHandleBuffer rt_active_goal_; // /< Currently active action goal, if any.
145+ rclcpp::TimerBase::SharedPtr goal_handle_timer_; // /< Timer to frequently check on the running goal
146+
147+ rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
148+
137149 /* Start an action server with an action called: /passthrough_trajectory_controller/forward_joint_trajectory. */
138150 void start_action_server (void );
139151
@@ -154,7 +166,7 @@ class PassthroughTrajectoryController : public controller_interface::ControllerI
154166 const std::shared_ptr<rclcpp_action::ServerGoalHandle<control_msgs::action::FollowJointTrajectory>> goal_handle);
155167
156168 void goal_accepted_callback (
157- const std::shared_ptr<rclcpp_action::ServerGoalHandle<control_msgs::action::FollowJointTrajectory>> goal_handle);
169+ std::shared_ptr<rclcpp_action::ServerGoalHandle<control_msgs::action::FollowJointTrajectory>> goal_handle);
158170
159171 std::vector<std::string> joint_names_;
160172 std::vector<std::string> state_interface_types_;
@@ -171,17 +183,15 @@ class PassthroughTrajectoryController : public controller_interface::ControllerI
171183 std::vector<control_msgs::msg::JointTolerance> goal_tolerance_;
172184 rclcpp::Duration goal_time_tolerance_ = rclcpp::Duration::from_nanoseconds(0 );
173185
174- realtime_tools::RealtimeBoxBestEffort<AsyncInfo> info_from_realtime_;
175- realtime_tools::RealtimeBoxBestEffort<AsyncInfo> info_to_realtime_;
176-
177- uint32_t current_point_;
178- bool trajectory_active_;
179- double active_trajectory_elapsed_time_;
180- double max_trajectory_time_;
186+ std::atomic<size_t > current_index_;
187+ std::atomic<bool > trajectory_active_;
188+ rclcpp::Duration active_trajectory_elapsed_time_ = rclcpp::Duration::from_nanoseconds(0 );
189+ rclcpp::Duration max_trajectory_time_ = rclcpp::Duration::from_nanoseconds(0 );
181190 double scaling_factor_;
182191 uint32_t number_of_joints_;
183- std::shared_ptr<rclcpp_action::ServerGoalHandle<control_msgs::action::FollowJointTrajectory>> active_goal_;
184192 static constexpr double NO_VAL = std::numeric_limits<double >::quiet_NaN();
193+
194+ std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>> scaling_state_interface_;
185195};
186196} // namespace ur_controllers
187197#endif // UR_CONTROLLERS__PASSTHROUGH_TRAJECTORY_CONTROLLER_HPP_
0 commit comments