moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
moveit::hybrid_planning::SimpleSampler Class Reference

#include <simple_sampler.h>

Inheritance diagram for moveit::hybrid_planning::SimpleSampler:
Inheritance graph
[legend]
Collaboration diagram for moveit::hybrid_planning::SimpleSampler:
Collaboration graph
[legend]

Public Member Functions

 SimpleSampler ()=default
 
 ~SimpleSampler () override=default
 
bool initialize ([[maybe_unused]] 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 &current_state, robot_trajectory::RobotTrajectory &local_trajectory) override
 
double getTrajectoryProgress ([[maybe_unused]] const moveit::core::RobotState &current_state) override
 
bool reset () override
 
- Public Member Functions inherited from moveit::hybrid_planning::TrajectoryOperatorInterface
 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 double getTrajectoryProgress (const moveit::core::RobotState &current_state)=0
 

Additional Inherited Members

- Protected Attributes inherited from moveit::hybrid_planning::TrajectoryOperatorInterface
robot_trajectory::RobotTrajectoryPtr reference_trajectory_
 
std::string group_
 

Detailed Description

Definition at line 46 of file simple_sampler.h.

Constructor & Destructor Documentation

◆ SimpleSampler()

moveit::hybrid_planning::SimpleSampler::SimpleSampler ( )
default

◆ ~SimpleSampler()

moveit::hybrid_planning::SimpleSampler::~SimpleSampler ( )
overridedefault

Member Function Documentation

◆ addTrajectorySegment()

moveit_msgs::action::LocalPlanner::Feedback moveit::hybrid_planning::SimpleSampler::addTrajectorySegment ( const robot_trajectory::RobotTrajectory new_trajectory)
overridevirtual

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

Implements moveit::hybrid_planning::TrajectoryOperatorInterface.

Definition at line 57 of file simple_sampler.cpp.

Here is the call graph for this function:

◆ getLocalTrajectory()

moveit_msgs::action::LocalPlanner::Feedback moveit::hybrid_planning::SimpleSampler::getLocalTrajectory ( const moveit::core::RobotState current_state,
robot_trajectory::RobotTrajectory local_trajectory 
)
overridevirtual

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

Implements moveit::hybrid_planning::TrajectoryOperatorInterface.

Definition at line 80 of file simple_sampler.cpp.

Here is the call graph for this function:

◆ getTrajectoryProgress()

double moveit::hybrid_planning::SimpleSampler::getTrajectoryProgress ( [[maybe_unused] ] const moveit::core::RobotState current_state)
override

Definition at line 110 of file simple_sampler.cpp.

◆ initialize()

bool moveit::hybrid_planning::SimpleSampler::initialize ( [[maybe_unused] ] const rclcpp::Node::SharedPtr &  node,
const moveit::core::RobotModelConstPtr &  robot_model,
const std::string &  group_name 
)
override

Definition at line 47 of file simple_sampler.cpp.

◆ reset()

bool moveit::hybrid_planning::SimpleSampler::reset ( )
overridevirtual

Reset trajectory operator to some user-defined initial state

Returns
True if reset was successful

Implements moveit::hybrid_planning::TrajectoryOperatorInterface.

Definition at line 72 of file simple_sampler.cpp.

Here is the caller graph for this function:

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