KinematicCarPlanning.cpp
17 : AppBase<AppType::CONTROL>(constructControlSpace(), Motion_2D), odeSolver(std::make_shared<control::ODEBasicSolver<>>(si_, [this](const control::ODESolver::StateType& q, const control::Control *ctrl, control::ODESolver::StateType& qdot)
26 [this](const base::State* state, const control::Control* control, const double duration, base::State* result)
32 ompl::app::KinematicCarPlanning::KinematicCarPlanning(const control::ControlSpacePtr &controlSpace)
33 : AppBase<AppType::CONTROL>(controlSpace, Motion_2D), odeSolver(std::make_shared<control::ODEBasicSolver<>>(si_, [this](const control::ODESolver::StateType& q, const control::Control *ctrl, control::ODESolver::StateType& qdot)
41 [this](const base::State* state, const control::Control* control, const double duration, base::State* result)
68 void ompl::app::KinematicCarPlanning::ode(const control::ODESolver::StateType& q, const control::Control *ctrl, control::ODESolver::StateType& qdot)
static StatePropagatorPtr getStatePropagator(ODESolverPtr solver, const PostPropagationEvent &postEvent=nullptr)
Retrieve a StatePropagator object that solves a system of ordinary differential equations defined by ...
Definition: ODESolver.h:127
ompl::base::CompoundState StateType
Define the type of state allocated by this state space.
Definition: StateSpace.h:577