moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Protected Attributes | List of all members
moveit::hybrid_planning::TrajectoryOperatorInterface Class Referenceabstract

#include <trajectory_operator_interface.h>

Inheritance diagram for moveit::hybrid_planning::TrajectoryOperatorInterface:
Inheritance graph
[legend]

Public Member Functions

 TrajectoryOperatorInterface ()=default
 
 TrajectoryOperatorInterface (const TrajectoryOperatorInterface &)=default
 
 TrajectoryOperatorInterface (TrajectoryOperatorInterface &&)=default
 
TrajectoryOperatorInterfaceoperator= (const TrajectoryOperatorInterface &)=default
 
TrajectoryOperatorInterfaceoperator= (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 &current_state, robot_trajectory::RobotTrajectory &local_trajectory)=0
 
virtual double getTrajectoryProgress (const moveit::core::RobotState &current_state)=0
 
virtual bool reset ()=0
 

Protected Attributes

robot_trajectory::RobotTrajectoryPtr reference_trajectory_
 
std::string group_
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ TrajectoryOperatorInterface() [1/3]

moveit::hybrid_planning::TrajectoryOperatorInterface::TrajectoryOperatorInterface ( )
default

◆ TrajectoryOperatorInterface() [2/3]

moveit::hybrid_planning::TrajectoryOperatorInterface::TrajectoryOperatorInterface ( const TrajectoryOperatorInterface )
default

◆ TrajectoryOperatorInterface() [3/3]

moveit::hybrid_planning::TrajectoryOperatorInterface::TrajectoryOperatorInterface ( TrajectoryOperatorInterface &&  )
default

◆ ~TrajectoryOperatorInterface()

virtual moveit::hybrid_planning::TrajectoryOperatorInterface::~TrajectoryOperatorInterface ( )
virtualdefault

Member Function Documentation

◆ addTrajectorySegment()

virtual moveit_msgs::action::LocalPlanner::Feedback moveit::hybrid_planning::TrajectoryOperatorInterface::addTrajectorySegment ( const robot_trajectory::RobotTrajectory new_trajectory)
pure virtual

Add a new reference trajectory segment to the vector of global trajectory segments to process

Parameters
new_trajectoryNew reference trajectory segment to add
Returns
True if segment was successfully added

Implemented in moveit::hybrid_planning::SimpleSampler.

◆ getLocalTrajectory()

virtual moveit_msgs::action::LocalPlanner::Feedback moveit::hybrid_planning::TrajectoryOperatorInterface::getLocalTrajectory ( const moveit::core::RobotState current_state,
robot_trajectory::RobotTrajectory local_trajectory 
)
pure virtual

Return the current local constraints based on the newest robot state

Parameters
current_stateCurrent RobotState
Returns
Current local constraints that define the local planning goal

Implemented in moveit::hybrid_planning::SimpleSampler.

◆ getTrajectoryProgress()

virtual double moveit::hybrid_planning::TrajectoryOperatorInterface::getTrajectoryProgress ( const moveit::core::RobotState current_state)
pure virtual

Return the processing status of the reference trajectory's execution based on a user defined metric.

Parameters
current_stateCurrent RobotState
Returns
A value between 0.0 (start) to 1.0 (completion).

◆ initialize()

virtual bool moveit::hybrid_planning::TrajectoryOperatorInterface::initialize ( const rclcpp::Node::SharedPtr &  node,
const moveit::core::RobotModelConstPtr &  robot_model,
const std::string &  group_name 
)
pure virtual

Initialize trajectory operator

Parameters
nodeNode handle to access parameters
robot_modelRobot model
group_nameName of the joint group the trajectory uses
Returns
True if initialization was successful

◆ operator=() [1/2]

TrajectoryOperatorInterface& moveit::hybrid_planning::TrajectoryOperatorInterface::operator= ( const TrajectoryOperatorInterface )
default

◆ operator=() [2/2]

TrajectoryOperatorInterface& moveit::hybrid_planning::TrajectoryOperatorInterface::operator= ( TrajectoryOperatorInterface &&  )
default

◆ reset()

virtual bool moveit::hybrid_planning::TrajectoryOperatorInterface::reset ( )
pure virtual

Reset trajectory operator to some user-defined initial state

Returns
True if reset was successful

Implemented in moveit::hybrid_planning::SimpleSampler.

Member Data Documentation

◆ group_

std::string moveit::hybrid_planning::TrajectoryOperatorInterface::group_
protected

Definition at line 113 of file trajectory_operator_interface.h.

◆ reference_trajectory_

robot_trajectory::RobotTrajectoryPtr moveit::hybrid_planning::TrajectoryOperatorInterface::reference_trajectory_
protected

Definition at line 112 of file trajectory_operator_interface.h.


The documentation for this class was generated from the following file: