Aikido
Planner.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_OMPL_OMPLPLANNER_HPP_
2 #define AIKIDO_OMPL_OMPLPLANNER_HPP_
3 
4 #include <chrono>
5 #include <utility> // std::pair
6 
7 #include <ompl/base/Planner.h>
8 #include <ompl/base/ProblemDefinition.h>
9 #include <ompl/base/ScopedState.h>
10 #include <ompl/base/SpaceInformation.h>
11 #include <ompl/base/goals/GoalRegion.h>
12 #include <ompl/geometric/PathSimplifier.h>
13 
23 
24 namespace aikido {
25 namespace planner {
26 namespace ompl {
27 
52 template <class PlannerType>
54  const statespace::StateSpace::State* _start,
55  const statespace::StateSpace::State* _goal,
57  statespace::InterpolatorPtr _interpolator,
60  constraint::TestablePtr _validityConstraint,
61  constraint::TestablePtr _boundsConstraint,
62  constraint::ProjectablePtr _boundsProjector,
63  double _maxPlanTime,
64  double _maxDistanceBtwValidityChecks);
65 
93 template <class PlannerType>
95  const statespace::StateSpace::State* _start,
96  constraint::TestablePtr _goalTestable,
97  constraint::SampleablePtr _goalSampler,
99  statespace::InterpolatorPtr _interpolator,
101  constraint::SampleablePtr _sampler,
102  constraint::TestablePtr _validityConstraint,
103  constraint::TestablePtr _boundsConstraint,
104  constraint::ProjectablePtr _boundsProjector,
105  double _maxPlanTime,
106  double _maxDistanceBtwValidityChecks);
107 
142  const statespace::StateSpace::State* _start,
143  constraint::TestablePtr _goalTestable,
144  constraint::SampleablePtr _goalSampler,
145  constraint::ProjectablePtr _trajConstraint,
146  statespace::ConstStateSpacePtr _stateSpace,
147  statespace::InterpolatorPtr _interpolator,
149  constraint::SampleablePtr _sampler,
150  constraint::TestablePtr _validityConstraint,
151  constraint::TestablePtr _boundsConstraint,
152  constraint::ProjectablePtr _boundsProjector,
153  double _maxPlanTime,
154  double _maxExtensionDistance,
155  double _maxDistanceBtwProjections,
156  double _minStepsize);
157 
194  const statespace::StateSpace::State* _start,
195  constraint::TestablePtr _goalTestable,
196  constraint::SampleablePtr _goalSampler,
197  constraint::ProjectablePtr _trajConstraint,
198  statespace::ConstStateSpacePtr _stateSpace,
199  statespace::InterpolatorPtr _interpolator,
201  constraint::SampleablePtr _sampler,
202  constraint::TestablePtr _validityConstraint,
203  constraint::TestablePtr _boundsConstraint,
204  constraint::ProjectablePtr _boundsProjector,
205  double _maxPlanTime,
206  double _maxExtensionDistance,
207  double _maxDistanceBtwProjections,
208  double _minStepsize,
209  double _minTreeConnectionDistance);
210 
230 ::ompl::base::SpaceInformationPtr getSpaceInformation(
231  statespace::ConstStateSpacePtr _stateSpace,
232  statespace::InterpolatorPtr _interpolator,
234  constraint::SampleablePtr _sampler,
235  constraint::TestablePtr _validityConstraint,
236  constraint::TestablePtr _boundsConstraint,
237  constraint::ProjectablePtr _boundsProjector,
238  double _maxDistanceBtwValidityChecks);
239 
247 ompl_shared_ptr<::ompl::base::GoalRegion> getGoalRegion(
248  ::ompl::base::SpaceInformationPtr _si,
249  constraint::TestablePtr _goalTestable,
250  constraint::SampleablePtr _goalSampler);
251 
266  const ::ompl::base::ProblemDefinitionPtr& _pdef,
268  statespace::InterpolatorPtr _interpolator,
269  double _maxPlanTime);
270 
297 std::pair<std::unique_ptr<trajectory::Interpolated>, bool> simplifyOMPL(
298  statespace::StateSpacePtr _stateSpace,
299  statespace::InterpolatorPtr _interpolator,
301  constraint::SampleablePtr _sampler,
302  constraint::TestablePtr _validityConstraint,
303  constraint::TestablePtr _boundsConstraint,
304  constraint::ProjectablePtr _boundsProjector,
305  double _maxDistanceBtwValidityChecks,
306  double _timeout,
307  std::size_t _maxEmptySteps,
308  trajectory::InterpolatedPtr _originalTraj);
309 
314 ::ompl::geometric::PathGeometric toOMPLTrajectory(
315  const trajectory::InterpolatedPtr& _interpolatedTraj,
316  ::ompl::base::SpaceInformationPtr _si);
317 
323 std::unique_ptr<trajectory::Interpolated> toInterpolatedTrajectory(
324  const ::ompl::geometric::PathGeometric& _path,
325  statespace::InterpolatorPtr _interpolator);
326 
327 } // namespace ompl
328 } // namespace planner
329 } // namespace aikido
330 
331 #include "detail/Planner-impl.hpp"
332 
333 #endif
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::constraint::SampleablePtr
std::shared_ptr< Sampleable > SampleablePtr
Definition: Sampleable.hpp:16
aikido::trajectory::InterpolatedPtr
std::shared_ptr< Interpolated > InterpolatedPtr
Definition: Interpolated.hpp:11
Interpolated.hpp
Sampleable.hpp
aikido::planner::ompl::toInterpolatedTrajectory
std::unique_ptr< trajectory::Interpolated > toInterpolatedTrajectory(const ::ompl::geometric::PathGeometric &_path, statespace::InterpolatorPtr _interpolator)
Take an OMPL geometric path and convert it into an interpolated trajectory.
Projectable.hpp
aikido::statespace::InterpolatorPtr
std::shared_ptr< Interpolator > InterpolatorPtr
Definition: Interpolator.hpp:12
aikido::planner::ompl::planOMPL
trajectory::InterpolatedPtr planOMPL(const statespace::StateSpace::State *_start, const statespace::StateSpace::State *_goal, statespace::ConstStateSpacePtr _stateSpace, statespace::InterpolatorPtr _interpolator, distance::DistanceMetricPtr _dmetric, constraint::SampleablePtr _sampler, constraint::TestablePtr _validityConstraint, constraint::TestablePtr _boundsConstraint, constraint::ProjectablePtr _boundsProjector, double _maxPlanTime, double _maxDistanceBtwValidityChecks)
Use the template OMPL Planner type to plan a trajectory that moves from the start to the goal point.
Definition: Planner-impl.hpp:15
aikido::planner::ompl::planCRRT
trajectory::InterpolatedPtr planCRRT(const statespace::StateSpace::State *_start, constraint::TestablePtr _goalTestable, constraint::SampleablePtr _goalSampler, constraint::ProjectablePtr _trajConstraint, statespace::ConstStateSpacePtr _stateSpace, statespace::InterpolatorPtr _interpolator, distance::DistanceMetricPtr _dmetric, constraint::SampleablePtr _sampler, constraint::TestablePtr _validityConstraint, constraint::TestablePtr _boundsConstraint, constraint::ProjectablePtr _boundsProjector, double _maxPlanTime, double _maxExtensionDistance, double _maxDistanceBtwProjections, double _minStepsize)
Use the CRRT planner to plan a trajectory that moves from the start to a goal region while respecting...
aikido::planner::ompl::getSpaceInformation
::ompl::base::SpaceInformationPtr getSpaceInformation(statespace::ConstStateSpacePtr _stateSpace, statespace::InterpolatorPtr _interpolator, distance::DistanceMetricPtr _dmetric, constraint::SampleablePtr _sampler, constraint::TestablePtr _validityConstraint, constraint::TestablePtr _boundsConstraint, constraint::ProjectablePtr _boundsProjector, double _maxDistanceBtwValidityChecks)
Generate an OMPL SpaceInformation from aikido components.
aikido::planner::ompl::planCRRTConnect
trajectory::InterpolatedPtr planCRRTConnect(const statespace::StateSpace::State *_start, constraint::TestablePtr _goalTestable, constraint::SampleablePtr _goalSampler, constraint::ProjectablePtr _trajConstraint, statespace::ConstStateSpacePtr _stateSpace, statespace::InterpolatorPtr _interpolator, distance::DistanceMetricPtr _dmetric, constraint::SampleablePtr _sampler, constraint::TestablePtr _validityConstraint, constraint::TestablePtr _boundsConstraint, constraint::ProjectablePtr _boundsProjector, double _maxPlanTime, double _maxExtensionDistance, double _maxDistanceBtwProjections, double _minStepsize, double _minTreeConnectionDistance)
Use the CRRT planner to plan a trajectory that moves from the start to a goal region while respecting...
Testable.hpp
DistanceMetric.hpp
BackwardCompatibility.hpp
aikido::statespace::StateSpacePtr
std::shared_ptr< StateSpace > StateSpacePtr
Definition: StateSpace.hpp:15
aikido::planner::PlannerPtr
std::shared_ptr< Planner > PlannerPtr
Definition: Planner.hpp:14
aikido::constraint::TestablePtr
std::shared_ptr< Testable > TestablePtr
Definition: Testable.hpp:13
Planner-impl.hpp
aikido::planner::ompl::simplifyOMPL
std::pair< std::unique_ptr< trajectory::Interpolated >, bool > simplifyOMPL(statespace::StateSpacePtr _stateSpace, statespace::InterpolatorPtr _interpolator, distance::DistanceMetricPtr _dmetric, constraint::SampleablePtr _sampler, constraint::TestablePtr _validityConstraint, constraint::TestablePtr _boundsConstraint, constraint::ProjectablePtr _boundsProjector, double _maxDistanceBtwValidityChecks, double _timeout, std::size_t _maxEmptySteps, trajectory::InterpolatedPtr _originalTraj)
Take in an aikido trajectory and simplify it using OMPL methods.
aikido::planner::ompl::toOMPLTrajectory
::ompl::geometric::PathGeometric toOMPLTrajectory(const trajectory::InterpolatedPtr &_interpolatedTraj, ::ompl::base::SpaceInformationPtr _si)
Take an interpolated trajectory and convert it into OMPL geometric path.
Interpolator.hpp
GeometricStateSpace.hpp
aikido::planner::ompl::getGoalRegion
ompl_shared_ptr<::ompl::base::GoalRegion > getGoalRegion(::ompl::base::SpaceInformationPtr _si, constraint::TestablePtr _goalTestable, constraint::SampleablePtr _goalSampler)
Create an OMPL GoalRegion from a Testable and Sampler that describe the goal region.