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

The CheckStartStateBounds adapter validates if the start state is within the joint limits specified in the URDF. More...

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

Public Member Functions

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

Detailed Description

The CheckStartStateBounds adapter validates if the start state is within the joint limits specified in the URDF.

Definition at line 62 of file check_start_state_bounds.cpp.

Constructor & Destructor Documentation

◆ CheckStartStateBounds()

default_planning_request_adapters::CheckStartStateBounds::CheckStartStateBounds ( )
inline

Definition at line 65 of file check_start_state_bounds.cpp.

Member Function Documentation

◆ adapt()

moveit::core::MoveItErrorCode default_planning_request_adapters::CheckStartStateBounds::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 79 of file check_start_state_bounds.cpp.

Here is the call graph for this function:

◆ getDescription()

std::string default_planning_request_adapters::CheckStartStateBounds::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 74 of file check_start_state_bounds.cpp.

Here is the caller graph for this function:

◆ initialize()

void default_planning_request_adapters::CheckStartStateBounds::initialize ( const rclcpp::Node::SharedPtr &  node,
const std::string &  parameter_namespace 
)
inlineoverridevirtual

Initialize parameters using the passed Node and parameter namespace.

Parameters
nodeNode instance used by the adapter
parameter_namespaceParameter namespace for adapter

The default implementation is empty

Reimplemented from planning_interface::PlanningRequestAdapter.

Definition at line 69 of file check_start_state_bounds.cpp.


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