moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Typedefs | Functions
ompl_interface Namespace Reference

The MoveIt interface to OMPL. More...

Classes

class  ConstrainedGoalSampler
 
class  ConstrainedSampler
 
class  ConstraintApproximation
 
struct  ConstraintApproximationConstructionOptions
 
struct  ConstraintApproximationConstructionResults
 
class  ConstraintsLibrary
 
class  GoalSampleableRegionMux
 
class  Bounds
 Represents upper and lower bound on the elements of a vector. More...
 
class  BaseConstraint
 Abstract base class for different types of constraints, implementations of ompl::base::Constraint. More...
 
class  BoxConstraint
 Box shaped position constraints. More...
 
class  EqualityPositionConstraint
 Equality constraints on a link's position. More...
 
class  OrientationConstraint
 Orientation constraints parameterized using exponential coordinates. More...
 
class  ProjectionEvaluatorLinkPose
 
class  ProjectionEvaluatorJointValue
 
class  StateValidityChecker
 An interface for a OMPL state validity checker. More...
 
class  ConstrainedPlanningStateValidityChecker
 A StateValidityChecker that can handle states of type ompl::base::ConstraintStateSpace::StateType. More...
 
class  TSStateStorage
 
struct  ModelBasedPlanningContextSpecification
 
class  ModelBasedPlanningContext
 
class  OMPLInterface
 
class  ConstrainedPlanningStateSpace
 State space to be used in combination with OMPL's constrained planning functionality. More...
 
class  ConstrainedPlanningStateSpaceFactory
 
class  JointModelStateSpace
 
class  JointModelStateSpaceFactory
 
struct  ModelBasedStateSpaceSpecification
 
class  ModelBasedStateSpace
 
class  ModelBasedStateSpaceFactory
 
class  PoseModelStateSpace
 
class  PoseModelStateSpaceFactory
 
class  MultiQueryPlannerAllocator
 
class  PlanningContextManager
 
class  ConstraintApproximationStateSampler
 
class  OMPLPlannerManager
 

Typedefs

typedef ompl::base::StateStorageWithMetadata< std::vector< std::size_t > > ConstraintApproximationStateStorage
 
typedef std::function< bool(const ompl::base::State *, const ompl::base::State *)> ConstraintStateStorageOrderFn
 
typedef std::pair< std::vector< std::size_t >, std::map< std::size_t, std::pair< std::size_t, std::size_t > > > ConstrainedStateMetadata
 
typedef std::function< ob::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name, const ModelBasedPlanningContextSpecification &spec)> ConfiguredPlannerAllocator
 
typedef std::function< ConfiguredPlannerAllocator(const std::string &planner_type)> ConfiguredPlannerSelector
 
typedef std::function< bool(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state)> InterpolationFunction
 
typedef std::function< double(const ompl::base::State *state1, const ompl::base::State *state2)> DistanceFunction
 

Functions

 MOVEIT_CLASS_FORWARD (ConstraintApproximation)
 
 MOVEIT_CLASS_FORWARD (ConstraintsLibrary)
 
 MOVEIT_CLASS_FORWARD (BaseConstraint)
 
 MOVEIT_CLASS_FORWARD (BoxConstraint)
 
 MOVEIT_CLASS_FORWARD (OrientationConstraint)
 
std::ostream & operator<< (std::ostream &os, const ompl_interface::Bounds &bounds)
 Pretty printing of bounds. More...
 
Bounds positionConstraintMsgToBoundVector (const moveit_msgs::msg::PositionConstraint &pos_con)
 Extract position constraints from the MoveIt message. More...
 
Bounds orientationConstraintMsgToBoundVector (const moveit_msgs::msg::OrientationConstraint &ori_con)
 Extract orientation constraints from the MoveIt message. More...
 
ompl::base::ConstraintPtr createOMPLConstraints (const moveit::core::RobotModelConstPtr &robot_model, const std::string &group, const moveit_msgs::msg::Constraints &constraints)
 Factory to create constraints based on what is in the MoveIt constraint message. More...
 
Eigen::Matrix3d angularVelocityToAngleAxis (double angle, const Eigen::Ref< const Eigen::Vector3d > &axis)
 Return a matrix to convert angular velocity to angle-axis velocity Based on: https://ethz.ch/content/dam/ethz/special-interest/mavt/robotics-n-intelligent-systems/rsl-dam/documents/RobotDynamics2016/RD2016script.pdf Eq. 2.107. More...
 
 MOVEIT_CLASS_FORWARD (ModelBasedPlanningContext)
 
 MOVEIT_CLASS_FORWARD (ConstrainedPlanningStateSpace)
 
 OMPL_CLASS_FORWARD (ModelBasedStateSpace)
 
 MOVEIT_CLASS_FORWARD (ModelBasedStateSpaceFactory)
 
