Skip to content

Commit 6920a2a

Browse files
Fix atomic variables in JTC (#1749)
1 parent a4cc58d commit 6920a2a

File tree

1 file changed

+4
-4
lines changed

1 file changed

+4
-4
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -153,9 +153,9 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
153153
// Timeout to consider commands old
154154
double cmd_timeout_;
155155
// 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};
157157
// 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};
159159
rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
160160
nullptr;
161161

@@ -179,8 +179,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
179179
using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>;
180180

181181
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?
184184
rclcpp::TimerBase::SharedPtr goal_handle_timer_;
185185
rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
186186

0 commit comments

Comments
 (0)