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 @@ -153,9 +153,9 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
153
153
// Timeout to consider commands old
154
154
double cmd_timeout_;
155
155
// True if holding position or repeating last trajectory point in case of success
156
- std::atomic<bool > rt_is_holding_;
156
+ std::atomic<bool > rt_is_holding_{ false } ;
157
157
// TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported
158
- bool subscriber_is_active_ = false ;
158
+ std::atomic< bool > subscriber_is_active_{ false } ;
159
159
rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
160
160
nullptr ;
161
161
@@ -179,8 +179,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
179
179
using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>;
180
180
181
181
rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
182
- RealtimeGoalHandleBuffer rt_active_goal_; // /< Currently active action goal, if any.
183
- std::atomic<bool > rt_has_pending_goal_; // /< Is there a pending action goal?
182
+ RealtimeGoalHandleBuffer rt_active_goal_; // /< Currently active action goal, if any.
183
+ std::atomic<bool > rt_has_pending_goal_{ false }; // /< Is there a pending action goal?
184
184
rclcpp::TimerBase::SharedPtr goal_handle_timer_;
185
185
rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
186
186
You can’t perform that action at this time.
0 commit comments