moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <trajectory_operator_interface.h>
Public Member Functions | |
TrajectoryOperatorInterface ()=default | |
TrajectoryOperatorInterface (const TrajectoryOperatorInterface &)=default | |
TrajectoryOperatorInterface (TrajectoryOperatorInterface &&)=default | |
TrajectoryOperatorInterface & | operator= (const TrajectoryOperatorInterface &)=default |
TrajectoryOperatorInterface & | operator= (TrajectoryOperatorInterface &&)=default |
virtual | ~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 |
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 |
virtual bool | reset ()=0 |
Protected Attributes | |
robot_trajectory::RobotTrajectoryPtr | reference_trajectory_ |
std::string | group_ |
Class TrajectoryOperatorInterface - Base class for a trajectory operator. The operator's task is manage the local planner's global reference trajectory. This includes trajectory matching based on the current state to identify the current planning problem and blending of new global trajectory updates into the currently processed reference trajectory.
Definition at line 60 of file trajectory_operator_interface.h.
|
default |
|
default |
|
default |
|
virtualdefault |
|
pure virtual |
Add a new reference trajectory segment to the vector of global trajectory segments to process
new_trajectory | New reference trajectory segment to add |
Implemented in moveit::hybrid_planning::SimpleSampler.
|
pure virtual |
Return the current local constraints based on the newest robot state
current_state | Current RobotState |
Implemented in moveit::hybrid_planning::SimpleSampler.
|
pure virtual |
Return the processing status of the reference trajectory's execution based on a user defined metric.
current_state | Current RobotState |
|
pure virtual |
Initialize trajectory operator
node | Node handle to access parameters |
robot_model | Robot model |
group_name | Name of the joint group the trajectory uses |
|
default |
|
default |
|
pure virtual |
Reset trajectory operator to some user-defined initial state
Implemented in moveit::hybrid_planning::SimpleSampler.
|
protected |
Definition at line 113 of file trajectory_operator_interface.h.
|
protected |
Definition at line 112 of file trajectory_operator_interface.h.