Public Member Functions | Protected Member Functions | List of all members
ompl_interface::PoseModelStateSpaceFactory Class Reference

#include <pose_model_state_space_factory.h>

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

Public Member Functions

virtual int canRepresentProblem (const std::string &group, const moveit_msgs::MotionPlanRequest &req, const robot_model::RobotModelConstPtr &robot_model) const
 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...
 
 PoseModelStateSpaceFactory ()
 
- Public Member Functions inherited from ompl_interface::ModelBasedStateSpaceFactory
ModelBasedStateSpacePtr getNewStateSpace (const ModelBasedStateSpaceSpecification &space_spec) const
 
const std::string & getType () const
 
 ModelBasedStateSpaceFactory ()
 
virtual ~ModelBasedStateSpaceFactory ()
 

Protected Member Functions

virtual ModelBasedStateSpacePtr allocStateSpace (const ModelBasedStateSpaceSpecification &space_spec) const
 

Additional Inherited Members

- Protected Attributes inherited from ompl_interface::ModelBasedStateSpaceFactory
std::string type_
 

Detailed Description

Definition at line 44 of file pose_model_state_space_factory.h.

Constructor & Destructor Documentation

ompl_interface::PoseModelStateSpaceFactory::PoseModelStateSpaceFactory ( )

Definition at line 40 of file pose_model_state_space_factory.cpp.

Member Function Documentation

ompl_interface::ModelBasedStateSpacePtr ompl_interface::PoseModelStateSpaceFactory::allocStateSpace ( const ModelBasedStateSpaceSpecification space_spec) const
protectedvirtual
int ompl_interface::PoseModelStateSpaceFactory::canRepresentProblem ( const std::string &  group,
const moveit_msgs::MotionPlanRequest req,
const robot_model::RobotModelConstPtr &  kmodel 
) const
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.

Implements ompl_interface::ModelBasedStateSpaceFactory.

Definition at line 45 of file pose_model_state_space_factory.cpp.


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


ompl
Author(s): Ioan Sucan
autogenerated on Sun Oct 18 2020 13:18:01