Aikido
aikido::statespace::dart::JointStateSpace Class Referenceabstract

StateSpace of a DART Joint. More...

#include <aikido/statespace/dart/JointStateSpace.hpp>

Inheritance diagram for aikido::statespace::dart::JointStateSpace:
aikido::statespace::StateSpace aikido::statespace::dart::RJoint< N > aikido::statespace::dart::SE2Joint aikido::statespace::dart::SE3Joint aikido::statespace::dart::SO2Joint aikido::statespace::dart::SO3Joint aikido::statespace::dart::WeldJoint

Classes

class  Properties
 Static properties from the DART Joint. More...
 

Public Member Functions

 JointStateSpace (const ::dart::dynamics::Joint *joint)
 Constructs a state space for joint. More...
 
virtual ~JointStateSpace ()=default
 Destructor. More...
 
const PropertiesgetProperties () 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 convertPositionsToState (const Eigen::VectorXd &positions, StateSpace::State *state) const =0
 Converts DART Joint positions, e.g. More...
 
virtual void convertStateToPositions (const StateSpace::State *state, Eigen::VectorXd &positions) const =0
 Converts a State in this state space to DART Joint positions, e.g. 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...
 
- 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 StateallocateState () const
 Allocate a new state. More...
 
virtual void freeState (State *_state) const
 Free a state previously created by allocateState. More...
 
virtual std::size_t getStateSizeInBytes () const =0
 Gets the size of a State, in bytes. More...
 
virtual StateallocateStateInBuffer (void *_buffer) const =0
 Create a new state in a pre-allocated buffer. More...
 
virtual void freeStateInBuffer (State *_state) const =0
 Free a state previously created by allocateStateInBuffer. 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...
 
virtual void getIdentity (State *_out) const =0
 Gets the identity element for this Lie group, such that: More...
 
virtual void getInverse (const State *_state, State *_out) const =0
 Gets the inverse of _in in this Lie group, such that: More...
 
virtual void getInverse (State *_state) const
 Gets the inverse of _in in this Lie group. More...
 
virtual std::size_t getDimension () const =0
 Get the dimension of this Lie group. More...
 
virtual void copyState (const StateSpace::State *_source, StateSpace::State *_destination) const =0
 Copy a state. More...
 
virtual void expMap (const Eigen::VectorXd &_tangent, State *_out) const =0
 Exponential mapping of Lie algebra element to a Lie group element. More...
 
virtual void logMap (const State *_in, Eigen::VectorXd &_tangent) const =0
 Log mapping of Lie group element to a Lie algebra element. More...
 
virtual void print (const State *_state, std::ostream &_os) const =0
 Print the state to the output stream. More...
 

Protected Attributes

Properties mProperties
 

Additional Inherited Members

- 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 >
 

Detailed Description

StateSpace of a DART Joint.

This is a base class that is inherited by concrete implementations for DART's various Joint subclasses. This class provides functions for converting between State objects and vectors of DART joint positions.

Since this class does not keep a reference to the underlying Joint, changes made to the Joint after the state space is constructed will not be reflected in the JointStateSpace.

Constructor & Destructor Documentation

◆ JointStateSpace()

aikido::statespace::dart::JointStateSpace::JointStateSpace ( const ::dart::dynamics::Joint *  joint)
explicit

Constructs a state space for joint.

Parameters
jointjoint to create a StateSpace from

◆ ~JointStateSpace()

virtual aikido::statespace::dart::JointStateSpace::~JointStateSpace ( )
virtualdefault

Destructor.

Member Function Documentation

◆ checkCompatibility()

void aikido::statespace::dart::JointStateSpace::checkCompatibility ( const ::dart::dynamics::Joint *  joint) const

Throws an error if the Joint cannot be used with this state space.

Parameters
jointJoint to check
Exceptions
invalid_argumentif the Joint does not match the state space

◆ convertPositionsToState()

virtual void aikido::statespace::dart::JointStateSpace::convertPositionsToState ( const Eigen::VectorXd &  positions,
StateSpace::State state 
) const
pure virtual

Converts DART Joint positions, e.g.

those returned by getPositions, to a State in this state space.

Parameters
positionsinput DART Joint positions
[out]stateoutput state

Implemented in aikido::statespace::dart::RJoint< N >, aikido::statespace::dart::SO2Joint, aikido::statespace::dart::SE3Joint, aikido::statespace::dart::SO3Joint, aikido::statespace::dart::WeldJoint, and aikido::statespace::dart::SE2Joint.

◆ convertStateToPositions()

virtual void aikido::statespace::dart::JointStateSpace::convertStateToPositions ( const StateSpace::State state,
Eigen::VectorXd &  positions 
) const
pure virtual

Converts a State in this state space to DART Joint positions, e.g.

that may be passed to setPositions.

Parameters
stateinput state
[out]positionsoutput DART Joint positions

Implemented in aikido::statespace::dart::RJoint< N >, aikido::statespace::dart::SO2Joint, aikido::statespace::dart::SE3Joint, aikido::statespace::dart::SO3Joint, aikido::statespace::dart::WeldJoint, and aikido::statespace::dart::SE2Joint.

◆ getProperties()

const Properties& aikido::statespace::dart::JointStateSpace::getProperties ( ) const

Gets the joint properties associated with this state space.

Returns
joint properties associated with this state space

◆ getState()

virtual void aikido::statespace::dart::JointStateSpace::getState ( const ::dart::dynamics::Joint *  joint,
StateSpace::State state 
) const
virtual

Gets the positions of the joint and store them in state.

Parameters
jointJoint to get position from
[out]stateoutput state

◆ isCompatible()

bool aikido::statespace::dart::JointStateSpace::isCompatible ( const ::dart::dynamics::Joint *  joint) const

Returns whether the Joint can be used with this state space.

Parameters
jointJoint to check

◆ setState()

virtual void aikido::statespace::dart::JointStateSpace::setState ( ::dart::dynamics::Joint *  joint,
const StateSpace::State state 
) const
virtual

Sets the positions of the joint to state.

Parameters
jointJoint to set position for
stateinput state

Member Data Documentation

◆ mProperties

Properties aikido::statespace::dart::JointStateSpace::mProperties
protected