bool interpolateUsingStoredStates (const ConstraintApproximationStateStorage *state_storage, const ob::State *from, const ob::State *to, const double t, ob::State *state)
 
ompl::base::StateSamplerPtr allocConstraintApproximationStateSampler (const ob::StateSpace *space, const std::vector< int > &expected_signature, const ConstraintApproximationStateStorage *state_storage, std::size_t milestones)
 
template<>
ompl::base::Planner * MultiQueryPlannerAllocator::allocatePersistentPlanner< ompl::geometric::PRM > (const ob::PlannerData &data)
 
template<>
ompl::base::Planner * MultiQueryPlannerAllocator::allocatePersistentPlanner< ompl::geometric::PRMstar > (const ob::PlannerData &data)
 
template<>
ompl::base::Planner * MultiQueryPlannerAllocator::allocatePersistentPlanner< ompl::geometric::LazyPRM > (const ob::PlannerData &data)
 
template<>
ompl::base::Planner * MultiQueryPlannerAllocator::allocatePersistentPlanner< ompl::geometric::LazyPRMstar > (const ob::PlannerData &data)
 

Detailed Description

The MoveIt interface to OMPL.

A state validity checker checks:

IMPORTANT: Although the isValid method takes the state as const ompl::base::State* state, it uses const_cast to modify the validity of the state with markInvalid and markValid for caching.

Typedef Documentation

◆ ConfiguredPlannerAllocator

typedef std::function<ob::PlannerPtr(const ompl::base::SpaceInformationPtr& si, const std::string& name, const ModelBasedPlanningContextSpecification& spec)> ompl_interface::ConfiguredPlannerAllocator

Definition at line 61 of file model_based_planning_context.h.

◆ ConfiguredPlannerSelector

typedef std::function<ConfiguredPlannerAllocator(const std::string& planner_type)> ompl_interface::ConfiguredPlannerSelector

Definition at line 62 of file model_based_planning_context.h.

◆ ConstrainedStateMetadata

typedef std::pair<std::vector<std::size_t>, std::map<std::size_t, std::pair<std::size_t, std::size_t> > > ompl_interface::ConstrainedStateMetadata

Definition at line 49 of file constraints_library.h.

◆ ConstraintApproximationStateStorage

typedef ompl::base::StateStorageWithMetadata< ConstrainedStateMetadata > ompl_interface::ConstraintApproximationStateStorage

Definition at line 47 of file constraint_approximations.h.

◆ ConstraintStateStorageOrderFn

typedef std::function<bool(const ompl::base::State*, const ompl::base::State*)> ompl_interface::ConstraintStateStorageOrderFn

Definition at line 48 of file constraint_approximations.h.

◆ DistanceFunction

typedef std::function<double(const ompl::base::State* state1, const ompl::base::State* state2)> ompl_interface::DistanceFunction

Definition at line 50 of file model_based_state_space.h.

◆ InterpolationFunction

typedef std::function<bool(const ompl::base::State* from, const ompl::base::State* to, const double t, ompl::base::State* state)> ompl_interface::InterpolationFunction

Definition at line 49 of file model_based_state_space.h.

Function Documentation

◆ allocConstraintApproximationStateSampler()

ompl::base::StateSamplerPtr ompl_interface::allocConstraintApproximationStateSampler ( const ob::StateSpace *  space,
const std::vector< int > &  expected_signature,
const ConstraintApproximationStateStorage state_storage,
std::size_t  milestones 
)

Definition at line 233 of file constraints_library.cpp.

Here is the caller graph for this function:

◆ angularVelocityToAngleAxis()

Eigen::Matrix3d ompl_interface::angularVelocityToAngleAxis ( double  angle,
const Eigen::Ref< const Eigen::Vector3d > &  axis 
)
inline

Return a matrix to convert angular velocity to angle-axis velocity Based on: https://ethz.ch/content/dam/ethz/special-interest/mavt/robotics-n-intelligent-systems/rsl-dam/documents/RobotDynamics2016/RD2016script.pdf Eq. 2.107.

Definition at line 449 of file ompl_constraints.h.

Here is the caller graph for this function:

◆ createOMPLConstraints()

ompl::base::ConstraintPtr ompl_interface::createOMPLConstraints ( const moveit::core::RobotModelConstPtr &  robot_model,
const std::string &  group,
const moveit_msgs::msg::Constraints &  constraints 
)

Factory to create constraints based on what is in the MoveIt constraint message.

Definition at line 370 of file ompl_constraints.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ interpolateUsingStoredStates()

