Public Member Functions | Protected Member Functions | Protected Attributes
ompl_interface::ModelBasedStateSpaceFactory Class Reference

#include <model_based_state_space_factory.h>

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

List of all members.

Public Member Functions

virtual int canRepresentProblem (const std::string &group, const moveit_msgs::MotionPlanRequest &req, const robot_model::RobotModelConstPtr &kmodel) 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.
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 =0

Protected Attributes

std::string type_

Detailed Description

Definition at line 48 of file model_based_state_space_factory.h.


Constructor & Destructor Documentation

Definition at line 51 of file model_based_state_space_factory.h.

Definition at line 55 of file model_based_state_space_factory.h.


Member Function Documentation

virtual int ompl_interface::ModelBasedStateSpaceFactory::canRepresentProblem ( const std::string &  group,
const moveit_msgs::MotionPlanRequest req,
const robot_model::RobotModelConstPtr &  kmodel 
) 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::JointModelStateSpaceFactory, and ompl_interface::PoseModelStateSpaceFactory.

Definition at line 40 of file model_based_state_space_factory.cpp.

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

Definition at line 61 of file model_based_state_space_factory.h.


Member Data Documentation

Definition at line 75 of file model_based_state_space_factory.h.


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


ompl
Author(s): Ioan Sucan
autogenerated on Mon Jul 24 2017 02:21:33