moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <model_based_state_space_factory.h>
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. | |
Protected Member Functions | |
virtual ModelBasedStateSpacePtr | allocStateSpace (const ModelBasedStateSpaceSpecification &space_spec) const =0 |
Protected Attributes | |
std::string | type_ |
Definition at line 47 of file model_based_state_space_factory.h.
|
inline |
Definition at line 50 of file model_based_state_space_factory.h.
|
inlinevirtual |
Definition at line 54 of file model_based_state_space_factory.h.
|
protectedpure virtual |
Implemented in ompl_interface::ConstrainedPlanningStateSpaceFactory, ompl_interface::JointModelStateSpaceFactory, and ompl_interface::PoseModelStateSpaceFactory.
|
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::ConstrainedPlanningStateSpaceFactory, ompl_interface::JointModelStateSpaceFactory, and ompl_interface::PoseModelStateSpaceFactory.
ompl_interface::ModelBasedStateSpacePtr ompl_interface::ModelBasedStateSpaceFactory::getNewStateSpace | ( | const ModelBasedStateSpaceSpecification & | space_spec | ) | const |
Definition at line 40 of file model_based_state_space_factory.cpp.
|
inline |
Definition at line 60 of file model_based_state_space_factory.h.
|
protected |
Definition at line 74 of file model_based_state_space_factory.h.