bool ompl_interface::interpolateUsingStoredStates ( const ConstraintApproximationStateStorage state_storage,
const ob::State *  from,
const ob::State *  to,
const double  t,
ob::State *  state 
)

Definition at line 177 of file constraints_library.cpp.

Here is the caller graph for this function:

◆ MOVEIT_CLASS_FORWARD() [1/8]

ompl_interface::MOVEIT_CLASS_FORWARD ( BaseConstraint  )

◆ MOVEIT_CLASS_FORWARD() [2/8]

ompl_interface::MOVEIT_CLASS_FORWARD ( BoxConstraint  )

◆ MOVEIT_CLASS_FORWARD() [3/8]

ompl_interface::MOVEIT_CLASS_FORWARD ( ConstrainedPlanningStateSpace  )

◆ MOVEIT_CLASS_FORWARD() [4/8]

ompl_interface::MOVEIT_CLASS_FORWARD ( ConstraintApproximation  )

◆ MOVEIT_CLASS_FORWARD() [5/8]

ompl_interface::MOVEIT_CLASS_FORWARD ( ConstraintsLibrary  )

◆ MOVEIT_CLASS_FORWARD() [6/8]

ompl_interface::MOVEIT_CLASS_FORWARD ( ModelBasedPlanningContext  )

◆ MOVEIT_CLASS_FORWARD() [7/8]

ompl_interface::MOVEIT_CLASS_FORWARD ( ModelBasedStateSpaceFactory  )

◆ MOVEIT_CLASS_FORWARD() [8/8]

ompl_interface::MOVEIT_CLASS_FORWARD ( OrientationConstraint  )

◆ MultiQueryPlannerAllocator::allocatePersistentPlanner< ompl::geometric::LazyPRM >()

template<>
ompl::base::Planner* ompl_interface::MultiQueryPlannerAllocator::allocatePersistentPlanner< ompl::geometric::LazyPRM > ( const ob::PlannerData &  data)
inline

Definition at line 242 of file planning_context_manager.cpp.

◆ MultiQueryPlannerAllocator::allocatePersistentPlanner< ompl::geometric::LazyPRMstar >()

template<>
ompl::base::Planner* ompl_interface::MultiQueryPlannerAllocator::allocatePersistentPlanner< ompl::geometric::LazyPRMstar > ( const ob::PlannerData &  data)
inline

Definition at line 248 of file planning_context_manager.cpp.

◆ MultiQueryPlannerAllocator::allocatePersistentPlanner< ompl::geometric::PRM >()

template<>
ompl::base::Planner* ompl_interface::MultiQueryPlannerAllocator::allocatePersistentPlanner< ompl::geometric::PRM > ( const ob::PlannerData &  data)
inline

Definition at line 230 of file planning_context_manager.cpp.

◆ MultiQueryPlannerAllocator::allocatePersistentPlanner< ompl::geometric::PRMstar >()

template<>
ompl::base::Planner* ompl_interface::MultiQueryPlannerAllocator::allocatePersistentPlanner< ompl::geometric::PRMstar > ( const ob::PlannerData &  data)
inline

Definition at line 236 of file planning_context_manager.cpp.

◆ OMPL_CLASS_FORWARD()

ompl_interface::OMPL_CLASS_FORWARD ( ModelBasedStateSpace  )

◆ operator<<()

std::ostream & ompl_interface::operator<< ( std::ostream &  os,
const ompl_interface::Bounds bounds 
)

Pretty printing of bounds.

Definition at line 117 of file ompl_constraints.cpp.

◆ orientationConstraintMsgToBoundVector()

Bounds ompl_interface::orientationConstraintMsgToBoundVector ( const moveit_msgs::msg::OrientationConstraint &  ori_con)

Extract orientation constraints from the MoveIt message.

These bounds are assumed to be centered around the target orientation / desired orientation given in the "orientation" field in the message. These bounds represent orientation error between the desired orientation and the current orientation of the end-effector.

The "absolute_x_axis_tolerance", "absolute_y_axis_tolerance" and "absolute_z_axis_tolerance" are interpreted as the width of the tolerance regions around the target orientation, represented using exponential coordinates.

Definition at line 353 of file ompl_constraints.cpp.

Here is the caller graph for this function:

◆ positionConstraintMsgToBoundVector()

Bounds ompl_interface::positionConstraintMsgToBoundVector ( const moveit_msgs::msg::PositionConstraint &  pos_con)

Extract position constraints from the MoveIt message.

Assumes there is a single primitive of type shape_msgs/SolidPrimitive.BOX. The dimensions of the box are the bounds on the deviation of the link origin from the target pose, given in constraint_regions.primitive_poses[0].

Definition at line 336 of file ompl_constraints.cpp.

Here is the caller graph for this function: