|
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 |
|
|
| MOVEIT_CLASS_FORWARD (ValidStateSampler) |
|
| 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 (const 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) |
|
The MoveIt interface to OMPL.
A state validity checker checks:
- Bounds (joint limits).
- Collision.
- Kinematic path constraints.
- Generic user-specified feasibility using the
isStateFeasible
of the planning scene.
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.
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 346 of file ompl_constraints.cpp.