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
161
161
// Timeout to consider commands old
162
162
double cmd_timeout_;
163
163
// 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 } ;
165
165
// 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 } ;
167
167
rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
168
168
nullptr ;
169
169
@@ -192,8 +192,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
192
192
using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>;
193
193
194
194
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?
197
197
rclcpp::TimerBase::SharedPtr goal_handle_timer_;
198
198
rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
199
199
You can’t perform that action at this time.
0 commit comments