Aikido
StateSpace.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_STATESPACE_STATESPACE_HPP_
2 #define AIKIDO_STATESPACE_STATESPACE_HPP_
3 
4 #include <memory>
5 
6 #include <Eigen/Dense>
7 
8 #include "aikido/common/RNG.hpp"
11 
12 namespace aikido {
13 namespace statespace {
14 
16 
17 class StateSpace
34 {
35 public:
37  class State;
38 
41 
44 
45  virtual ~StateSpace() = default;
46 
50  ScopedState createState() const;
51 
53  ScopedState cloneState(const State* stateIn) const;
54 
60  virtual State* allocateState() const;
61 
66  virtual void freeState(State* _state) const;
67 
71  virtual std::size_t getStateSizeInBytes() const = 0;
72 
79  virtual State* allocateStateInBuffer(void* _buffer) const = 0;
80 
85  virtual void freeStateInBuffer(State* _state) const = 0;
86 
93  virtual void compose(
94  const State* _state1, const State* _state2, State* _out) const = 0;
95 
105  virtual void compose(State* _state1, const State* _state2) const;
106 
113  virtual void getIdentity(State* _out) const = 0;
114 
123  virtual void getInverse(const State* _state, State* _out) const = 0;
124 
129  virtual void getInverse(State* _state) const;
130 
135  virtual std::size_t getDimension() const = 0;
136 
141  virtual void copyState(
142  const StateSpace::State* _source,
143  StateSpace::State* _destination) const = 0;
144 
151  virtual void expMap(const Eigen::VectorXd& _tangent, State* _out) const = 0;
152 
159  virtual void logMap(const State* _in, Eigen::VectorXd& _tangent) const = 0;
160 
164  virtual void print(const State* _state, std::ostream& _os) const = 0;
165 };
166 
168 {
169 protected:
171  State() = default;
172 
176  ~State() = default;
177 };
178 
179 } // namespace statespace
180 } // namespace aikido
181 
182 #endif // ifndef AIKIDO_STATESPACE_STATESPACE_HPP_
RNG.hpp
aikido::statespace::StateSpace::State::~State
~State()=default
It is unsafe to call this, since it is a non-virtual destructor.
aikido::statespace::StateSpace::freeState
virtual void freeState(State *_state) const
Free a state previously created by allocateState.
aikido::statespace::StateSpace::expMap
virtual void expMap(const Eigen::VectorXd &_tangent, State *_out) const =0
Exponential mapping of Lie algebra element to a Lie group element.
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::statespace::StateSpace::logMap
virtual void logMap(const State *_in, Eigen::VectorXd &_tangent) const =0
Log mapping of Lie group element to a Lie algebra element.
aikido::statespace::StateSpace::print
virtual void print(const State *_state, std::ostream &_os) const =0
Print the state to the output stream.
aikido::statespace::StateSpace::allocateStateInBuffer
virtual State * allocateStateInBuffer(void *_buffer) const =0
Create a new state in a pre-allocated buffer.
aikido::statespace::StateSpace::getInverse
virtual void getInverse(const State *_state, State *_out) const =0
Gets the inverse of _in in this Lie group, such that:
aikido::statespace::StateSpace::allocateState
virtual State * allocateState() const
Allocate a new state.
aikido::statespace::StateSpace::State::State
State()=default
This is a base class that should only only be used in derived classes.
aikido::statespace::StateSpace::createState
ScopedState createState() const
Helper function to create a ScopedState.
pointers.hpp
aikido::statespace::StateHandle
Wrap a State with its StateSpace to provide convenient accessor methods.
Definition: StateHandle.hpp:16
aikido::statespace::StateSpace::getDimension
virtual std::size_t getDimension() const =0
Get the dimension of this Lie group.
aikido::statespace::StateSpace
Represents a Lie group and its associated Lie algebra, i.e.
Definition: StateSpace.hpp:33
aikido::statespace::StateSpace::getIdentity
virtual void getIdentity(State *_out) const =0
Gets the identity element for this Lie group, such that:
aikido::statespace::ScopedState< StateHandle >
aikido::statespace::StateSpace::freeStateInBuffer
virtual void freeStateInBuffer(State *_state) const =0
Free a state previously created by allocateStateInBuffer.
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::StateSpace::cloneState
ScopedState cloneState(const State *stateIn) const
Creates an identical clone of stateIn.
aikido::statespace::StateSpace::State
Definition: StateSpace.hpp:167
aikido::statespace::StateSpace::~StateSpace
virtual ~StateSpace()=default
AIKIDO_DECLARE_POINTERS
#define AIKIDO_DECLARE_POINTERS(X)
Definition: pointers.hpp:21
ScopedState.hpp
aikido::statespace::StateSpace::copyState
virtual void copyState(const StateSpace::State *_source, StateSpace::State *_destination) const =0
Copy a state.
aikido::statespace::StateSpace::getStateSizeInBytes
virtual std::size_t getStateSizeInBytes() const =0
Gets the size of a State, in bytes.