41 #include <rclcpp/rclcpp.hpp>
42 #include <rclcpp_action/rclcpp_action.hpp>
44 #include <moveit_msgs/msg/robot_trajectory.hpp>
45 #include <moveit_msgs/msg/constraints.hpp>
47 #include <moveit_msgs/action/local_planner.hpp>
76 virtual bool initialize(
const rclcpp::Node::SharedPtr& node,
const moveit::core::RobotModelConstPtr& robot_model,
77 const std::string& group_name) = 0;
84 virtual moveit_msgs::action::LocalPlanner::Feedback
92 virtual moveit_msgs::action::LocalPlanner::Feedback
Representation of a robot's state. This includes position, velocity, acceleration and effort.
TrajectoryOperatorInterface()=default
virtual bool initialize(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name)=0
virtual moveit_msgs::action::LocalPlanner::Feedback addTrajectorySegment(const robot_trajectory::RobotTrajectory &new_trajectory)=0
robot_trajectory::RobotTrajectoryPtr reference_trajectory_
virtual ~TrajectoryOperatorInterface()=default
TrajectoryOperatorInterface & operator=(TrajectoryOperatorInterface &&)=default
TrajectoryOperatorInterface(const TrajectoryOperatorInterface &)=default
virtual moveit_msgs::action::LocalPlanner::Feedback getLocalTrajectory(const moveit::core::RobotState ¤t_state, robot_trajectory::RobotTrajectory &local_trajectory)=0
virtual double getTrajectoryProgress(const moveit::core::RobotState ¤t_state)=0
TrajectoryOperatorInterface & operator=(const TrajectoryOperatorInterface &)=default
TrajectoryOperatorInterface(TrajectoryOperatorInterface &&)=default
Maintain a sequence of waypoints and the time durations between these waypoints.