Aikido
StateHandle.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_STATESPACE_STATEHANDLE_HPP_
2 #define AIKIDO_STATESPACE_STATEHANDLE_HPP_
3 
4 #include <type_traits>
5 
6 namespace aikido {
7 namespace statespace {
8 
15 template <class _StateSpace, class _QualifiedState>
17 {
18 public:
19  using StateSpace = _StateSpace;
20  using QualifiedState = _QualifiedState;
21 
22  using State = typename StateSpace::State;
23  using ConstState = typename std::conditional<
24  std::is_const<QualifiedState>::value,
26  const QualifiedState>::type;
27 
29  StateHandle();
30 
35  StateHandle(const StateSpace* space, QualifiedState* state);
36 
37  StateHandle(const StateHandle&) = default;
38  StateHandle(StateHandle&&) = default;
39 
40  StateHandle& operator=(StateHandle&&) = default;
41  StateHandle& operator=(const StateHandle&) = default;
42 
44  operator QualifiedState*() const;
45 
47  void reset();
48 
53  void reset(const StateSpace* space, QualifiedState* state);
54 
59  template <typename Q = QualifiedState>
60  auto getState() ->
61  typename std::enable_if<!std::is_const<Q>::value, Q*>::type;
62  // Note: We don't define non-const function for const State type because it
63  // violates const-correctness.
64 
68  template <typename Q = QualifiedState>
69  auto getState() const ->
70  typename std::conditional<std::is_const<Q>::value, Q*, const Q*>::type;
71 
75  const StateSpace* getStateSpace() const;
76 
77 protected:
80 
83 };
84 
85 } // namespace statespace
86 } // namespace aikido
87 
88 #include "detail/StateHandle-impl.hpp"
89 
90 #endif // AIKIDO_STATESPACE_STATEHANDLE_HPP_
aikido::statespace::StateHandle::StateHandle
StateHandle()
Constructs a nullptr handle.
Definition: StateHandle-impl.hpp:8
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::statespace::StateHandle::getState
auto getState() -> typename std::enable_if<!std::is_const< Q >::value, Q * >::type
Returns the State.
Definition: StateHandle-impl.hpp:49
aikido::statespace::StateHandle::operator=
StateHandle & operator=(StateHandle &&)=default
aikido::statespace::StateHandle::reset
void reset()
Resets StateHandle to nullptr.
Definition: StateHandle-impl.hpp:32
aikido::statespace::StateHandle::mSpace
const StateSpace * mSpace
State space of the sate that is managed by this handler.
Definition: StateHandle.hpp:79
aikido::statespace::StateHandle::getStateSpace
const StateSpace * getStateSpace() const
Returns the state space that created this state.
Definition: StateHandle-impl.hpp:66
aikido::statespace::StateHandle< SE3, _QualifiedState >::ConstState
typename std::conditional< std::is_const< QualifiedState >::value, QualifiedState, const QualifiedState >::type ConstState
Definition: StateHandle.hpp:26
aikido::statespace::StateHandle
Wrap a State with its StateSpace to provide convenient accessor methods.
Definition: StateHandle.hpp:16
aikido::statespace::SE3
The three-dimensional special Euclidean group SE(3), i.e.
Definition: SE3.hpp:19
aikido::statespace::StateHandle< SE3, _QualifiedState >::QualifiedState
_QualifiedState QualifiedState
Definition: StateHandle.hpp:20
aikido::statespace::SE3::State
Definition: SE3.hpp:22
aikido::statespace::StateHandle::mState
QualifiedState * mState
State managed by this handler. This can be either const or non-const type.
Definition: StateHandle.hpp:82
aikido::statespace::StateHandle< SE3, _QualifiedState >::State
typename StateSpace::State State
Definition: StateHandle.hpp:22