Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | List of all members
exotica::TimeIndexedRRTConnectSolver Class Reference

#include <time_indexed_rrt_connect.h>

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

Public Member Functions

void Instantiate (const TimeIndexedRRTConnectSolverInitializer &init) override
 
void SetPlannerTerminationCondition (const std::shared_ptr< ompl::base::PlannerTerminationCondition > &ptc)
 
void Solve (Eigen::MatrixXd &solution) override
 
void SpecifyProblem (PlanningProblemPtr pointer) override
 
- 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
 

Protected Member Functions

void GetPath (Eigen::MatrixXd &traj, ompl::base::PlannerTerminationCondition &ptc)
 
void PostSolve ()
 
void PreSolve ()
 
void SetGoalState (const Eigen::VectorXd &qT, const double t, 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_
 
ompl::geometric::SimpleSetupPtr ompl_simple_setup_
 
ConfiguredPlannerAllocator planner_allocator_
 
TimeIndexedSamplingProblemPtr prob_
 
std::shared_ptr< ompl::base::PlannerTerminationCondition > ptc_
 
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_
 
- Private Member Functions inherited from exotica::Instantiable< TimeIndexedRRTConnectSolverInitializer >
std::vector< InitializerGetAllTemplates () const override
 
Initializer GetInitializerTemplate () override
 
const TimeIndexedRRTConnectSolverInitializer & 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< TimeIndexedRRTConnectSolverInitializer >
TimeIndexedRRTConnectSolverInitializer parameters_
 

Detailed Description

Definition at line 106 of file time_indexed_rrt_connect.h.

Member Function Documentation

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

Definition at line 116 of file time_indexed_rrt_connect.h.

void exotica::TimeIndexedRRTConnectSolver::GetPath ( Eigen::MatrixXd &  traj,
ompl::base::PlannerTerminationCondition &  ptc 
)
protected

Definition at line 180 of file time_indexed_rrt_connect.cpp.

void exotica::TimeIndexedRRTConnectSolver::Instantiate ( const TimeIndexedRRTConnectSolverInitializer &  init)
overridevirtual
void exotica::TimeIndexedRRTConnectSolver::PostSolve ( )
protected

Definition at line 144 of file time_indexed_rrt_connect.cpp.

void exotica::TimeIndexedRRTConnectSolver::PreSolve ( )
protected

Definition at line 134 of file time_indexed_rrt_connect.cpp.

void exotica::TimeIndexedRRTConnectSolver::SetGoalState ( const Eigen::VectorXd &  qT,
const double  t,
const double  eps = 0 
)
protected

Definition at line 156 of file time_indexed_rrt_connect.cpp.

void exotica::TimeIndexedRRTConnectSolver::SetPlannerTerminationCondition ( const std::shared_ptr< ompl::base::PlannerTerminationCondition > &  ptc)

Definition at line 270 of file time_indexed_rrt_connect.cpp.

void exotica::TimeIndexedRRTConnectSolver::Solve ( Eigen::MatrixXd &  solution)
overridevirtual

Implements exotica::MotionSolver.

Definition at line 240 of file time_indexed_rrt_connect.cpp.

void exotica::TimeIndexedRRTConnectSolver::SpecifyProblem ( PlanningProblemPtr  pointer)
overridevirtual

Reimplemented from exotica::MotionSolver.

Definition at line 118 of file time_indexed_rrt_connect.cpp.

Member Data Documentation

std::string exotica::TimeIndexedRRTConnectSolver::algorithm_
protected

Definition at line 132 of file time_indexed_rrt_connect.h.

ompl::geometric::SimpleSetupPtr exotica::TimeIndexedRRTConnectSolver::ompl_simple_setup_
protected

Definition at line 129 of file time_indexed_rrt_connect.h.

ConfiguredPlannerAllocator exotica::TimeIndexedRRTConnectSolver::planner_allocator_
protected

Definition at line 131 of file time_indexed_rrt_connect.h.

TimeIndexedSamplingProblemPtr exotica::TimeIndexedRRTConnectSolver::prob_
protected

Definition at line 128 of file time_indexed_rrt_connect.h.

std::shared_ptr<ompl::base::PlannerTerminationCondition> exotica::TimeIndexedRRTConnectSolver::ptc_
protected

Definition at line 133 of file time_indexed_rrt_connect.h.

ompl::base::StateSpacePtr exotica::TimeIndexedRRTConnectSolver::state_space_
protected

Definition at line 130 of file time_indexed_rrt_connect.h.


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


exotica_time_indexed_rrt_connect_solver
Author(s): Yiming Yang
autogenerated on Sat Apr 10 2021 02:36:59