| 
    Aikido
    
   | 
 
SO2 for a DART SingleDofJoint.  
 More...
#include <aikido/statespace/dart/SO2Joint.hpp>
  
Public Member Functions | |
| SO2Joint (const ::dart::dynamics::GenericJoint<::dart::math::R1Space > *joint) | |
Creates a state space for a FreeJoint.  More... | |
| void | convertPositionsToState (const Eigen::VectorXd &positions, StateSpace::State *state) const override | 
Converts DART Joint positions, e.g.  More... | |
| void | convertStateToPositions (const StateSpace::State *state, Eigen::VectorXd &positions) const override | 
Converts a State in this state space to DART Joint positions, e.g.  More... | |
  Public Member Functions inherited from aikido::statespace::SO2 | |
| SO2 ()=default | |
| Constructs a state space representing SO(2).  More... | |
| ScopedState | createState () const | 
Helper function to create a ScopedState.  More... | |
| ScopedState | cloneState (const StateSpace::State *stateIn) const | 
Creates an identical clone of stateIn.  More... | |
| double | toAngle (const State *state) const | 
| Returns state as a rotation angle in (-pi, pi].  More... | |
| void | fromAngle (State *state, double angle) const | 
| Sets state from a rotation angle in (-inf, inf).  More... | |
| Eigen::Rotation2Dd | toRotation (const State *state) const | 
| Returns state as an Eigen rotation.  More... | |
| void | fromRotation (State *state, const Eigen::Rotation2Dd &rotation) const | 
| Sets state from an Eigen rotation.  More... | |
| std::size_t | getStateSizeInBytes () const override | 
| Gets the size of a State, in bytes.  More... | |
| StateSpace::State * | allocateStateInBuffer (void *buffer) const override | 
| Create a new state in a pre-allocated buffer.  More... | |
| void | freeStateInBuffer (StateSpace::State *state) const override | 
Free a state previously created by allocateStateInBuffer.  More... | |
| void | compose (const StateSpace::State *state1, const StateSpace::State *state2, StateSpace::State *out) const override | 
| Lie group operation for this StateSpace.  More... | |
| void | getIdentity (StateSpace::State *out) const override | 
| Gets the identity element for this Lie group, such that:  More... | |
| void | getInverse (const StateSpace::State *in, StateSpace::State *out) const override | 
Gets the inverse of _in in this Lie group, such that:  More... | |
| std::size_t | getDimension () const override | 
| Get the dimension of this Lie group.  More... | |
| void | copyState (const StateSpace::State *source, StateSpace::State *destination) const override | 
| Copy a state.  More... | |
| void | expMap (const Eigen::VectorXd &tangent, StateSpace::State *out) const override | 
| Exponential mapping of Lie algebra element to a Lie group element.  More... | |
| void | logMap (const StateSpace::State *in, Eigen::VectorXd &tangent) const override | 
| Log mapping of Lie group element to a Lie algebra element.  More... | |
| void | print (const StateSpace::State *state, std::ostream &os) const override | 
| Print the angle represented by the state.  More... | |
| virtual void | compose (const State *_state1, const State *_state2, State *_out) const=0 | 
| Lie group operation for this StateSpace.  More... | |
| virtual void | compose (State *_state1, const State *_state2) const | 
| Lie group operation for this StateSpace.  More... | |
  Public Member Functions inherited from aikido::statespace::StateSpace | |
| virtual | ~StateSpace ()=default | 
| ScopedState | createState () const | 
Helper function to create a ScopedState.  More... | |
| ScopedState | cloneState (const State *stateIn) const | 
Creates an identical clone of stateIn.  More... | |
| virtual State * | allocateState () const | 
| Allocate a new state.  More... | |
| virtual void | freeState (State *_state) const | 
Free a state previously created by allocateState.  More... | |
| virtual void | compose (State *_state1, const State *_state2) const | 
| Lie group operation for this StateSpace.  More... | |
| virtual void | getInverse (State *_state) const | 
Gets the inverse of _in in this Lie group.  More... | |
  Public Member Functions inherited from aikido::statespace::dart::JointStateSpace | |
| JointStateSpace (const ::dart::dynamics::Joint *joint) | |
Constructs a state space for joint.  More... | |
| virtual | ~JointStateSpace ()=default | 
| Destructor.  More... | |
| const Properties & | getProperties () const | 
| Gets the joint properties associated with this state space.  More... | |
| bool | isCompatible (const ::dart::dynamics::Joint *joint) const | 
| Returns whether the Joint can be used with this state space.  More... | |
| void | checkCompatibility (const ::dart::dynamics::Joint *joint) const | 
| Throws an error if the Joint cannot be used with this state space.  More... | |
| virtual void | getState (const ::dart::dynamics::Joint *joint, StateSpace::State *state) const | 
Gets the positions of the joint and store them in state.  More... | |
| virtual void | setState (::dart::dynamics::Joint *joint, const StateSpace::State *state) const | 
Sets the positions of the joint to state.  More... | |
Additional Inherited Members | |
  Public Types inherited from aikido::statespace::SO2 | |
| using | StateHandle = SO2StateHandle< State > | 
| using | StateHandleConst = SO2StateHandle< const State > | 
| using | ScopedState = statespace::ScopedState< StateHandle > | 
| using | ScopedStateConst = statespace::ScopedState< StateHandleConst > | 
  Public Types inherited from aikido::statespace::StateSpace | |
| using | StateHandle = statespace::StateHandle< StateSpace, State > | 
| using | StateHandleConst = statespace::StateHandle< StateSpace, const State > | 
| using | ScopedState = statespace::ScopedState< StateHandle > | 
| using | ScopedStateConst = statespace::ScopedState< StateHandleConst > | 
  Protected Attributes inherited from aikido::statespace::dart::JointStateSpace | |
| Properties | mProperties | 
SO2 for a DART SingleDofJoint. 
This class does not support position limits.
      
  | 
  explicit | 
Creates a state space for a FreeJoint. 
This class does not support position limits.
| joint | joint to create a state space for | 
      
  | 
  overridevirtual | 
Converts DART Joint positions, e.g. 
those returned by getPositions, to a State in this state space.
| positions | input DART Joint positions  | |
| [out] | state | output state | 
Implements aikido::statespace::dart::JointStateSpace.
      
  | 
  overridevirtual | 
Converts a State in this state space to DART Joint positions, e.g. 
that may be passed to setPositions.
| state | input state | |
| [out] | positions | output DART Joint positions  | 
Implements aikido::statespace::dart::JointStateSpace.