moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Protected Member Functions | List of all members
ompl_interface::ConstrainedPlanningStateSpaceFactory Class Reference

#include <constrained_planning_state_space_factory.h>

Inheritance diagram for ompl_interface::ConstrainedPlanningStateSpaceFactory:
Inheritance graph
[legend]
Collaboration diagram for ompl_interface::ConstrainedPlanningStateSpaceFactory:
Collaboration graph
[legend]

Public Member Functions

 ConstrainedPlanningStateSpaceFactory ()
 
int canRepresentProblem (const std::string &group, const moveit_msgs::msg::MotionPlanRequest &req, const moveit::core::RobotModelConstPtr &robot_model) const override
 Return a priority that this planner should be used for this specific planning problem. More...
 
- Public Member Functions inherited from ompl_interface::ModelBasedStateSpaceFactory
 ModelBasedStateSpaceFactory ()
 
virtual ~ModelBasedStateSpaceFactory ()
 
ModelBasedStateSpacePtr getNewStateSpace (const ModelBasedStateSpaceSpecification &space_spec) const
 
const std::string & getType () const
 

Protected Member Functions

ModelBasedStateSpacePtr allocStateSpace (const ModelBasedStateSpaceSpecification &space_spec) const override
 

Additional Inherited Members

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

Detailed Description

Definition at line 44 of file constrained_planning_state_space_factory.h.

Constructor & Destructor Documentation

◆ ConstrainedPlanningStateSpaceFactory()

ompl_interface::ConstrainedPlanningStateSpaceFactory::ConstrainedPlanningStateSpaceFactory ( )

Definition at line 43 of file constrained_planning_state_space_factory.cpp.

Member Function Documentation

◆ allocStateSpace()

ModelBasedStateSpacePtr ompl_interface::ConstrainedPlanningStateSpaceFactory::allocStateSpace ( const ModelBasedStateSpaceSpecification space_spec) const
overrideprotectedvirtual

◆ canRepresentProblem()

int ompl_interface::ConstrainedPlanningStateSpaceFactory::canRepresentProblem ( const std::string &  group,
const moveit_msgs::msg::MotionPlanRequest &  req,
const moveit::core::RobotModelConstPtr &  robot_model 
) const
overridevirtual

Return a priority that this planner should be used for this specific planning problem.

This state space factory is currently only used if there is exactly one position or orientation constraint, or if enforce_constrained_state_space was set to true in ompl_planning.yaml. In the first case, we prefer planning in the constrained state space and return a priority of 200. In the second case, it is the only factory to choose from, so the priority does not matter, and it returns a low priority so it will never be chosen when others are available. (The second lowest priority is -1 in the PoseModelStateSpaceFactory.)

For more details on this state space selection process, see: https://github.com/JeroenDM/moveit/pull/2

Implements ompl_interface::ModelBasedStateSpaceFactory.

Definition at line 48 of file constrained_planning_state_space_factory.cpp.


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