#include <time_indexed_rrt_connect.h>

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< Initializer > | GetAllTemplates () 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_ |
Definition at line 106 of file time_indexed_rrt_connect.h.
|
inlinestaticprotected |
Definition at line 116 of file time_indexed_rrt_connect.h.
|
protected |
Definition at line 180 of file time_indexed_rrt_connect.cpp.
|
overridevirtual |
Reimplemented from exotica::Instantiable< TimeIndexedRRTConnectSolverInitializer >.
Definition at line 105 of file time_indexed_rrt_connect.cpp.
|
protected |
Definition at line 144 of file time_indexed_rrt_connect.cpp.
|
protected |
Definition at line 134 of file time_indexed_rrt_connect.cpp.
|
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.
|
overridevirtual |
Implements exotica::MotionSolver.
Definition at line 240 of file time_indexed_rrt_connect.cpp.
|
overridevirtual |
Reimplemented from exotica::MotionSolver.
Definition at line 118 of file time_indexed_rrt_connect.cpp.
|
protected |
Definition at line 132 of file time_indexed_rrt_connect.h.
|
protected |
Definition at line 129 of file time_indexed_rrt_connect.h.
|
protected |
Definition at line 131 of file time_indexed_rrt_connect.h.
|
protected |
Definition at line 128 of file time_indexed_rrt_connect.h.
|
protected |
Definition at line 133 of file time_indexed_rrt_connect.h.
|
protected |
Definition at line 130 of file time_indexed_rrt_connect.h.