85 std::function<bool(
ExecutableMotionPlan& plan_to_update,
const std::pair<int, int>& trajectory_index)>
95 const trajectory_execution_manager::TrajectoryExecutionManagerPtr& trajectory_execution);
100 return planning_scene_monitor_;
105 return trajectory_execution_manager_;
110 if (trajectory_monitor_)
112 return trajectory_monitor_->getSamplingFrequency();
122 if (trajectory_monitor_)
123 trajectory_monitor_->setSamplingFrequency(freq);
128 default_max_replan_attempts_ = attempts;
133 return default_max_replan_attempts_;
149 bool isRemainingPathValid(
const ExecutableMotionPlan& plan,
const std::pair<int, int>& path_segment);
155 const rclcpp::Node::SharedPtr node_;
156 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
157 trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_;
158 planning_scene_monitor::TrajectoryMonitorPtr trajectory_monitor_;
159 std::vector<std::map<std::string, const moveit::core::AttachedBody*>> plan_components_attached_objects_;
161 unsigned int default_max_replan_attempts_;
166 std::atomic<bool> preemption_requested_{
false };
172 inline bool checkAndClear()
174 return preemption_requested_.exchange(
false);
176 inline void request()
178 preemption_requested_.store(
true);
182 bool new_scene_update_;
184 bool execution_complete_;
185 bool path_became_invalid_;
187 rclcpp::Logger logger_;