Public Member Functions | List of all members
exotica::PRMSolver Class Reference

#include <ompl_native_solvers.h>

Inheritance diagram for exotica::PRMSolver:
Inheritance graph
[legend]

Public Member Functions

void Clear ()
 
void ClearQuery ()
 
int EdgeCount ()
 
void ExpandRoadmap (double t)
 
void GrowRoadmap (double t)
 
void Instantiate (const PRMSolverInitializer &init) override
 
bool IsMultiQuery () const
 
int MilestoneCount ()
 
 PRMSolver ()
 
void SetMultiQuery (bool val)
 
void Setup ()
 
- Public Member Functions inherited from exotica::OMPLSolver< SamplingProblem >
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
 InstantiableBase ()=default
 
virtual ~InstantiableBase ()=default
 

Additional Inherited Members

- Public Attributes inherited from exotica::Object
bool debug_
 
std::string ns_
 
std::string object_name_
 
- Protected Member Functions inherited from exotica::OMPLSolver< SamplingProblem >
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 inherited from exotica::OMPLSolver< SamplingProblem >
static ompl::base::PlannerPtr AllocatePlanner (const ompl::base::SpaceInformationPtr &si, const std::string &new_name)
 
- Protected Attributes inherited from exotica::OMPLSolver< SamplingProblem >
std::string algorithm_
 
std::vector< double > bounds_
 
OMPLSolverInitializer init_
 
bool multi_query_
 
ompl::geometric::SimpleSetupPtr ompl_simple_setup_
 
ConfiguredPlannerAllocator planner_allocator_
 
std::shared_ptr< SamplingProblemprob_
 
ompl::base::StateSpacePtr state_space_
 
- Protected Attributes inherited from exotica::MotionSolver
int max_iterations_
 
double planning_time_
 
PlanningProblemPtr problem_
 
- Private Member Functions inherited from exotica::Instantiable< PRMSolverInitializer >
std::vector< InitializerGetAllTemplates () const override
 
Initializer GetInitializerTemplate () override
 
const PRMSolverInitializer & GetParameters () const
 
void InstantiateInternal (const Initializer &init) override
 
- Private Member Functions inherited from exotica::InstantiableBase
 InstantiableBase ()=default
 
virtual ~InstantiableBase ()=default
 
- Private Attributes inherited from exotica::Instantiable< PRMSolverInitializer >
PRMSolverInitializer parameters_
 

Detailed Description

Definition at line 74 of file ompl_native_solvers.h.

Constructor & Destructor Documentation

exotica::PRMSolver::PRMSolver ( )
default

Member Function Documentation

void exotica::PRMSolver::Clear ( void  )

Definition at line 153 of file ompl_native_solvers.cpp.

void exotica::PRMSolver::ClearQuery ( )

Definition at line 160 of file ompl_native_solvers.cpp.

int exotica::PRMSolver::EdgeCount ( )

Definition at line 172 of file ompl_native_solvers.cpp.

void exotica::PRMSolver::ExpandRoadmap ( double  t)

Definition at line 147 of file ompl_native_solvers.cpp.

void exotica::PRMSolver::GrowRoadmap ( double  t)

Definition at line 141 of file ompl_native_solvers.cpp.

void exotica::PRMSolver::Instantiate ( const PRMSolverInitializer &  init)
overridevirtual

Reimplemented from exotica::Instantiable< PRMSolverInitializer >.

Definition at line 133 of file ompl_native_solvers.cpp.

bool exotica::PRMSolver::IsMultiQuery ( ) const

Definition at line 184 of file ompl_native_solvers.cpp.

int exotica::PRMSolver::MilestoneCount ( )

Definition at line 178 of file ompl_native_solvers.cpp.

void exotica::PRMSolver::SetMultiQuery ( bool  val)

Definition at line 189 of file ompl_native_solvers.cpp.

void exotica::PRMSolver::Setup ( )

Definition at line 166 of file ompl_native_solvers.cpp.


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