The MoveIt! interface to OMPL. More...
Classes | |
class | ConstrainedGoalSampler |
class | ConstrainedSampler |
struct | ConstraintApproximation |
struct | ConstraintApproximationConstructionOptions |
struct | ConstraintApproximationConstructionResults |
class | ConstraintApproximationStateSampler |
class | ConstraintsLibrary |
class | GoalSampleableRegionMux |
class | JointModelStateSpace |
class | JointModelStateSpaceFactory |
class | ModelBasedPlanningContext |
struct | ModelBasedPlanningContextSpecification |
class | ModelBasedStateSpace |
class | ModelBasedStateSpaceFactory |
struct | ModelBasedStateSpaceSpecification |
class | OMPLInterface |
class | OMPLPlannerManager |
class | PlanningContextManager |
class | PoseModelStateSpace |
class | PoseModelStateSpaceFactory |
class | ProjectionEvaluatorJointValue |
class | ProjectionEvaluatorLinkPose |
struct | same_shared_ptr |
struct | same_shared_ptr< T, boost::shared_ptr< Wrapped > > |
class | StateValidityChecker |
An interface for a OMPL state validity checker. More... | |
class | TSStateStorage |
class | ValidConstrainedSampler |
Typedefs | |
typedef boost::function< ob::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name, const ModelBasedPlanningContextSpecification &spec)> | ConfiguredPlannerAllocator |
typedef boost::function< ConfiguredPlannerAllocator(const std::string &planner_type)> | ConfiguredPlannerSelector |
typedef std::pair< std::vector< std::size_t >, std::map< std::size_t, std::pair< std::size_t, std::size_t > > > | ConstrainedStateMetadata |
typedef ompl::base::StateStorageWithMetadata< ConstrainedStateMetadata > | ConstraintApproximationStateStorage |
typedef boost::function< bool(const ompl::base::State *, const ompl::base::State *)> | ConstraintStateStorageOrderFn |
typedef boost::function< double(const ompl::base::State *state1, const ompl::base::State *state2)> | DistanceFunction |
typedef boost::function< bool(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state)> | InterpolationFunction |
typedef same_shared_ptr< ModelBasedStateSpace, ompl::base::StateSpacePtr >::type | ModelBasedStateSpacePtr |
Functions | |
ompl::base::StateSamplerPtr | allocConstraintApproximationStateSampler (const ob::StateSpace *space, const std::vector< int > &expected_signature, const ConstraintApproximationStateStorage *state_storage, std::size_t milestones) |
bool | interpolateUsingStoredStates (const ConstraintApproximationStateStorage *state_storage, const ob::State *from, const ob::State *to, const double t, ob::State *state) |
MOVEIT_CLASS_FORWARD (ModelBasedStateSpaceFactory) | |
MOVEIT_CLASS_FORWARD (ValidStateSampler) | |
MOVEIT_CLASS_FORWARD (ModelBasedPlanningContext) | |
MOVEIT_CLASS_FORWARD (ConstraintsLibrary) | |
The MoveIt! interface to OMPL.
typedef boost::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.
typedef boost::function<ConfiguredPlannerAllocator(const std::string& planner_type)> ompl_interface::ConfiguredPlannerSelector |
Definition at line 65 of file model_based_planning_context.h.
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 50 of file constraints_library.h.
typedef ompl::base::StateStorageWithMetadata< std::vector< std::size_t > > ompl_interface::ConstraintApproximationStateStorage |
Definition at line 51 of file constraints_library.h.
typedef boost::function<bool(const ompl::base::State*, const ompl::base::State*)> ompl_interface::ConstraintStateStorageOrderFn |
Definition at line 50 of file constraint_approximations.h.
typedef boost::function<double(const ompl::base::State* state1, const ompl::base::State* state2)> ompl_interface::DistanceFunction |
Definition at line 52 of file model_based_state_space.h.
typedef boost::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 51 of file model_based_state_space.h.
typedef same_shared_ptr<ModelBasedStateSpace, ompl::base::StateSpacePtr>::type ompl_interface::ModelBasedStateSpacePtr |
Definition at line 272 of file model_based_state_space.h.
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 189 of file constraints_library.cpp.
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 146 of file constraints_library.cpp.
ompl_interface::MOVEIT_CLASS_FORWARD | ( | ModelBasedStateSpaceFactory | ) |
ompl_interface::MOVEIT_CLASS_FORWARD | ( | ValidStateSampler | ) |
ompl_interface::MOVEIT_CLASS_FORWARD | ( | ModelBasedPlanningContext | ) |
ompl_interface::MOVEIT_CLASS_FORWARD | ( | ConstraintsLibrary | ) |