Aikido
aikido::statespace::dart::SE2Joint Class Reference

SEStateSpace for a DART PlanarJoint This class does not support position limits on the rotational DegreeOfFreedom. More...

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

Inheritance diagram for aikido::statespace::dart::SE2Joint:
aikido::statespace::SE2 aikido::statespace::dart::JointStateSpace aikido::statespace::StateSpace aikido::statespace::StateSpace

Public Types

using Isometry2d = State::Isometry2d
 
- Public Types inherited from aikido::statespace::SE2
using StateHandle = SE2StateHandle< State >
 
using StateHandleConst = SE2StateHandle< const State >
 
using ScopedState = statespace::ScopedState< StateHandle >
 
using ScopedStateConst = statespace::ScopedState< StateHandleConst >
 
using Isometry2d = State::Isometry2d
 
- 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 >
 

Public Member Functions

 SE2Joint (const ::dart::dynamics::PlanarJoint *_joint)
 Creates a state space for a PlanarJoint. 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::SE2
 SE2 ()=default
 Constructs a state space representing SE(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...
 
const Isometry2dgetIsometry (const State *_state) const
 Gets value as an Eigen transformation object. More...
 
void setIsometry (State *_state, const Isometry2d &_transform) const
 Sets value to an Eigen transfomation object. More...
 
std::size_t getStateSizeInBytes () const override
 Gets the size of a State, in bytes. More...
 
StateSpace::StateallocateStateInBuffer (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 *_state, 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 state. Format: [x, y, theta]. 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 StateallocateState () 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 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 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

- Protected Attributes inherited from aikido::statespace::dart::JointStateSpace
Properties mProperties
 

Detailed Description

SEStateSpace for a DART PlanarJoint This class does not support position limits on the rotational DegreeOfFreedom.

Member Typedef Documentation

◆ Isometry2d

using aikido::statespace::SE2::Isometry2d = State::Isometry2d

Constructor & Destructor Documentation

◆ SE2Joint()

aikido::statespace::dart::SE2Joint::SE2Joint ( const ::dart::dynamics::PlanarJoint *  _joint)
explicit

Creates a state space for a PlanarJoint.

This class does not support position limits on the rotational DegreeOfFreedom.

Parameters
_jointjoint to create a state space for

Member Function Documentation

◆ convertPositionsToState()

void aikido::statespace::dart::SE2Joint::convertPositionsToState ( const Eigen::VectorXd &  positions,
StateSpace::State state 
) const
overridevirtual

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

Implements aikido::statespace::dart::JointStateSpace.

◆ convertStateToPositions()

void aikido::statespace::dart::SE2Joint::convertStateToPositions ( const StateSpace::State state,
Eigen::VectorXd &  positions 
) const
overridevirtual

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

Implements aikido::statespace::dart::JointStateSpace.