Aikido
SE3.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_STATESPACE_SE3STATESPACE_HPP_
2 #define AIKIDO_STATESPACE_SE3STATESPACE_HPP_
3 #include <Eigen/Geometry>
4 
7 
8 namespace aikido {
9 namespace statespace {
10 
11 // Defined in detail/SE3-impl.hpp
12 template <class>
13 class SE3StateHandle;
14 
19 class SE3 : public virtual StateSpace
20 {
21 public:
22  class State : public StateSpace::State
23  {
24  public:
25  using Isometry3d
26  = Eigen::Transform<double, 3, Eigen::Isometry, Eigen::DontAlign>;
27 
29  State();
30 
31  ~State() = default;
32 
36  explicit State(const Isometry3d& _transform);
37 
41  void setIsometry(const Isometry3d& _transform);
42 
46  const Isometry3d& getIsometry() const;
47 
48  private:
50 
51  friend class SE3;
52  };
53 
56 
59 
60  using StateSpace::compose;
61 
63 
65  SE3() = default;
66 
70  ScopedState createState() const;
71 
73  ScopedState cloneState(const StateSpace::State* stateIn) const;
74 
79  const Isometry3d& getIsometry(const State* _state) const;
80 
85  void setIsometry(State* _state, const Isometry3d& _transform) const;
86 
87  // Documentation inherited.
88  std::size_t getStateSizeInBytes() const override;
89 
90  // Documentation inherited.
91  StateSpace::State* allocateStateInBuffer(void* _buffer) const override;
92 
93  // Documentation inherited.
94  void freeStateInBuffer(StateSpace::State* _state) const override;
95 
96  // Documentation inherited.
97  void compose(
98  const StateSpace::State* _state1,
99  const StateSpace::State* _state2,
100  StateSpace::State* _out) const override;
101 
102  // Documentation inherited.
103  void getIdentity(StateSpace::State* _out) const override;
104 
105  // Documentation inherited.
106  void getInverse(
107  const StateSpace::State* _in, StateSpace::State* _out) const override;
108 
109  // Documentation inherited.
110  std::size_t getDimension() const override;
111 
112  // Documentation inherited.
113  void copyState(
114  const StateSpace::State* _source,
115  StateSpace::State* _destination) const override;
116 
123  void expMap(
124  const Eigen::VectorXd& _tangent, StateSpace::State* _out) const override;
125 
132  void logMap(
133  const StateSpace::State* _in, Eigen::VectorXd& _tangent) const override;
134 
138  void print(const StateSpace::State* _state, std::ostream& _os) const override;
139 };
140 
141 } // namespace statespace
142 } // namespace aikido
143 
144 #include "detail/SE3-impl.hpp"
145 
146 #endif // ifndef AIKIDO_STATESPACE_SE3STATESPACE_HPP_
aikido::statespace::SE3::cloneState
ScopedState cloneState(const StateSpace::State *stateIn) const
Creates an identical clone of stateIn.
aikido::statespace::SE3::getStateSizeInBytes
std::size_t getStateSizeInBytes() const override
Gets the size of a State, in bytes.
aikido::statespace::SE3::freeStateInBuffer
void freeStateInBuffer(StateSpace::State *_state) const override
Free a state previously created by allocateStateInBuffer.
aikido::statespace::SE3::getIsometry
const Isometry3d & getIsometry(const State *_state) const
Gets value as an Eigen transformation object.
aikido::statespace::SE3::SE3
SE3()=default
Constructs a state space representing SE(3).
aikido::statespace::SE3::State::getIsometry
const Isometry3d & getIsometry() const
Gets value as an Eigen transformation object.
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::statespace::SE3::State::Isometry3d
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::DontAlign > Isometry3d
Definition: SE3.hpp:26
aikido::statespace::SE3::createState
ScopedState createState() const
Helper function to create a ScopedState.
aikido::statespace::SE3::print
void print(const StateSpace::State *_state, std::ostream &_os) const override
Print the quaternion followed by the translation Format: [q.w, q.x, q.y, q.z, x, y,...
aikido::statespace::SE3::logMap
void logMap(const StateSpace::State *_in, Eigen::VectorXd &_tangent) const override
Log mapping of Lie group element to a Lie algebra element.
StateSpace.hpp
aikido::statespace::SE3::Isometry3d
State::Isometry3d Isometry3d
Definition: SE3.hpp:62
aikido::statespace::SE3::State::State
State()
Constructs the identity element.
aikido::statespace::SE3StateHandle
StateHandle for a SE3.
Definition: SE3-impl.hpp:9
aikido::statespace::SE3::State::~State
~State()=default
aikido::statespace::SE3::copyState
void copyState(const StateSpace::State *_source, StateSpace::State *_destination) const override
Copy a state.
aikido::statespace::SE3::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::SE3::compose
void compose(const StateSpace::State *_state1, const StateSpace::State *_state2, StateSpace::State *_out) const override
Lie group operation for this StateSpace.
aikido::statespace::SE3::setIsometry
void setIsometry(State *_state, const Isometry3d &_transform) const
Sets value to an Eigen transfomation object.
aikido::statespace::StateSpace
Represents a Lie group and its associated Lie algebra, i.e.
Definition: StateSpace.hpp:33
aikido::statespace::ScopedState< StateHandle >
aikido::statespace::SE3
The three-dimensional special Euclidean group SE(3), i.e.
Definition: SE3.hpp:19
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::SE3::State::mTransform
Isometry3d mTransform
Definition: SE3.hpp:49
aikido::statespace::SE3::getDimension
std::size_t getDimension() const override
Get the dimension of this Lie group.
aikido::statespace::SE3::allocateStateInBuffer
StateSpace::State * allocateStateInBuffer(void *_buffer) const override
Create a new state in a pre-allocated buffer.
aikido::statespace::SE3::State
Definition: SE3.hpp:22
aikido::statespace::StateSpace::State
Definition: StateSpace.hpp:167
aikido::statespace::SE3::State::setIsometry
void setIsometry(const Isometry3d &_transform)
Sets value to an Eigen transfomation object.
aikido::statespace::SE3::getIdentity
void getIdentity(StateSpace::State *_out) const override
Gets the identity element for this Lie group, such that:
aikido::statespace::SE3::getInverse
void getInverse(const StateSpace::State *_in, StateSpace::State *_out) const override
Gets the inverse of _in in this Lie group, such that:
ScopedState.hpp
SE3-impl.hpp