43 #include <rclcpp/rclcpp.hpp>
53 bool initialize(
const rclcpp::Node::SharedPtr& node,
55 const std::string& )
override;
56 bool reset()
override;
58 moveit_msgs::action::LocalPlanner::Feedback
60 const std::shared_ptr<const moveit_msgs::action::LocalPlanner::Goal> ,
61 trajectory_msgs::msg::JointTrajectory& local_solution)
override;
64 rclcpp::Node::SharedPtr node_;
65 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
66 bool path_invalidation_event_send_;
67 bool stop_before_collision_;
70 size_t num_iterations_stuck_;
71 moveit::core::RobotStatePtr prev_waypoint_target_;
moveit_msgs::action::LocalPlanner::Feedback solve(const robot_trajectory::RobotTrajectory &local_trajectory, const std::shared_ptr< const moveit_msgs::action::LocalPlanner::Goal >, trajectory_msgs::msg::JointTrajectory &local_solution) override
bool initialize(const rclcpp::Node::SharedPtr &node, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor, const std::string &) override
~ForwardTrajectory() override=default
ForwardTrajectory()=default
Maintain a sequence of waypoints and the time durations between these waypoints.