#include <pose_model_state_space_factory.h>
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. | |
PoseModelStateSpaceFactory () | |
Protected Member Functions | |
virtual ModelBasedStateSpacePtr | allocStateSpace (const ModelBasedStateSpaceSpecification &space_spec) const |
Definition at line 44 of file pose_model_state_space_factory.h.
Definition at line 40 of file pose_model_state_space_factory.cpp.
ompl_interface::ModelBasedStateSpacePtr ompl_interface::PoseModelStateSpaceFactory::allocStateSpace | ( | const ModelBasedStateSpaceSpecification & | space_spec | ) | const [protected, virtual] |
Implements ompl_interface::ModelBasedStateSpaceFactory.
Definition at line 85 of file pose_model_state_space_factory.cpp.
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.