52 bool initialize([[maybe_unused]]
const rclcpp::Node::SharedPtr& node,
53 const moveit::core::RobotModelConstPtr& robot_model,
const std::string& group_name)
override;
54 moveit_msgs::action::LocalPlanner::Feedback
56 moveit_msgs::action::LocalPlanner::Feedback
60 bool reset()
override;
65 moveit_msgs::action::LocalPlanner::Feedback feedback_;
Representation of a robot's state. This includes position, velocity, acceleration and effort.
bool initialize(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name) override
moveit_msgs::action::LocalPlanner::Feedback addTrajectorySegment(const robot_trajectory::RobotTrajectory &new_trajectory) override
moveit_msgs::action::LocalPlanner::Feedback getLocalTrajectory(const moveit::core::RobotState ¤t_state, robot_trajectory::RobotTrajectory &local_trajectory) override
double getTrajectoryProgress(const moveit::core::RobotState ¤t_state) override
~SimpleSampler() override=default
Maintain a sequence of waypoints and the time durations between these waypoints.