Skip to content

Commit 8287413

Browse files
authored
Fix JTC crashing when shutdown while executing (backport #1960) (#1962)
1 parent 1aad51b commit 8287413

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
@@ -173,8 +173,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
173173
using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
174174
using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>;
175175

176+
RealtimeGoalHandleBuffer rt_active_goal_; ///< Currently active action goal, if any.
176177
rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
177-
RealtimeGoalHandleBuffer rt_active_goal_; ///< Currently active action goal, if any.
178178
std::atomic<bool> rt_has_pending_goal_{false}; ///< Is there a pending action goal?
179179
rclcpp::TimerBase::SharedPtr goal_handle_timer_;
180180
rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);

0 commit comments

Comments
 (0)