#include <model_based_state_space_factory.h>
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_ |
Definition at line 49 of file model_based_state_space_factory.h.
Definition at line 53 of file model_based_state_space_factory.h.
virtual ompl_interface::ModelBasedStateSpaceFactory::~ModelBasedStateSpaceFactory | ( | ) | [inline, virtual] |
Definition at line 57 of file model_based_state_space_factory.h.
virtual ModelBasedStateSpacePtr ompl_interface::ModelBasedStateSpaceFactory::allocStateSpace | ( | const ModelBasedStateSpaceSpecification & | space_spec | ) | const [protected, pure virtual] |
Implemented in ompl_interface::JointModelStateSpaceFactory, and ompl_interface::PoseModelStateSpaceFactory.
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.
ompl_interface::ModelBasedStateSpacePtr ompl_interface::ModelBasedStateSpaceFactory::getNewStateSpace | ( | const ModelBasedStateSpaceSpecification & | space_spec | ) | const |
Definition at line 39 of file model_based_state_space_factory.cpp.
const std::string& ompl_interface::ModelBasedStateSpaceFactory::getType | ( | ) | const [inline] |
Definition at line 63 of file model_based_state_space_factory.h.
std::string ompl_interface::ModelBasedStateSpaceFactory::type_ [protected] |
Definition at line 77 of file model_based_state_space_factory.h.