Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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<bool> rt_is_holding_;
std::atomic<bool> rt_is_holding_{false};
// TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported
bool subscriber_is_active_ = false;
std::atomic<bool> subscriber_is_active_{false};
rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
nullptr;

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

rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
RealtimeGoalHandleBuffer rt_active_goal_; ///< Currently active action goal, if any.
std::atomic<bool> rt_has_pending_goal_; ///< Is there a pending action goal?
RealtimeGoalHandleBuffer rt_active_goal_; ///< Currently active action goal, if any.
std::atomic<bool> 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);

Expand Down
Loading