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

Check if the motion plan request contains stacked path or goal constraints. More...

Inheritance diagram for default_planning_request_adapters::CheckForStackedConstraints:
Inheritance graph
[legend]
Collaboration diagram for default_planning_request_adapters::CheckForStackedConstraints:
Collaboration graph
[legend]

Public Member Functions

 CheckForStackedConstraints ()
 
std::string getDescription () const override
 Get a description of this adapter. More...
 
moveit::core::MoveItErrorCode adapt (const planning_scene::PlanningSceneConstPtr &, planning_interface::MotionPlanRequest &req) const override
 Adapt the planning request. More...
 
- Public Member Functions inherited from planning_interface::PlanningRequestAdapter
virtual void initialize (const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace)
 Initialize parameters using the passed Node and parameter namespace. More...
 

Detailed Description

Check if the motion plan request contains stacked path or goal constraints.

Definition at line 52 of file check_for_stacked_constraints.cpp.

Constructor & Destructor Documentation

◆ CheckForStackedConstraints()

default_planning_request_adapters::CheckForStackedConstraints::CheckForStackedConstraints ( )
inline

Definition at line 55 of file check_for_stacked_constraints.cpp.

Member Function Documentation

◆ adapt()

moveit::core::MoveItErrorCode default_planning_request_adapters::CheckForStackedConstraints::adapt ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
planning_interface::MotionPlanRequest req 
) const
inlineoverridevirtual

Adapt the planning request.

Parameters
planning_sceneRepresentation of the environment for the planning
reqMotion planning request with a set of constraints
Returns
True if response was generated correctly

Implements planning_interface::PlanningRequestAdapter.

Definition at line 64 of file check_for_stacked_constraints.cpp.

Here is the call graph for this function:

◆ getDescription()

std::string default_planning_request_adapters::CheckForStackedConstraints::getDescription ( ) const
inlineoverridevirtual

Get a description of this adapter.

Returns
Returns a short string that identifies the planning request adapter

Implements planning_interface::PlanningRequestAdapter.

Definition at line 59 of file check_for_stacked_constraints.cpp.

Here is the caller graph for this function:

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