Skip to content

Commit d7a699f

Browse files
authored
Fix JTC crashing when shutdown while executing (#1960)
1 parent 34c5ff3 commit d7a699f

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -183,8 +183,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
183183
using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
184184
using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>;
185185

186+
RealtimeGoalHandleBuffer rt_active_goal_; ///< Currently active action goal, if any.
186187
rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
187-
RealtimeGoalHandleBuffer rt_active_goal_; ///< Currently active action goal, if any.
188188
std::atomic<bool> rt_has_pending_goal_{false}; ///< Is there a pending action goal?
189189
rclcpp::TimerBase::SharedPtr goal_handle_timer_;
190190
rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);

0 commit comments

Comments
 (0)