Aikido
CartesianProduct-impl.hpp
Go to the documentation of this file.
1 #include <sstream>
2 
4 
5 namespace aikido {
6 namespace statespace {
7 
10 template <class _QualifiedState>
11 class CompoundStateHandle
12  : public statespace::StateHandle<CartesianProduct, _QualifiedState>
13 {
14 public:
15  using typename statespace::StateHandle<CartesianProduct, _QualifiedState>::
16  State;
17  using typename statespace::StateHandle<CartesianProduct, _QualifiedState>::
18  StateSpace;
19  using typename statespace::StateHandle<CartesianProduct, _QualifiedState>::
20  QualifiedState;
21 
24  {
25  // Do nothing
26  }
27 
32  CompoundStateHandle(const StateSpace* _space, State* _state)
33  : statespace::StateHandle<CartesianProduct, QualifiedState>(_space, _state)
34  {
35  // Do nothing
36  }
37 
43  template <class Space = statespace::StateSpace>
44  typename Space::State* getSubState(std::size_t _index)
45  {
46  return this->getStateSpace()->template getSubState<Space>(
47  this->getState(), _index);
48  }
49 
55  template <class Space = statespace::StateSpace>
56  const typename Space::State* getSubState(std::size_t _index) const
57  {
58  return this->getStateSpace()->template getSubState<Space>(
59  this->getState(), _index);
60  }
61 
68  template <class Space = statespace::StateSpace>
69  typename Space::StateHandle getSubStateHandle(std::size_t _index)
70  {
71  return typename Space::StateHandle(
72  this->getStateSpace()->template getSubspace<Space>(_index).get(),
73  getSubState<Space>(_index));
74  }
75 
82  template <class Space = statespace::StateSpace>
83  typename Space::StateHandleConst getSubStateHandle(std::size_t _index) const
84  {
85  return typename Space::StateHandleConst(
86  this->getStateSpace()->template getSubspace<Space>(_index).get(),
87  getSubState<Space>(_index));
88  }
89 };
90 
91 //==============================================================================
92 template <class Space>
93 std::shared_ptr<const Space> CartesianProduct::getSubspace(
94  std::size_t _index) const
95 {
96  // TODO: Replace this with a static_cast in release mode.
97  const auto rawSpace = mSubspaces[_index];
98  auto space = std::dynamic_pointer_cast<const Space>(rawSpace);
99  if (!space)
100  {
101  // Create a reference to *rawSpace so we can use it in typeid below. Doing
102  // this inline trips -Wpotentially-evaluated-expression in Clang.
103  const auto& rawSpaceValue = *rawSpace;
104 
105  std::stringstream ss;
106  ss << "Requested StateSpace of type '" << typeid(Space).name()
107  << "', but the StateSpace at index " << _index
108  << " is of incompatible type '" << typeid(rawSpaceValue).name() << "'.";
109  throw std::runtime_error(ss.str());
110  }
111  return space;
112 }
113 
114 //==============================================================================
115 template <class Space>
116 typename Space::State* CartesianProduct::getSubState(
117  State* _state, std::size_t _index) const
118 {
119  // Use getStateSpace() to perform a type-check on the StateSpace.
120  getSubspace(_index);
121 
122  return reinterpret_cast<typename Space::State*>(
123  reinterpret_cast<char*>(_state) + mOffsets[_index]);
124 }
125 
126 //==============================================================================
127 template <class Space>
128 const typename Space::State* CartesianProduct::getSubState(
129  const State* _state, std::size_t _index) const
130 {
131  // Use getStateSpace() to perform a type-check on the StateSpace.
132  getSubspace(_index);
133 
134  return reinterpret_cast<const typename Space::State*>(
135  reinterpret_cast<const char*>(_state) + mOffsets[_index]);
136 }
137 
138 //==============================================================================
139 template <class Space>
140 typename Space::StateHandle CartesianProduct::getSubStateHandle(
141  State* _state, std::size_t _index) const
142 {
143  return typename Space::StateHandle(
144  getSubspace<Space>(_index).get(), getSubState<Space>(_state, _index));
145 }
146 
147 //==============================================================================
148 template <class Space>
149 typename Space::StateHandleConst CartesianProduct::getSubStateHandle(
150  const State* _state, std::size_t _index) const
151 {
152  return typename Space::StateHandleConst(
153  getSubspace<Space>(_index).get(), getSubState<Space>(_state, _index));
154 }
155 
156 } // namespace statespace
157 } // namespace aikido
aikido::statespace::CompoundStateHandle::getSubState
const Space::State * getSubState(std::size_t _index) const
Gets state by subspace index.
Definition: CartesianProduct-impl.hpp:56
aikido::statespace::CompoundStateHandle::CompoundStateHandle
CompoundStateHandle(const StateSpace *_space, State *_state)
Construct a handle for _state in _space.
Definition: CartesianProduct-impl.hpp:32
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::statespace::CompoundStateHandle::getSubStateHandle
Space::StateHandle getSubStateHandle(std::size_t _index)
Gets state by subspace index and wraps it in a Space::StateHandle helper class.
Definition: CartesianProduct-impl.hpp:69
aikido::statespace::CartesianProduct::getSubStateHandle
Space::StateHandle getSubStateHandle(State *_state, std::size_t _index) const
Gets substate of type Space::State from a CompoundState by index and wraps it in a Space::StateHandle...
Definition: CartesianProduct-impl.hpp:140
aikido::statespace::CompoundStateHandle::CompoundStateHandle
CompoundStateHandle()
Construct and initialize to nullptr.
Definition: CartesianProduct-impl.hpp:23
aikido::statespace::CartesianProduct::mSubspaces
std::vector< ConstStateSpacePtr > mSubspaces
Definition: CartesianProduct.hpp:156
CartesianProduct.hpp
aikido::statespace::CartesianProduct::getSubspace
std::shared_ptr< const Space > getSubspace(std::size_t _index) const
Gets subspace of type Space by at _index.
Definition: CartesianProduct-impl.hpp:93
aikido::statespace::CompoundStateHandle::getSubStateHandle
Space::StateHandleConst getSubStateHandle(std::size_t _index) const
Gets state by subspace index and wraps it in a Space::StateHandle helper class.
Definition: CartesianProduct-impl.hpp:83
aikido::statespace::StateHandle
Wrap a State with its StateSpace to provide convenient accessor methods.
Definition: StateHandle.hpp:16
aikido::statespace::CartesianProduct::getSubState
Space::State * getSubState(State *_state, std::size_t _index) const
Gets substate of type Space::State from a CompoundState by index.
Definition: CartesianProduct-impl.hpp:116
aikido::statespace::StateSpace
Represents a Lie group and its associated Lie algebra, i.e.
Definition: StateSpace.hpp:33
aikido::statespace::CartesianProduct::State
A tuple of states where the i-th state is from the i-th subspace.
Definition: CartesianProduct.hpp:162
aikido::statespace::CompoundStateHandle::getSubState
Space::State * getSubState(std::size_t _index)
Gets state by subspace index.
Definition: CartesianProduct-impl.hpp:44
aikido::statespace::CartesianProduct::mOffsets
std::vector< std::size_t > mOffsets
Definition: CartesianProduct.hpp:157
aikido::statespace::CartesianProduct
Represents the Cartesian product of other StateSpaces.
Definition: CartesianProduct.hpp:18