#include <time_indexed_rrt_connect.h>
Classes | |
class | StateType |
Public Member Functions | |
ompl::base::StateSamplerPtr | allocDefaultStateSampler () const override |
void | ExoticaToOMPLState (const Eigen::VectorXd &q, const double &t, ompl::base::State *state) const |
OMPLTimeIndexedRNStateSpace (TimeIndexedSamplingProblemPtr &prob, TimeIndexedRRTConnectSolverInitializer init) | |
void | OMPLToExoticaState (const ompl::base::State *state, Eigen::VectorXd &q, double &t) const |
void | StateDebug (const Eigen::VectorXd &q) const |
Public Attributes | |
TimeIndexedSamplingProblemPtr | prob_ |
Definition at line 51 of file time_indexed_rrt_connect.h.
exotica::OMPLTimeIndexedRNStateSpace::OMPLTimeIndexedRNStateSpace | ( | TimeIndexedSamplingProblemPtr & | prob, |
TimeIndexedRRTConnectSolverInitializer | init | ||
) |
Definition at line 38 of file time_indexed_rrt_connect.cpp.
|
override |
Definition at line 55 of file time_indexed_rrt_connect.cpp.
void exotica::OMPLTimeIndexedRNStateSpace::ExoticaToOMPLState | ( | const Eigen::VectorXd & | q, |
const double & | t, | ||
ompl::base::State * | state | ||
) | const |
Definition at line 59 of file time_indexed_rrt_connect.cpp.
void exotica::OMPLTimeIndexedRNStateSpace::OMPLToExoticaState | ( | const ompl::base::State * | state, |
Eigen::VectorXd & | q, | ||
double & | t | ||
) | const |
Definition at line 65 of file time_indexed_rrt_connect.cpp.
void exotica::OMPLTimeIndexedRNStateSpace::StateDebug | ( | const Eigen::VectorXd & | q | ) | const |
Definition at line 72 of file time_indexed_rrt_connect.cpp.
TimeIndexedSamplingProblemPtr exotica::OMPLTimeIndexedRNStateSpace::prob_ |
Definition at line 88 of file time_indexed_rrt_connect.h.