All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator
Working with States and State Spaces

Allocating memory for states

See Operating with states for how to fill the contents of the allocated states.

Operating with states

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.

Operators for States and State Spaces

      These operators are intended to simplify code that
      manipulates states and state spaces. They rely on the fact
      that state spaces have unique names. Here are some examples
      for using these operators:
           // Assume X, Y, Z, W are state space instances, none of
           // which inherits from ompl::base::CompoundStateSpace.
           // Denote a compound state space as C[...], where "..." is the
           // list of subspaces.

           ompl::base::StateSpacePtr X;
           ompl::base::StateSpacePtr Y;
           ompl::base::StateSpacePtr Z;
           ompl::base::StateSpacePtr W;

           // the following line will construct a state space C1 = C[X, Y]
           ompl::base::StateSpacePtr C1 = X + Y;

           // the following line will construct a state space C2 = C[X, Y, Z]
           ompl::base::StateSpacePtr C2 = C1 + Z;

           // the following line will leave C2 as C[X, Y, Z]
           ompl::base::StateSpacePtr C2 = C1 + C2;

           // the following line will construct a state space C2 = C[X, Y, Z, W]
           ompl::base::StateSpacePtr C2 = C2 + W;

           // the following line will construct a state space C3 = C[X, Z, Y]
           ompl::base::StateSpacePtr C3 = X + Z + Y;

           // the following line will construct a state space C4 = C[Z, W]
           ompl::base::StateSpacePtr C4 = C2 - C1;

           // the following line will construct a state space C5 = W
           ompl::base::StateSpacePtr C5 = C2 - C3;

           // the following line will construct an empty state space C6 = C[]
           ompl::base::StateSpacePtr C6 = X - X;

           // the following line will construct an empty state space C7 = Y
           ompl::base::StateSpacePtr C7 = Y + C6;

These state spaces can be used when operating with states:

           ompl::base::ScopedState<> sX(X);
           ompl::base::ScopedState<> sXY(X + Y);
           ompl::base::ScopedState<> sY(Y);
           ompl::base::ScopedState<> sZX(Z + X);
           ompl::base::ScopedState<> sXZW(X + Z + W);

           // the following line will copy the content of the state sX to
           // the corresponding locations in sXZW. The components of the state
           // corresponding to the Z and W state spaces are not touched
           sX >> sXZW;

           // the following line will initialize the X component of sXY with
           // the X component of sXZW;
           sXY << sXZW;

           // the following line will initialize both components of sZX, using
           // the X and Z components of sXZW;
           sZX << sXZW;

           // the following line compares the concatenation of states sX and sY with sXY
           // the concatenation will automatically construct the state space X + Y and a state
           // from that state space containing the information from sX and sY. Since sXY is
           // constructed from the state space X + Y, the two are comparable.
           bool eq = (sX ^ sY) == sXY;