diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp index 19e74af61d..fecfa3af28 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp @@ -153,9 +153,9 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa // Timeout to consider commands old double cmd_timeout_; // True if holding position or repeating last trajectory point in case of success - std::atomic rt_is_holding_; + std::atomic rt_is_holding_{false}; // TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported - bool subscriber_is_active_ = false; + std::atomic subscriber_is_active_{false}; rclcpp::Subscription::SharedPtr joint_command_subscriber_ = nullptr; @@ -179,8 +179,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer; rclcpp_action::Server::SharedPtr action_server_; - RealtimeGoalHandleBuffer rt_active_goal_; ///< Currently active action goal, if any. - std::atomic rt_has_pending_goal_; ///< Is there a pending action goal? + RealtimeGoalHandleBuffer rt_active_goal_; ///< Currently active action goal, if any. + std::atomic rt_has_pending_goal_{false}; ///< Is there a pending action goal? rclcpp::TimerBase::SharedPtr goal_handle_timer_; rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);