#include <time_indexed_rrt_connect.h>
|
void | SetGoalState (const Eigen::VectorXd &qT, const double t, const double eps=0) |
|
void | PreSolve () |
|
void | PostSolve () |
|
void | GetPath (Eigen::MatrixXd &traj, ompl::base::PlannerTerminationCondition &ptc) |
|
|
template<typename T > |
static ompl::base::PlannerPtr | allocatePlanner (const ompl::base::SpaceInformationPtr &si, const std::string &new_name) |
|
◆ allocatePlanner()
template<typename T >
static ompl::base::PlannerPtr exotica::TimeIndexedRRTConnectSolver::allocatePlanner |
( |
const ompl::base::SpaceInformationPtr & |
si, |
|
|
const std::string & |
new_name |
|
) |
| |
|
inlinestaticprotected |
◆ GetPath()
void exotica::TimeIndexedRRTConnectSolver::GetPath |
( |
Eigen::MatrixXd & |
traj, |
|
|
ompl::base::PlannerTerminationCondition & |
ptc |
|
) |
| |
|
protected |
◆ Instantiate()
void exotica::TimeIndexedRRTConnectSolver::Instantiate |
( |
const TimeIndexedRRTConnectSolverInitializer & |
init | ) |
|
|
overridevirtual |
◆ PostSolve()
void exotica::TimeIndexedRRTConnectSolver::PostSolve |
( |
| ) |
|
|
protected |
◆ PreSolve()
void exotica::TimeIndexedRRTConnectSolver::PreSolve |
( |
| ) |
|
|
protected |
◆ SetGoalState()
void exotica::TimeIndexedRRTConnectSolver::SetGoalState |
( |
const Eigen::VectorXd & |
qT, |
|
|
const double |
t, |
|
|
const double |
eps = 0 |
|
) |
| |
|
protected |
◆ SetPlannerTerminationCondition()
void exotica::TimeIndexedRRTConnectSolver::SetPlannerTerminationCondition |
( |
const std::shared_ptr< ompl::base::PlannerTerminationCondition > & |
ptc | ) |
|
◆ Solve()
void exotica::TimeIndexedRRTConnectSolver::Solve |
( |
Eigen::MatrixXd & |
solution | ) |
|
|
overridevirtual |
◆ SpecifyProblem()
◆ algorithm_
std::string exotica::TimeIndexedRRTConnectSolver::algorithm_ |
|
protected |
◆ ompl_simple_setup_
ompl::geometric::SimpleSetupPtr exotica::TimeIndexedRRTConnectSolver::ompl_simple_setup_ |
|
protected |
◆ planner_allocator_
◆ prob_
◆ ptc_
std::shared_ptr<ompl::base::PlannerTerminationCondition> exotica::TimeIndexedRRTConnectSolver::ptc_ |
|
protected |
◆ state_space_
ompl::base::StateSpacePtr exotica::TimeIndexedRRTConnectSolver::state_space_ |
|
protected |
The documentation for this class was generated from the following file:
- /tmp/exotica/exotations/solvers/exotica_time_indexed_rrt_connect_solver/include/exotica_time_indexed_rrt_connect_solver/time_indexed_rrt_connect.h