File tree Expand file tree Collapse file tree 1 file changed +4
-4
lines changed
joint_trajectory_controller/include/joint_trajectory_controller Expand file tree Collapse file tree 1 file changed +4
-4
lines changed Original file line number Diff line number Diff line change @@ -161,9 +161,9 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
161161 // Timeout to consider commands old
162162 double cmd_timeout_;
163163 // True if holding position or repeating last trajectory point in case of success
164- std::atomic<bool > rt_is_holding_;
164+ std::atomic<bool > rt_is_holding_{ false } ;
165165 // TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported
166- bool subscriber_is_active_ = false ;
166+ std::atomic< bool > subscriber_is_active_{ false } ;
167167 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
168168 nullptr ;
169169
@@ -192,8 +192,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
192192 using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>;
193193
194194 rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
195- RealtimeGoalHandleBuffer rt_active_goal_; // /< Currently active action goal, if any.
196- std::atomic<bool > rt_has_pending_goal_; // /< Is there a pending action goal?
195+ RealtimeGoalHandleBuffer rt_active_goal_; // /< Currently active action goal, if any.
196+ std::atomic<bool > rt_has_pending_goal_{ false }; // /< Is there a pending action goal?
197197 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
198198 rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
199199
You can’t perform that action at this time.
0 commit comments