Working with States and State Spaces {#workingWithStates}
Allocating memory for states {#stateAlloc}
The simple version
or
The ompl::base::ScopedState class will do the necessary memory operations to allocate a state from the correct state space. This is the recommended way of allocating states for code other than ompl internals. Convenience operators such as = and == are provided. If a type T is provided, where T is a state space type, the maintained state is cast as T::StateType. operator= will use ompl::base::StateSpace::copyState() and operator== will use ompl::base::StateSpace::equalStates().
The expert version
The structure of a state depends on the state space specification. The ompl::base::State type is just an abstract base for the states of other state spaces. For this reason, states cannot be allocated directly, but through the allocation mechanism of the state space: ompl::base::StateSpace::allocState(). States are to be freed using ompl::base::StateSpace::freeState(). For convenience, ompl::base::SpaceInformation::allocState() and ompl::base::SpaceInformation::freeState() are defined as well. Using the calls from the ompl::base::SpaceInformation class is better since they certainly use the same state space as the one used for planning. This is the lowest level of operating on states and only recommended for expert users.
See Working with states for how to fill the contents of the allocated states.
Working with states {#stateOps}
In order for states to be useful in setting start (or goal) positions, accessing their content is needed. It is assumed the reader is familiar with Allocating memory for states. Furthermore, operators on states and state spaces are also used.
Simple version
The recommended use of states is with ompl::base::ScopedState. Given the instance of a state space, this class will allocate a state from that space. The internally maintained state is freed when the instance of ompl::base::ScopedState goes out of scope. ompl::base::ScopedState is a templated class and it inherits from T::StateType, where T is a state space type. This allows it to cast the state it maintains to the desired type and thus exhibit the functionality (the same members) as T::StateType. If no template argument is specified, the internal state is kept as ompl::base::State*.
Combining ompl::base::ScopedState with ompl::base::CompoundStateSpace:
The code above can be equivalently written as:
States can also be printed to streams:
Sometimes it may be useful to extract parts of a state, or assign only to some parts of a state, especially when using compound state spaces:
Expert version
For a state space type of type T, the result of ompl::base::StateSpace::allocState() can be casted to T::StateType* to gain access to the state’s members. To ease this functionality, the ompl::base::State::as() functions have been defined.
See Advanced methods for copying states for more information on copying states.
Operators for States and State Spaces {#stateAndSpaceOperatorsCopy}
\copydoc stateAndSpaceOperators