#include <ompl_control_solver.h>
Public Member Functions | |
void | Solve (Eigen::MatrixXd &solution) override |
Solves the problem. More... | |
void | SpecifyProblem (PlanningProblemPtr pointer) override |
Binds the solver to a specific problem which must be pre-initalised. More... | |
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< Initializer > | GetAllTemplates () const =0 |
virtual Initializer | GetInitializerTemplate ()=0 |
InstantiableBase ()=default | |
virtual void | InstantiateInternal (const Initializer &init)=0 |
virtual | ~InstantiableBase ()=default |
Protected Member Functions | |
bool | isStateValid (const oc::SpaceInformationPtr si, const ob::State *state) |
void | Setup () |
Static Protected Member Functions | |
template<typename PlannerType > | |
static ob::PlannerPtr | AllocatePlanner (const oc::SpaceInformationPtr &si) |
Protected Attributes | |
std::string | algorithm_ |
DynamicsSolverPtr | dynamics_solver_ |
!< Shared pointer to the planning problem. More... | |
OMPLControlSolverInitializer | init_ |
!< Shared pointer to the dynamics solver. More... | |
ConfiguredPlannerAllocator | planner_allocator_ |
DynamicTimeIndexedShootingProblemPtr | prob_ |
std::unique_ptr< oc::SimpleSetup > | setup_ |
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_ |
Definition at line 106 of file ompl_control_solver.h.
|
inlinestaticprotected |
Definition at line 120 of file ompl_control_solver.h.
|
inlineprotected |
Definition at line 137 of file ompl_control_solver.h.
|
protected |
Definition at line 51 of file ompl_control_solver.cpp.
|
overridevirtual |
Solves the problem.
solution | Returned solution trajectory as a vector of joint configurations. |
Implements exotica::MotionSolver.
Definition at line 125 of file ompl_control_solver.cpp.
|
overridevirtual |
Binds the solver to a specific problem which must be pre-initalised.
pointer | Shared pointer to the motion planning problem |
Reimplemented from exotica::MotionSolver.
Definition at line 34 of file ompl_control_solver.cpp.
|
protected |
Definition at line 132 of file ompl_control_solver.h.
|
protected |
!< Shared pointer to the planning problem.
Definition at line 127 of file ompl_control_solver.h.
|
protected |
!< Shared pointer to the dynamics solver.
Definition at line 129 of file ompl_control_solver.h.
|
protected |
Definition at line 133 of file ompl_control_solver.h.
|
protected |
Definition at line 126 of file ompl_control_solver.h.
|
protected |
Definition at line 131 of file ompl_control_solver.h.