30 #ifndef EXOTICA_OMPL_SOLVER_OMPL_NATIVE_SOLVER_H_ 31 #define EXOTICA_OMPL_SOLVER_OMPL_NATIVE_SOLVER_H_ 41 void Instantiate(
const RRTSolverInitializer& init)
override;
48 void Instantiate(
const RRTConnectSolverInitializer& init)
override;
49 void SetRange(
double range);
57 void Instantiate(
const ESTSolverInitializer& init)
override;
64 void Instantiate(
const KPIECESolverInitializer& init)
override;
71 void Instantiate(
const BKPIECESolverInitializer& init)
override;
78 void Instantiate(
const PRMSolverInitializer& init)
override;
79 void GrowRoadmap(
double t);
80 void ExpandRoadmap(
double t);
86 bool IsMultiQuery()
const;
87 void SetMultiQuery(
bool val);
94 void Instantiate(
const LazyPRMSolverInitializer& init)
override;
100 bool IsMultiQuery()
const;
101 void SetMultiQuery(
bool val);
108 void Instantiate(
const RRTStarSolverInitializer& init)
override;
115 void Instantiate(
const LBTRRTSolverInitializer& init)
override;
119 #endif // EXOTICA_OMPL_SOLVER_OMPL_NATIVE_SOLVER_H_
void Instantiate(const RRTSolverInitializer &init) override