Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | List of all members
exotica::OMPLSolver< ProblemType > Class Template Reference

#include <ompl_solver.h>

Inheritance diagram for exotica::OMPLSolver< ProblemType >:
Inheritance graph
[legend]

Public Member Functions

double GetLongestValidSegmentLength () const
 
double GetMaximumExtent () const
 
int GetRandomSeed () const
 
unsigned int GetValidSegmentCountFactor () const
 
 OMPLSolver ()
 
void SetLongestValidSegmentFraction (double segmentFraction)
 
void SetValidSegmentCountFactor (unsigned int factor)
 
void Solve (Eigen::MatrixXd &solution) override
 
void SpecifyProblem (PlanningProblemPtr pointer) override
 
virtual ~OMPLSolver ()
 
- Public Member Functions inherited from exotica::MotionSolver
int GetNumberOfMaxIterations ()
 
double GetPlanningTime ()
 
PlanningProblemPtr GetProblem () const
 
void InstantiateBase (const Initializer &init) override
 
 MotionSolver ()=default
 
std::string Print (const std::string &prepend) const override
 
void SetNumberOfMaxIterations (int max_iter)
 
virtual ~MotionSolver ()=default
 
- Public Member Functions inherited from exotica::Object
std::string GetObjectName ()
 
void InstantiateObject (const Initializer &init)
 
 Object ()
 
virtual std::string type () const
 
virtual ~Object ()
 
- Public Member Functions inherited from exotica::InstantiableBase
virtual std::vector< InitializerGetAllTemplates () const =0
 
virtual Initializer GetInitializerTemplate ()=0
 
 InstantiableBase ()=default
 
virtual void InstantiateInternal (const Initializer &init)=0
 
virtual ~InstantiableBase ()=default
 

Protected Member Functions

void GetPath (Eigen::MatrixXd &traj, ompl::base::PlannerTerminationCondition &ptc)
 
void PostSolve ()
 
void PreSolve ()
 
void SetGoalState (Eigen::VectorXdRefConst qT, const double eps=0)
 

Static Protected Member Functions

template<typename T >
static ompl::base::PlannerPtr AllocatePlanner (const ompl::base::SpaceInformationPtr &si, const std::string &new_name)
 

Protected Attributes

std::string algorithm_
 
std::vector< double > bounds_
 
OMPLSolverInitializer init_
 
bool multi_query_ = false
 
ompl::geometric::SimpleSetupPtr ompl_simple_setup_
 
ConfiguredPlannerAllocator planner_allocator_
 
std::shared_ptr< ProblemType > prob_
 
ompl::base::StateSpacePtr state_space_
 
- Protected Attributes inherited from exotica::MotionSolver
int max_iterations_
 
double planning_time_
 
PlanningProblemPtr problem_
 

Additional Inherited Members

- Public Attributes inherited from exotica::Object
bool debug_
 
std::string ns_
 
std::string object_name_
 

Detailed Description

template<class ProblemType>
class exotica::OMPLSolver< ProblemType >

Definition at line 59 of file ompl_solver.h.

Constructor & Destructor Documentation

template<class ProblemType >
exotica::OMPLSolver< ProblemType >::OMPLSolver ( )
default
template<class ProblemType >
exotica::OMPLSolver< ProblemType >::~OMPLSolver ( )
virtualdefault

Member Function Documentation

template<class ProblemType>
template<typename T >
static ompl::base::PlannerPtr exotica::OMPLSolver< ProblemType >::AllocatePlanner ( const ompl::base::SpaceInformationPtr &  si,
const std::string &  new_name 
)
inlinestaticprotected

Definition at line 79 of file ompl_solver.h.

template<class ProblemType>
double exotica::OMPLSolver< ProblemType >::GetLongestValidSegmentLength ( ) const
inline

Definition at line 72 of file ompl_solver.h.

template<class ProblemType>
double exotica::OMPLSolver< ProblemType >::GetMaximumExtent ( ) const
inline

Definition at line 71 of file ompl_solver.h.

template<class ProblemType >
void exotica::OMPLSolver< ProblemType >::GetPath ( Eigen::MatrixXd &  traj,
ompl::base::PlannerTerminationCondition &  ptc 
)
protected

Definition at line 143 of file ompl_solver.cpp.

template<class ProblemType >
int exotica::OMPLSolver< ProblemType >::GetRandomSeed ( ) const

Definition at line 83 of file ompl_solver.cpp.

template<class ProblemType>
unsigned int exotica::OMPLSolver< ProblemType >::GetValidSegmentCountFactor ( ) const
inline

Definition at line 75 of file ompl_solver.h.

template<class ProblemType >
void exotica::OMPLSolver< ProblemType >::PostSolve ( )
protected

Definition at line 104 of file ompl_solver.cpp.

template<class ProblemType >
void exotica::OMPLSolver< ProblemType >::PreSolve ( )
protected

Definition at line 89 of file ompl_solver.cpp.

template<class ProblemType >
void exotica::OMPLSolver< ProblemType >::SetGoalState ( Eigen::VectorXdRefConst  qT,
const double  eps = 0 
)
protected

Definition at line 116 of file ompl_solver.cpp.

template<class ProblemType>
void exotica::OMPLSolver< ProblemType >::SetLongestValidSegmentFraction ( double  segmentFraction)
inline

Definition at line 73 of file ompl_solver.h.

template<class ProblemType>
void exotica::OMPLSolver< ProblemType >::SetValidSegmentCountFactor ( unsigned int  factor)
inline

Definition at line 74 of file ompl_solver.h.

template<class ProblemType >
void exotica::OMPLSolver< ProblemType >::Solve ( Eigen::MatrixXd &  solution)
overridevirtual

Implements exotica::MotionSolver.

Definition at line 195 of file ompl_solver.cpp.

template<class ProblemType >
void exotica::OMPLSolver< ProblemType >::SpecifyProblem ( PlanningProblemPtr  pointer)
overridevirtual

Reimplemented from exotica::MotionSolver.

Definition at line 44 of file ompl_solver.cpp.

Member Data Documentation

template<class ProblemType>
std::string exotica::OMPLSolver< ProblemType >::algorithm_
protected

Definition at line 96 of file ompl_solver.h.

template<class ProblemType>
std::vector<double> exotica::OMPLSolver< ProblemType >::bounds_
protected

Definition at line 98 of file ompl_solver.h.

template<class ProblemType>
OMPLSolverInitializer exotica::OMPLSolver< ProblemType >::init_
protected

Definition at line 91 of file ompl_solver.h.

template<class ProblemType>
bool exotica::OMPLSolver< ProblemType >::multi_query_ = false
protected

Definition at line 97 of file ompl_solver.h.

template<class ProblemType>
ompl::geometric::SimpleSetupPtr exotica::OMPLSolver< ProblemType >::ompl_simple_setup_
protected

Definition at line 93 of file ompl_solver.h.

template<class ProblemType>
ConfiguredPlannerAllocator exotica::OMPLSolver< ProblemType >::planner_allocator_
protected

Definition at line 95 of file ompl_solver.h.

template<class ProblemType>
std::shared_ptr<ProblemType> exotica::OMPLSolver< ProblemType >::prob_
protected

Definition at line 92 of file ompl_solver.h.

template<class ProblemType>
ompl::base::StateSpacePtr exotica::OMPLSolver< ProblemType >::state_space_
protected

Definition at line 94 of file ompl_solver.h.


The documentation for this class was generated from the following files:


exotica_ompl_solver
Author(s): Yiming Yang
autogenerated on Sat Apr 10 2021 02:36:37