SE2MultiRigidBodyPlanning.h
45 base::ScopedState<> getFullStateFromGeometricComponent(const base::ScopedState<> &state) const override
69 const base::State* getGeometricComponentStateInternal(const base::State* state, unsigned int index) const override;
A space to allow the composition of state spaces.
Definition: StateSpace.h:574
virtual const base::StateSpacePtr & getGeometricComponentStateSpace(unsigned int index) const
Returns the state space corresponding for the indexth rigid body.
Definition: SE2MultiRigidBodyPlanning.h:51
const base::State * getGeometricComponentStateInternal(const base::State *state, unsigned int index) const override
Returns the state corresponding to the indexth rigid body in the compound state.
Definition: SE2MultiRigidBodyPlanning.cpp:57
SE2MultiRigidBodyPlanning(unsigned int n)
Constructs an instance of multiple rigid bodies for 2D geometric planning. n is the number of indepen...
Definition: SE2MultiRigidBodyPlanning.cpp:15
Definition: AppBase.h:46
const base::StateSpacePtr & getStateSpace() const
Get the current instance of the state space.
Definition: SimpleSetup.h:92
base::ScopedState getDefaultStartState() const override
Constructs the default start state where all robots begin at their geometric center....
Definition: SE2MultiRigidBodyPlanning.cpp:42
Wrapper for ompl::app::RigidBodyPlanning that plans for multiple rigid bodies in SE2.
Definition: SE2MultiRigidBodyPlanning.h:24
unsigned int n_
The number of independent rigid bodies to plan for.
Definition: SE2MultiRigidBodyPlanning.h:72