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

#include <model_based_state_space_factory.h>

Inheritance diagram for ompl_interface::ModelBasedStateSpaceFactory:
Inheritance graph
[legend]

Public Member Functions

 ModelBasedStateSpaceFactory ()
 
virtual ~ModelBasedStateSpaceFactory ()
 
ModelBasedStateSpacePtr getNewStateSpace (const ModelBasedStateSpaceSpecification &space_spec) const
 
const std::string & getType () const
 
virtual int canRepresentProblem (const std::string &group, const moveit_msgs::msg::MotionPlanRequest &req, const moveit::core::RobotModelConstPtr &robot_model) const =0
 Decide whether the type of state space constructed by this factory could represent problems specified by the user request req for group group. The group group must always be specified and takes precedence over req.group_name, which may be different. More...
 

Protected Member Functions

virtual ModelBasedStateSpacePtr allocStateSpace (const ModelBasedStateSpaceSpecification &space_spec) const =0
 

Protected Attributes

std::string type_
 

Detailed Description

Definition at line 47 of file model_based_state_space_factory.h.

Constructor & Destructor Documentation

◆ ModelBasedStateSpaceFactory()

ompl_interface::ModelBasedStateSpaceFactory::ModelBasedStateSpaceFactory ( )
inline

Definition at line 50 of file model_based_state_space_factory.h.

◆ ~ModelBasedStateSpaceFactory()

virtual ompl_interface::ModelBasedStateSpaceFactory::~ModelBasedStateSpaceFactory ( )
inlinevirtual

Definition at line 54 of file model_based_state_space_factory.h.

Member Function Documentation

◆ allocStateSpace()

virtual ModelBasedStateSpacePtr ompl_interface::ModelBasedStateSpaceFactory::allocStateSpace ( const ModelBasedStateSpaceSpecification space_spec) const
protectedpure virtual

◆ canRepresentProblem()

virtual int ompl_interface::ModelBasedStateSpaceFactory::canRepresentProblem ( const std::string &  group,
const moveit_msgs::msg::MotionPlanRequest &  req,
const moveit::core::RobotModelConstPtr &  robot_model 
) const
pure virtual

Decide whether the type of state space constructed by this factory could represent problems specified by the user request req for group group. The group group must always be specified and takes precedence over req.group_name, which may be different.

Implemented in ompl_interface::PoseModelStateSpaceFactory, ompl_interface::JointModelStateSpaceFactory, and ompl_interface::ConstrainedPlanningStateSpaceFactory.

◆ getNewStateSpace()

ompl_interface::ModelBasedStateSpacePtr ompl_interface::ModelBasedStateSpaceFactory::getNewStateSpace ( const ModelBasedStateSpaceSpecification space_spec) const

Definition at line 40 of file model_based_state_space_factory.cpp.

Here is the call graph for this function:

◆ getType()

const std::string& ompl_interface::ModelBasedStateSpaceFactory::getType ( ) const
inline

Definition at line 60 of file model_based_state_space_factory.h.

Member Data Documentation

◆ type_

std::string ompl_interface::ModelBasedStateSpaceFactory::type_
protected

Definition at line 74 of file model_based_state_space_factory.h.


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