Aikido
OMPLConfigurationToConfigurationPlanner.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PLANNER_OMPL_OMPLCONFIGURATIONTOCONFIGURATIONPLANNER_HPP_
2 #define AIKIDO_PLANNER_OMPL_OMPLCONFIGURATIONTOCONFIGURATIONPLANNER_HPP_
3 
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>
10 
11 #include "aikido/common/RNG.hpp"
20 
21 namespace aikido {
22 namespace planner {
23 namespace ompl {
24 
28 template <class PlannerType>
31 {
32 public:
55  common::RNG* rng = nullptr,
56  statespace::ConstInterpolatorPtr interpolator = nullptr,
57  distance::DistanceMetricPtr dmetric = nullptr,
58  constraint::SampleablePtr sampler = nullptr,
59  constraint::ConstTestablePtr boundsConstraint = nullptr,
60  constraint::ProjectablePtr boundsProjector = nullptr,
61  double maxDistanceBtwValidityChecks = 0.1);
62 
76  const SolvableProblem& problem, Result* result = nullptr) override;
77 
80 
81 protected:
84 };
85 
86 } // namespace ompl
87 } // namespace planner
88 } // namespace aikido
89 
91 
92 #endif // AIKIDO_PLANNER_OMPL_OMPLCONFIGURATIONTOCONFIGURATIONPLANNER_HPP_
RNG.hpp
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::constraint::ProjectablePtr
std::shared_ptr< Projectable > ProjectablePtr
Definition: Projectable.hpp:33
aikido::distance::DistanceMetricPtr
std::shared_ptr< DistanceMetric > DistanceMetricPtr
Definition: DistanceMetric.hpp:10
StateSpace.hpp
aikido::statespace::ConstStateSpacePtr
std::shared_ptr< const StateSpace > ConstStateSpacePtr
Definition: StateSpace.hpp:15
aikido::planner::ConfigurationToConfigurationPlanner
Base planner class for ConfigurationToConfiguration planning problem.
Definition: ConfigurationToConfigurationPlanner.hpp:12
aikido::planner::ompl::OMPLConfigurationToConfigurationPlanner
Creates an OMPL Planner.
Definition: OMPLConfigurationToConfigurationPlanner.hpp:29
aikido::constraint::SampleablePtr
std::shared_ptr< Sampleable > SampleablePtr
Definition: Sampleable.hpp:16
aikido::statespace::ConstInterpolatorPtr
std::shared_ptr< const Interpolator > ConstInterpolatorPtr
Definition: Interpolator.hpp:12
aikido::trajectory::TrajectoryPtr
std::shared_ptr< Trajectory > TrajectoryPtr
Definition: Trajectory.hpp:13
Sampleable.hpp
aikido::planner::ompl::OMPLConfigurationToConfigurationPlanner::mPlanner
::ompl::base::PlannerPtr mPlanner
Pointer to the underlying OMPL Planner.
Definition: OMPLConfigurationToConfigurationPlanner.hpp:83
Projectable.hpp
aikido::planner::SingleProblemPlanner< ConfigurationToConfigurationPlanner, ConfigurationToConfiguration >::SolvableProblem
ConfigurationToConfiguration SolvableProblem
Definition: SingleProblemPlanner.hpp:25
ConfigurationToConfiguration.hpp
aikido::planner::ompl::OMPLConfigurationToConfigurationPlanner::getOMPLPlanner
::ompl::base::PlannerPtr getOMPLPlanner()
Returns the underlying OMPL planner used.
Definition: OMPLConfigurationToConfigurationPlanner-impl.hpp:186
aikido::common::RNG
Implementation of the C++11 "random engine" concept that uses virtual function calls to erase the typ...
Definition: RNG.hpp:24
OMPLConfigurationToConfigurationPlanner-impl.hpp
Testable.hpp
DistanceMetric.hpp
aikido::planner::PlannerPtr
std::shared_ptr< Planner > PlannerPtr
Definition: Planner.hpp:14
ConfigurationToConfigurationPlanner.hpp
aikido::planner::ompl::OMPLConfigurationToConfigurationPlanner::OMPLConfigurationToConfigurationPlanner
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
aikido::planner::ompl::OMPLConfigurationToConfigurationPlanner::plan
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
GeometricStateSpace.hpp
aikido::planner::Planner::Result
Base class for planning result of various planning problems.
Definition: Planner.hpp:58
aikido::constraint::ConstTestablePtr
std::shared_ptr< const Testable > ConstTestablePtr
Definition: Testable.hpp:13