Go to the documentation of this file. 1 #ifndef AIKIDO_PLANNER_OMPL_OMPLCONFIGURATIONTOCONFIGURATIONPLANNER_HPP_
2 #define AIKIDO_PLANNER_OMPL_OMPLCONFIGURATIONTOCONFIGURATIONPLANNER_HPP_
4 #include <ompl/base/Planner.h>
5 #include <ompl/base/ProblemDefinition.h>
6 #include <ompl/base/ScopedState.h>
7 #include <ompl/base/SpaceInformation.h>
8 #include <ompl/base/goals/GoalRegion.h>
9 #include <ompl/geometric/PathSimplifier.h>
28 template <
class PlannerType>
61 double maxDistanceBtwValidityChecks = 0.1);
92 #endif // AIKIDO_PLANNER_OMPL_OMPLCONFIGURATIONTOCONFIGURATIONPLANNER_HPP_
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
std::shared_ptr< Projectable > ProjectablePtr
Definition: Projectable.hpp:33
std::shared_ptr< DistanceMetric > DistanceMetricPtr
Definition: DistanceMetric.hpp:10
std::shared_ptr< const StateSpace > ConstStateSpacePtr
Definition: StateSpace.hpp:15
Base planner class for ConfigurationToConfiguration planning problem.
Definition: ConfigurationToConfigurationPlanner.hpp:12
Creates an OMPL Planner.
Definition: OMPLConfigurationToConfigurationPlanner.hpp:29
std::shared_ptr< Sampleable > SampleablePtr
Definition: Sampleable.hpp:16
std::shared_ptr< const Interpolator > ConstInterpolatorPtr
Definition: Interpolator.hpp:12
std::shared_ptr< Trajectory > TrajectoryPtr
Definition: Trajectory.hpp:13
::ompl::base::PlannerPtr mPlanner
Pointer to the underlying OMPL Planner.
Definition: OMPLConfigurationToConfigurationPlanner.hpp:83
ConfigurationToConfiguration SolvableProblem
Definition: SingleProblemPlanner.hpp:25
::ompl::base::PlannerPtr getOMPLPlanner()
Returns the underlying OMPL planner used.
Definition: OMPLConfigurationToConfigurationPlanner-impl.hpp:186
Implementation of the C++11 "random engine" concept that uses virtual function calls to erase the typ...
Definition: RNG.hpp:24
std::shared_ptr< Planner > PlannerPtr
Definition: Planner.hpp:14
OMPLConfigurationToConfigurationPlanner(statespace::ConstStateSpacePtr stateSpace, common::RNG *rng=nullptr, statespace::ConstInterpolatorPtr interpolator=nullptr, distance::DistanceMetricPtr dmetric=nullptr, constraint::SampleablePtr sampler=nullptr, constraint::ConstTestablePtr boundsConstraint=nullptr, constraint::ProjectablePtr boundsProjector=nullptr, double maxDistanceBtwValidityChecks=0.1)
Constructor.
Definition: OMPLConfigurationToConfigurationPlanner-impl.hpp:30
trajectory::TrajectoryPtr plan(const SolvableProblem &problem, Result *result=nullptr) override
Plans a trajectory from start state to goal state by using an interpolator to interpolate between the...
Definition: OMPLConfigurationToConfigurationPlanner-impl.hpp:102
Base class for planning result of various planning problems.
Definition: Planner.hpp:58
std::shared_ptr< const Testable > ConstTestablePtr
Definition: Testable.hpp:13