Aikido
SO2.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_STATESPACE_SO2STATESPACE_HPP_
2 #define AIKIDO_STATESPACE_SO2STATESPACE_HPP_
3 #include <Eigen/Core>
4 #include <Eigen/Geometry>
5 
8 
9 namespace aikido {
10 namespace statespace {
11 
12 // Defined in detail/SO2-impl.hpp
13 template <class>
14 class SO2StateHandle;
15 
18 class SO2 : virtual public StateSpace
19 {
20 public:
22  class State;
23 
26 
29 
30  using StateSpace::compose;
31 
33  SO2() = default;
34 
38  ScopedState createState() const;
39 
41  ScopedState cloneState(const StateSpace::State* stateIn) const;
42 
46  double toAngle(const State* state) const;
47 
52  void fromAngle(State* state, double angle) const;
53 
57  Eigen::Rotation2Dd toRotation(const State* state) const;
58 
63  void fromRotation(State* state, const Eigen::Rotation2Dd& rotation) const;
64 
65  // Documentation inherited.
66  std::size_t getStateSizeInBytes() const override;
67 
68  // Documentation inherited.
69  StateSpace::State* allocateStateInBuffer(void* buffer) const override;
70 
71  // Documentation inherited.
72  void freeStateInBuffer(StateSpace::State* state) const override;
73 
74  // Documentation inherited.
75  void compose(
76  const StateSpace::State* state1,
77  const StateSpace::State* state2,
78  StateSpace::State* out) const override;
79 
80  // Documentation inherited.
81  void getIdentity(StateSpace::State* out) const override;
82 
83  // Documentation inherited.
84  void getInverse(
85  const StateSpace::State* in, StateSpace::State* out) const override;
86 
87  // Documentation inherited.
88  std::size_t getDimension() const override;
89 
90  // Documentation inherited.
91  void copyState(
92  const StateSpace::State* source,
93  StateSpace::State* destination) const override;
94 
100  void expMap(
101  const Eigen::VectorXd& tangent, StateSpace::State* out) const override;
102 
108  void logMap(
109  const StateSpace::State* in, Eigen::VectorXd& tangent) const override;
110 
112  void print(const StateSpace::State* state, std::ostream& os) const override;
113 };
114 
115 class SO2::State final : public StateSpace::State
116 {
117 public:
121  explicit State(double angle = 0.0);
122 
123  ~State() = default;
124 
126  double toAngle() const;
127 
131  void fromAngle(double angle);
132 
134  Eigen::Rotation2Dd toRotation() const;
135 
139  void fromRotation(const Eigen::Rotation2Dd& rotation);
140 
141 private:
143  double mAngle;
144 
145  friend class SO2;
146 };
147 
148 } // namespace statespace
149 } // namespace aikido
150 
151 #include "detail/SO2-impl.hpp"
152 
153 #endif // ifndef AIKIDO_STATESPACE_SO2STATESPACE_HPP_
aikido::statespace::SO2::toRotation
Eigen::Rotation2Dd toRotation(const State *state) const
Returns state as an Eigen rotation.
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::statespace::SO2::print
void print(const StateSpace::State *state, std::ostream &os) const override
Print the angle represented by the state.
aikido::statespace::SO2::getStateSizeInBytes
std::size_t getStateSizeInBytes() const override
Gets the size of a State, in bytes.
aikido::statespace::SO2::State
Definition: SO2.hpp:115
aikido::statespace::SO2::expMap
void expMap(const Eigen::VectorXd &tangent, StateSpace::State *out) const override
Exponential mapping of Lie algebra element to a Lie group element.
aikido::statespace::SO2::State::toRotation
Eigen::Rotation2Dd toRotation() const
Returns state as an Eigen rotation.
StateSpace.hpp
aikido::statespace::SO2::allocateStateInBuffer
StateSpace::State * allocateStateInBuffer(void *buffer) const override
Create a new state in a pre-allocated buffer.
aikido::statespace::SO2StateHandle
StateHandle for a SO2.
Definition: SO2-impl.hpp:9
aikido::statespace::SO2::compose
void compose(const StateSpace::State *state1, const StateSpace::State *state2, StateSpace::State *out) const override
Lie group operation for this StateSpace.
aikido::statespace::SO2::copyState
void copyState(const StateSpace::State *source, StateSpace::State *destination) const override
Copy a state.
aikido::statespace::SO2::State::fromAngle
void fromAngle(double angle)
Sets state from a rotation angle.
aikido::statespace::SO2::State::~State
~State()=default
aikido::statespace::SO2::createState
ScopedState createState() const
Helper function to create a ScopedState.
aikido::statespace::StateSpace::State::State
State()=default
This is a base class that should only only be used in derived classes.
aikido::statespace::SO2::toAngle
double toAngle(const State *state) const
Returns state as a rotation angle in (-pi, pi].
SO2-impl.hpp
aikido::statespace::SO2::freeStateInBuffer
void freeStateInBuffer(StateSpace::State *state) const override
Free a state previously created by allocateStateInBuffer.
aikido::statespace::SO2::getIdentity
void getIdentity(StateSpace::State *out) const override
Gets the identity element for this Lie group, such that:
aikido::statespace::StateSpace
Represents a Lie group and its associated Lie algebra, i.e.
Definition: StateSpace.hpp:33
aikido::statespace::SO2::fromAngle
void fromAngle(State *state, double angle) const
Sets state from a rotation angle in (-inf, inf).
aikido::statespace::SO2::State::toAngle
double toAngle() const
Returns state as a rotation angle in (-pi, pi].
aikido::statespace::ScopedState< StateHandle >
aikido::statespace::StateSpace::compose
virtual void compose(const State *_state1, const State *_state2, State *_out) const =0
Lie group operation for this StateSpace.
aikido::statespace::SO2::State::mAngle
double mAngle
Angle bounded in (-pi, pi] representing the SO(2) state.
Definition: SO2.hpp:143
aikido::statespace::SO2::getInverse
void getInverse(const StateSpace::State *in, StateSpace::State *out) const override
Gets the inverse of _in in this Lie group, such that:
aikido::statespace::SO2::fromRotation
void fromRotation(State *state, const Eigen::Rotation2Dd &rotation) const
Sets state from an Eigen rotation.
aikido::statespace::SO2::SO2
SO2()=default
Constructs a state space representing SO(2).
aikido::statespace::StateSpace::State
Definition: StateSpace.hpp:167
aikido::statespace::SO2::cloneState
ScopedState cloneState(const StateSpace::State *stateIn) const
Creates an identical clone of stateIn.
aikido::statespace::SO2::logMap
void logMap(const StateSpace::State *in, Eigen::VectorXd &tangent) const override
Log mapping of Lie group element to a Lie algebra element.
aikido::statespace::SO2::getDimension
std::size_t getDimension() const override
Get the dimension of this Lie group.
ScopedState.hpp
aikido::statespace::SO2
The two-dimensional special orthogonal group SO(2), i.e.
Definition: SO2.hpp:18
aikido::statespace::SO2::State::fromRotation
void fromRotation(const Eigen::Rotation2Dd &rotation)
Sets state from an Eigen rotation.