Go to the documentation of this file.    1 #ifndef AIKIDO_OMPL_OMPLPLANNER_HPP_ 
    2 #define AIKIDO_OMPL_OMPLPLANNER_HPP_ 
    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> 
   52 template <
class PlannerType>
 
   54     const statespace::StateSpace::State* _start,
 
   55     const statespace::StateSpace::State* _goal,
 
   64     double _maxDistanceBtwValidityChecks);
 
   93 template <
class PlannerType>
 
   95     const statespace::StateSpace::State* _start,
 
  106     double _maxDistanceBtwValidityChecks);
 
  142     const statespace::StateSpace::State* _start,
 
  154     double _maxExtensionDistance,
 
  155     double _maxDistanceBtwProjections,
 
  156     double _minStepsize);
 
  194     const statespace::StateSpace::State* _start,
 
  206     double _maxExtensionDistance,
 
  207     double _maxDistanceBtwProjections,
 
  209     double _minTreeConnectionDistance);
 
  238     double _maxDistanceBtwValidityChecks);
 
  248     ::ompl::base::SpaceInformationPtr _si,
 
  266     const ::ompl::base::ProblemDefinitionPtr& _pdef,
 
  269     double _maxPlanTime);
 
  297 std::pair<std::unique_ptr<trajectory::Interpolated>, 
bool> 
simplifyOMPL(
 
  305     double _maxDistanceBtwValidityChecks,
 
  307     std::size_t _maxEmptySteps,
 
  316     ::ompl::base::SpaceInformationPtr _si);
 
  324     const ::ompl::geometric::PathGeometric& _path,
 
 
 
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
 
std::shared_ptr< Sampleable > SampleablePtr
Definition: Sampleable.hpp:16
 
std::shared_ptr< Interpolated > InterpolatedPtr
Definition: Interpolated.hpp:11
 
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.
 
std::shared_ptr< Interpolator > InterpolatorPtr
Definition: Interpolator.hpp:12
 
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
 
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...
 
::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.
 
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...
 
std::shared_ptr< StateSpace > StateSpacePtr
Definition: StateSpace.hpp:15
 
std::shared_ptr< Planner > PlannerPtr
Definition: Planner.hpp:14
 
std::shared_ptr< Testable > TestablePtr
Definition: Testable.hpp:13
 
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.
 
::ompl::geometric::PathGeometric toOMPLTrajectory(const trajectory::InterpolatedPtr &_interpolatedTraj, ::ompl::base::SpaceInformationPtr _si)
Take an interpolated trajectory and convert it into OMPL geometric path.
 
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.