dynamicgraph::sot::Dynamic Class Reference

This class provides an inverse dynamic model of the robot. More precisely it wraps the newton euler algorithm implemented by the dynamicsJRLJapan library to make it accessible in the stack of tasks. The robot is described by a VRML file. More...

#include <sot-dynamic/dynamic.h>

Inheritance diagram for dynamicgraph::sot::Dynamic:
Collaboration diagram for dynamicgraph::sot::Dynamic:

Public Types

typedef int Dummy
 
- Public Types inherited from dynamicgraph::Entity
typedef std::map< std::string, SignalBase< int > * > SignalMap
 
typedef std::map< const std::string, command::Command *> CommandMap_t
 

Public Member Functions

 DYNAMIC_GRAPH_ENTITY_DECL ()
 
 Dynamic (const std::string &name, bool build=true)
 
virtual ~Dynamic (void)
 
virtual void buildModel (void)
 
void setVrmlDirectory (const std::string &filename)
 
void setVrmlMainFile (const std::string &filename)
 
void setXmlSpecificityFile (const std::string &filename)
 
void setXmlRankFile (const std::string &filename)
 
void parseConfigFiles (void)
 
dg::SignalTimeDependent< ml::Matrix, int > & createEndeffJacobianSignal (const std::string &signame, CjrlJoint *inJoint)
 
dg::SignalTimeDependent< ml::Matrix, int > & createJacobianSignal (const std::string &signame, CjrlJoint *inJoint)
 
void destroyJacobianSignal (const std::string &signame)
 
dg::SignalTimeDependent< MatrixHomogeneous, int > & createPositionSignal (const std::string &signame, CjrlJoint *inJoint)
 
void destroyPositionSignal (const std::string &signame)
 
dg::SignalTimeDependent< ml::Vector, int > & createVelocitySignal (const std::string &signame, CjrlJoint *inJoint)
 
void destroyVelocitySignal (const std::string &signame)
 
dg::SignalTimeDependent< ml::Vector, int > & createAccelerationSignal (const std::string &signame, CjrlJoint *inJoint)
 
void destroyAccelerationSignal (const std::string &signame)
 
bool zmpActivation (void)
 
void zmpActivation (const bool &b)
 
bool comActivation (void)
 
void comActivation (const bool &b)
 
int & computeNewtonEuler (int &dummy, int time)
 
int & initNewtonEuler (int &dummy, int time)
 
dg::SignalTimeDependent< ml::Matrix, int > & jacobiansSOUT (const std::string &name)
 
dg::SignalTimeDependent< MatrixHomogeneous, int > & positionsSOUT (const std::string &name)
 
dg::SignalTimeDependent< ml::Vector, int > & velocitiesSOUT (const std::string &name)
 
dg::SignalTimeDependent< ml::Vector, int > & accelerationsSOUT (const std::string &name)
 
virtual void commandLine (const std::string &cmdLine, std::istringstream &cmdArgs, std::ostream &os)
 
void cmd_createOpPointSignals (const std::string &sig, const std::string &j)
 
void cmd_createJacobianWorldSignal (const std::string &sig, const std::string &j)
 
void cmd_createJacobianEndEffectorSignal (const std::string &sig, const std::string &j)
 
void cmd_createPositionSignal (const std::string &sig, const std::string &j)
 
Construction of a robot by commands
void createRobot ()
 Create an empty device. More...
 
void createJoint (const std::string &inJointName, const std::string &inJointType, const ml::Matrix &inPosition)
 create a joint More...
 
void setRootJoint (const std::string &inJointName)
 Set a joint as root joint of the robot. More...
 
void addJoint (const std::string &inParentName, const std::string &inChildName)
 Add a child joint to a joint. More...
 
void setDofBounds (const std::string &inJointName, unsigned int inDofId, double inMinValue, double inMaxValue)
 Set bound of degree of freedom. More...
 
void setMass (const std::string &inJointName, double inMass)
 Set mass of a body. More...
 
void setLocalCenterOfMass (const std::string &inJointName, ml::Vector inCom)
 Set local center of mass of a body. More...
 
void setInertiaMatrix (const std::string &inJointName, ml::Matrix inMatrix)
 Set inertia matrix of a body. More...
 
void setSpecificJoint (const std::string &inJointName, const std::string &inJointType)
 Set specific joints. More...
 
void setHandParameters (bool inRight, const ml::Vector &inCenter, const ml::Vector &inThumbAxis, const ml::Vector &inForefingerAxis, const ml::Vector &inPalmNormal)
 Set hand parameters. More...
 
void setFootParameters (bool inRight, const double &inSoleLength, const double &inSoleWidth, const ml::Vector &inAnklePosition)
 Set foot parameters. More...
 
void setGazeParameters (const ml::Vector &inGazeOrigin, const ml::Vector &inGazeDirection)
 Set gaze parameters. More...
 
double getSoleLength () const
 Get length of left foot sole. More...
 
double getSoleWidth () const
 Get width of left foot sole. More...
 
ml::Vector getAnklePositionInFootFrame () const
 Get left ankle position in foot frame. More...
 
- Public Member Functions inherited from dynamicgraph::Entity
 Entity (const std::string &name)
 
virtual ~Entity ()
 
const std::string & getName () const
 
virtual const std::string & getClassName () const=0
 
virtual std::string getDocString () const
 
bool hasSignal (const std::string &signame) const
 
SignalBase< int > & getSignal (const std::string &signalName)
 
const SignalBase< int > & getSignal (const std::string &signalName) const
 
std::ostream & displaySignalList (std::ostream &os) const
 
virtual std::ostream & writeGraph (std::ostream &os) const
 
virtual std::ostream & writeCompletionList (std::ostream &os) const
 
virtual void display (std::ostream &os) const
 
virtual SignalBase< int > * test ()
 
virtual void test2 (SignalBase< int > *)
 
const std::string & getCommandList () const
 
CommandMap_t getNewStyleCommandMap ()
 
command::CommandgetNewStyleCommand (const std::string &cmdName)
 
SignalMap getSignalMap () const
 

Public Attributes

bool init
 
std::list< dg::SignalBase< int > *> genericSignalRefs
 
dg::SignalPtr< ml::Vector, int > jointPositionSIN
 
dg::SignalPtr< ml::Vector, int > freeFlyerPositionSIN
 
dg::SignalPtr< ml::Vector, int > jointVelocitySIN
 
dg::SignalPtr< ml::Vector, int > freeFlyerVelocitySIN
 
dg::SignalPtr< ml::Vector, int > jointAccelerationSIN
 
dg::SignalPtr< ml::Vector, int > freeFlyerAccelerationSIN
 
dg::SignalTimeDependent< Dummy, int > firstSINTERN
 
dg::SignalTimeDependent< Dummy, int > newtonEulerSINTERN
 
dg::SignalTimeDependent< ml::Vector, int > zmpSOUT
 
dg::SignalTimeDependent< ml::Matrix, int > JcomSOUT
 
dg::SignalTimeDependent< ml::Vector, int > comSOUT
 
dg::SignalTimeDependent< ml::Matrix, int > inertiaSOUT
 
dg::SignalTimeDependent< double, int > footHeightSOUT
 
dg::SignalTimeDependent< ml::Vector, int > upperJlSOUT
 
dg::SignalTimeDependent< ml::Vector, int > lowerJlSOUT
 
dg::SignalTimeDependent< ml::Vector, int > upperVlSOUT
 
dg::SignalTimeDependent< ml::Vector, int > lowerVlSOUT
 
dg::SignalTimeDependent< ml::Vector, int > upperTlSOUT
 
dg::SignalTimeDependent< ml::Vector, int > lowerTlSOUT
 
dg::Signal< ml::Vector, int > inertiaRotorSOUT
 
dg::Signal< ml::Vector, int > gearRatioSOUT
 
dg::SignalTimeDependent< ml::Matrix, int > inertiaRealSOUT
 
dg::SignalTimeDependent< ml::Vector, int > MomentaSOUT
 
dg::SignalTimeDependent< ml::Vector, int > AngularMomentumSOUT
 
dg::SignalTimeDependent< ml::Vector, int > dynamicDriftSOUT
 
Fields to access dynamicsJRLJapan Library
CjrlHumanoidDynamicRobot * m_HDR
 Abstract pointer on the structure. Ultimately we should be able to use only the abstract interface and do not care about the implementation. More...
 
int debugInertia
 
std::string vrmlDirectory
 Fields to access the humanoid model. More...
 
std::string vrmlMainFile
 Name of the root's robot model file. More...
 
std::string xmlSpecificityFile
 Name of the name specifying which end-effector is the head, the feet and so on... More...
 
std::string xmlRankFile
 Name of the name specifying which end-effector is the head, the feet and so on... More...
 

Protected Member Functions

ml::VectorcomputeZmp (ml::Vector &res, int time)
 
ml::VectorcomputeMomenta (ml::Vector &res, int time)
 
ml::VectorcomputeAngularMomentum (ml::Vector &res, int time)
 
ml::MatrixcomputeJcom (ml::Matrix &res, int time)
 
ml::VectorcomputeCom (ml::Vector &res, int time)
 
ml::MatrixcomputeInertia (ml::Matrix &res, int time)
 
ml::MatrixcomputeInertiaReal (ml::Matrix &res, int time)
 
double & computeFootHeight (double &res, int time)
 
ml::MatrixcomputeGenericJacobian (CjrlJoint *j, ml::Matrix &res, int time)
 
ml::MatrixcomputeGenericEndeffJacobian (CjrlJoint *j, ml::Matrix &res, int time)
 
MatrixHomogeneouscomputeGenericPosition (CjrlJoint *j, MatrixHomogeneous &res, int time)
 
ml::VectorcomputeGenericVelocity (CjrlJoint *j, ml::Vector &res, int time)
 
ml::VectorcomputeGenericAcceleration (CjrlJoint *j, ml::Vector &res, int time)
 
ml::VectorgetUpperJointLimits (ml::Vector &res, const int &time)
 
ml::VectorgetLowerJointLimits (ml::Vector &res, const int &time)
 
ml::VectorgetUpperVelocityLimits (ml::Vector &res, const int &time)
 
ml::VectorgetLowerVelocityLimits (ml::Vector &res, const int &time)
 
ml::VectorgetUpperTorqueLimits (ml::Vector &res, const int &time)
 
ml::VectorgetLowerTorqueLimits (ml::Vector &res, const int &time)
 
ml::VectorcomputeTorqueDrift (ml::Vector &res, const int &time)
 
- Protected Member Functions inherited from dynamicgraph::Entity
void addCommand (const std::string &name, command::Command *command)
 
void entityRegistration ()
 
void entityDeregistration ()
 
void signalRegistration (const SignalArray< int > &signals)
 
void signalDeregistration (const std::string &name)
 

Friends

class sot::command::SetFiles
 
class sot::command::Parse
 
class sot::command::CreateOpPoint
 
class sot::command::InitializeRobot
 

Additional Inherited Members

- Protected Attributes inherited from dynamicgraph::Entity
std::string name
 
SignalMap signalMap
 
CommandMap_t commandMap
 

Detailed Description

This class provides an inverse dynamic model of the robot. More precisely it wraps the newton euler algorithm implemented by the dynamicsJRLJapan library to make it accessible in the stack of tasks. The robot is described by a VRML file.

Member Typedef Documentation

◆ Dummy

Constructor & Destructor Documentation

◆ Dynamic()

dynamicgraph::sot::Dynamic::Dynamic ( const std::string &  name,
bool  build = true 
)

◆ ~Dynamic()

virtual dynamicgraph::sot::Dynamic::~Dynamic ( void  )
virtual

Member Function Documentation

◆ accelerationsSOUT()

dg::SignalTimeDependent<ml::Vector,int>& dynamicgraph::sot::Dynamic::accelerationsSOUT ( const std::string &  name)

◆ addJoint()

void dynamicgraph::sot::Dynamic::addJoint ( const std::string &  inParentName,
const std::string &  inChildName 
)

Add a child joint to a joint.

Parameters
inParentNamename of the joint to which a child is added.
inChildNamename of the child joint added.

◆ buildModel()

virtual void dynamicgraph::sot::Dynamic::buildModel ( void  )
virtual

◆ cmd_createJacobianEndEffectorSignal()

void dynamicgraph::sot::Dynamic::cmd_createJacobianEndEffectorSignal ( const std::string &  sig,
const std::string &  j 
)

◆ cmd_createJacobianWorldSignal()

void dynamicgraph::sot::Dynamic::cmd_createJacobianWorldSignal ( const std::string &  sig,
const std::string &  j 
)

◆ cmd_createOpPointSignals()

void dynamicgraph::sot::Dynamic::cmd_createOpPointSignals ( const std::string &  sig,
const std::string &  j 
)

◆ cmd_createPositionSignal()

void dynamicgraph::sot::Dynamic::cmd_createPositionSignal ( const std::string &  sig,
const std::string &  j 
)

◆ comActivation() [1/2]

bool dynamicgraph::sot::Dynamic::comActivation ( void  )
inline

◆ comActivation() [2/2]

void dynamicgraph::sot::Dynamic::comActivation ( const bool &  b)
inline

◆ commandLine()

virtual void dynamicgraph::sot::Dynamic::commandLine ( const std::string &  cmdLine,
std::istringstream &  cmdArgs,
std::ostream &  os 
)
virtual

Reimplemented from dynamicgraph::Entity.

◆ computeAngularMomentum()

ml::Vector& dynamicgraph::sot::Dynamic::computeAngularMomentum ( ml::Vector res,
int  time 
)
protected

◆ computeCom()

ml::Vector& dynamicgraph::sot::Dynamic::computeCom ( ml::Vector res,
int  time 
)
protected

◆ computeFootHeight()

double& dynamicgraph::sot::Dynamic::computeFootHeight ( double &  res,
int  time 
)
protected

◆ computeGenericAcceleration()

ml::Vector& dynamicgraph::sot::Dynamic::computeGenericAcceleration ( CjrlJoint *  j,
ml::Vector res,
int  time 
)
protected

◆ computeGenericEndeffJacobian()

ml::Matrix& dynamicgraph::sot::Dynamic::computeGenericEndeffJacobian ( CjrlJoint *  j,
ml::Matrix res,
int  time 
)
protected

◆ computeGenericJacobian()

ml::Matrix& dynamicgraph::sot::Dynamic::computeGenericJacobian ( CjrlJoint *  j,
ml::Matrix res,
int  time 
)
protected

◆ computeGenericPosition()

MatrixHomogeneous& dynamicgraph::sot::Dynamic::computeGenericPosition ( CjrlJoint *  j,
MatrixHomogeneous res,
int  time 
)
protected

◆ computeGenericVelocity()

ml::Vector& dynamicgraph::sot::Dynamic::computeGenericVelocity ( CjrlJoint *  j,
ml::Vector res,
int  time 
)
protected

◆ computeInertia()

ml::Matrix& dynamicgraph::sot::Dynamic::computeInertia ( ml::Matrix res,
int  time 
)
protected

◆ computeInertiaReal()

ml::Matrix& dynamicgraph::sot::Dynamic::computeInertiaReal ( ml::Matrix res,
int  time 
)
protected

◆ computeJcom()

ml::Matrix& dynamicgraph::sot::Dynamic::computeJcom ( ml::Matrix res,
int  time 
)
protected

◆ computeMomenta()

ml::Vector& dynamicgraph::sot::Dynamic::computeMomenta ( ml::Vector res,
int  time 
)
protected

◆ computeNewtonEuler()

int& dynamicgraph::sot::Dynamic::computeNewtonEuler ( int &  dummy,
int  time 
)

◆ computeTorqueDrift()

ml::Vector& dynamicgraph::sot::Dynamic::computeTorqueDrift ( ml::Vector res,
const int &  time 
)
protected

◆ computeZmp()

ml::Vector& dynamicgraph::sot::Dynamic::computeZmp ( ml::Vector res,
int  time 
)
protected

◆ createAccelerationSignal()

dg::SignalTimeDependent< ml::Vector,int >& dynamicgraph::sot::Dynamic::createAccelerationSignal ( const std::string &  signame,
CjrlJoint *  inJoint 
)

◆ createEndeffJacobianSignal()

dg::SignalTimeDependent< ml::Matrix,int >& dynamicgraph::sot::Dynamic::createEndeffJacobianSignal ( const std::string &  signame,
CjrlJoint *  inJoint 
)

◆ createJacobianSignal()

dg::SignalTimeDependent< ml::Matrix,int >& dynamicgraph::sot::Dynamic::createJacobianSignal ( const std::string &  signame,
CjrlJoint *  inJoint 
)

◆ createJoint()

void dynamicgraph::sot::Dynamic::createJoint ( const std::string &  inJointName,
const std::string &  inJointType,
const ml::Matrix inPosition 
)

create a joint

Parameters
inJointNamename of the joint,
inJointTypetype of joint in ["freeflyer","rotation","translation","anchor"],
inPositionposition of the joint (4x4 homogeneous matrix).
Note
joints are stored in a map with names as keys for retrieval by other commands. An empty CjrlBody is also created and attached to the joint.

◆ createPositionSignal()

dg::SignalTimeDependent< MatrixHomogeneous,int >& dynamicgraph::sot::Dynamic::createPositionSignal ( const std::string &  signame,
CjrlJoint *  inJoint 
)

◆ createRobot()

void dynamicgraph::sot::Dynamic::createRobot ( )

Create an empty device.

◆ createVelocitySignal()

dg::SignalTimeDependent< ml::Vector,int >& dynamicgraph::sot::Dynamic::createVelocitySignal ( const std::string &  signame,
CjrlJoint *  inJoint 
)

◆ destroyAccelerationSignal()

void dynamicgraph::sot::Dynamic::destroyAccelerationSignal ( const std::string &  signame)

◆ destroyJacobianSignal()

void dynamicgraph::sot::Dynamic::destroyJacobianSignal ( const std::string &  signame)

◆ destroyPositionSignal()

void dynamicgraph::sot::Dynamic::destroyPositionSignal ( const std::string &  signame)

◆ destroyVelocitySignal()

void dynamicgraph::sot::Dynamic::destroyVelocitySignal ( const std::string &  signame)

◆ DYNAMIC_GRAPH_ENTITY_DECL()

dynamicgraph::sot::Dynamic::DYNAMIC_GRAPH_ENTITY_DECL ( )

◆ getAnklePositionInFootFrame()

ml::Vector dynamicgraph::sot::Dynamic::getAnklePositionInFootFrame ( ) const

Get left ankle position in foot frame.

The robot is assumed to be symmetric.

◆ getLowerJointLimits()

ml::Vector& dynamicgraph::sot::Dynamic::getLowerJointLimits ( ml::Vector res,
const int &  time 
)
protected

◆ getLowerTorqueLimits()

ml::Vector& dynamicgraph::sot::Dynamic::getLowerTorqueLimits ( ml::Vector res,
const int &  time 
)
protected

◆ getLowerVelocityLimits()

ml::Vector& dynamicgraph::sot::Dynamic::getLowerVelocityLimits ( ml::Vector res,
const int &  time 
)
protected

◆ getSoleLength()

double dynamicgraph::sot::Dynamic::getSoleLength ( ) const

Get length of left foot sole.

The robot is assumed to be symmetric.

◆ getSoleWidth()

double dynamicgraph::sot::Dynamic::getSoleWidth ( ) const

Get width of left foot sole.

The robot is assumed to be symmetric.

◆ getUpperJointLimits()

ml::Vector& dynamicgraph::sot::Dynamic::getUpperJointLimits ( ml::Vector res,
const int &  time 
)
protected

◆ getUpperTorqueLimits()

ml::Vector& dynamicgraph::sot::Dynamic::getUpperTorqueLimits ( ml::Vector res,
const int &  time 
)
protected

◆ getUpperVelocityLimits()

ml::Vector& dynamicgraph::sot::Dynamic::getUpperVelocityLimits ( ml::Vector res,
const int &  time 
)
protected

◆ initNewtonEuler()

int& dynamicgraph::sot::Dynamic::initNewtonEuler ( int &  dummy,
int  time 
)

◆ jacobiansSOUT()

dg::SignalTimeDependent<ml::Matrix,int>& dynamicgraph::sot::Dynamic::jacobiansSOUT ( const std::string &  name)

◆ parseConfigFiles()

void dynamicgraph::sot::Dynamic::parseConfigFiles ( void  )

◆ positionsSOUT()

dg::SignalTimeDependent<MatrixHomogeneous,int>& dynamicgraph::sot::Dynamic::positionsSOUT ( const std::string &  name)

◆ setDofBounds()

void dynamicgraph::sot::Dynamic::setDofBounds ( const std::string &  inJointName,
unsigned int  inDofId,
double  inMinValue,
double  inMaxValue 
)

Set bound of degree of freedom.

Parameters
inJointNamename of the joint,
inDofIdid of the degree of freedom in the joint,
inMinValue,inMaxValuevalues of degree of freedom bounds

◆ setFootParameters()

void dynamicgraph::sot::Dynamic::setFootParameters ( bool  inRight,
const double &  inSoleLength,
const double &  inSoleWidth,
const ml::Vector inAnklePosition 
)

Set foot parameters.

Parameters
inRighttrue if right foot, false if left foot,
inSoleLengthsole length,
inSoleWidthsole width,
inAnklePositionankle position in foot local frame,

◆ setGazeParameters()

void dynamicgraph::sot::Dynamic::setGazeParameters ( const ml::Vector inGazeOrigin,
const ml::Vector inGazeDirection 
)

Set gaze parameters.

Parameters
inGazeOriginorigin of the gaze in gaze joint local frame,
inGazeDirectiondirection of the gase in gaze joint local frame.

◆ setHandParameters()

void dynamicgraph::sot::Dynamic::setHandParameters ( bool  inRight,
const ml::Vector inCenter,
const ml::Vector inThumbAxis,
const ml::Vector inForefingerAxis,
const ml::Vector inPalmNormal 
)

Set hand parameters.

Parameters
inRighttrue if right hand, false if left hand,
inCentercenter of the hand in wrist local frame,
inThumbAxisthumb axis in wrist local frame,
inForefingerAxisforefinger axis in wrist local frame,
inPalmNormalAxispalm normal in wrist local frame,

◆ setInertiaMatrix()

void dynamicgraph::sot::Dynamic::setInertiaMatrix ( const std::string &  inJointName,
ml::Matrix  inMatrix 
)

Set inertia matrix of a body.

Parameters
inJointNamename of the joint to which the body is attached,
inMatrixinertia matrix.

◆ setLocalCenterOfMass()

void dynamicgraph::sot::Dynamic::setLocalCenterOfMass ( const std::string &  inJointName,
ml::Vector  inCom 
)

Set local center of mass of a body.

Parameters
inJointNamename of the joint to which the body is attached,
inComlocal center of mass.

◆ setMass()

void dynamicgraph::sot::Dynamic::setMass ( const std::string &  inJointName,
double  inMass 
)

Set mass of a body.

Parameters
inJointNamename of the joint to which the body is attached,
inMassmass of the body

◆ setRootJoint()

void dynamicgraph::sot::Dynamic::setRootJoint ( const std::string &  inJointName)

Set a joint as root joint of the robot.

◆ setSpecificJoint()

void dynamicgraph::sot::Dynamic::setSpecificJoint ( const std::string &  inJointName,
const std::string &  inJointType 
)

Set specific joints.

Parameters
inJointNamename of the joint,
inJointTypetype of joint in ['chest','waist','left-wrist','right-wrist','left-ankle','right-ankle','gaze'].

◆ setVrmlDirectory()

void dynamicgraph::sot::Dynamic::setVrmlDirectory ( const std::string &  filename)

◆ setVrmlMainFile()

void dynamicgraph::sot::Dynamic::setVrmlMainFile ( const std::string &  filename)

◆ setXmlRankFile()

void dynamicgraph::sot::Dynamic::setXmlRankFile ( const std::string &  filename)

◆ setXmlSpecificityFile()

void dynamicgraph::sot::Dynamic::setXmlSpecificityFile ( const std::string &  filename)

◆ velocitiesSOUT()

dg::SignalTimeDependent<ml::Vector,int>& dynamicgraph::sot::Dynamic::velocitiesSOUT ( const std::string &  name)

◆ zmpActivation() [1/2]

bool dynamicgraph::sot::Dynamic::zmpActivation ( void  )
inline

◆ zmpActivation() [2/2]

void dynamicgraph::sot::Dynamic::zmpActivation ( const bool &  b)
inline

Friends And Related Function Documentation

◆ sot::command::CreateOpPoint

friend class sot::command::CreateOpPoint
friend

◆ sot::command::InitializeRobot

friend class sot::command::InitializeRobot
friend

◆ sot::command::Parse

friend class sot::command::Parse
friend

◆ sot::command::SetFiles

friend class sot::command::SetFiles
friend

Member Data Documentation

◆ AngularMomentumSOUT

dg::SignalTimeDependent<ml::Vector,int> dynamicgraph::sot::Dynamic::AngularMomentumSOUT

◆ comSOUT

dg::SignalTimeDependent<ml::Vector,int> dynamicgraph::sot::Dynamic::comSOUT

◆ debugInertia

int dynamicgraph::sot::Dynamic::debugInertia

◆ dynamicDriftSOUT

dg::SignalTimeDependent<ml::Vector,int> dynamicgraph::sot::Dynamic::dynamicDriftSOUT

◆ firstSINTERN

dg::SignalTimeDependent<Dummy,int> dynamicgraph::sot::Dynamic::firstSINTERN

◆ footHeightSOUT

dg::SignalTimeDependent<double,int> dynamicgraph::sot::Dynamic::footHeightSOUT

◆ freeFlyerAccelerationSIN

dg::SignalPtr<ml::Vector,int> dynamicgraph::sot::Dynamic::freeFlyerAccelerationSIN

◆ freeFlyerPositionSIN

dg::SignalPtr<ml::Vector,int> dynamicgraph::sot::Dynamic::freeFlyerPositionSIN

◆ freeFlyerVelocitySIN

dg::SignalPtr<ml::Vector,int> dynamicgraph::sot::Dynamic::freeFlyerVelocitySIN

◆ gearRatioSOUT

dg::Signal<ml::Vector,int> dynamicgraph::sot::Dynamic::gearRatioSOUT

◆ genericSignalRefs

std::list< dg::SignalBase<int>* > dynamicgraph::sot::Dynamic::genericSignalRefs

◆ inertiaRealSOUT

dg::SignalTimeDependent<ml::Matrix,int> dynamicgraph::sot::Dynamic::inertiaRealSOUT

◆ inertiaRotorSOUT

dg::Signal<ml::Vector,int> dynamicgraph::sot::Dynamic::inertiaRotorSOUT

◆ inertiaSOUT

dg::SignalTimeDependent<ml::Matrix,int> dynamicgraph::sot::Dynamic::inertiaSOUT

◆ init

bool dynamicgraph::sot::Dynamic::init

◆ JcomSOUT

dg::SignalTimeDependent<ml::Matrix,int> dynamicgraph::sot::Dynamic::JcomSOUT

◆ jointAccelerationSIN

dg::SignalPtr<ml::Vector,int> dynamicgraph::sot::Dynamic::jointAccelerationSIN

◆ jointPositionSIN

dg::SignalPtr<ml::Vector,int> dynamicgraph::sot::Dynamic::jointPositionSIN

◆ jointVelocitySIN

dg::SignalPtr<ml::Vector,int> dynamicgraph::sot::Dynamic::jointVelocitySIN

◆ lowerJlSOUT

dg::SignalTimeDependent<ml::Vector,int> dynamicgraph::sot::Dynamic::lowerJlSOUT

◆ lowerTlSOUT

dg::SignalTimeDependent<ml::Vector,int> dynamicgraph::sot::Dynamic::lowerTlSOUT

◆ lowerVlSOUT

dg::SignalTimeDependent<ml::Vector,int> dynamicgraph::sot::Dynamic::lowerVlSOUT

◆ m_HDR

CjrlHumanoidDynamicRobot* dynamicgraph::sot::Dynamic::m_HDR

Abstract pointer on the structure. Ultimately we should be able to use only the abstract interface and do not care about the implementation.

◆ MomentaSOUT

dg::SignalTimeDependent<ml::Vector,int> dynamicgraph::sot::Dynamic::MomentaSOUT

◆ newtonEulerSINTERN

dg::SignalTimeDependent<Dummy,int> dynamicgraph::sot::Dynamic::newtonEulerSINTERN

◆ upperJlSOUT

dg::SignalTimeDependent<ml::Vector,int> dynamicgraph::sot::Dynamic::upperJlSOUT

◆ upperTlSOUT

dg::SignalTimeDependent<ml::Vector,int> dynamicgraph::sot::Dynamic::upperTlSOUT

◆ upperVlSOUT

dg::SignalTimeDependent<ml::Vector,int> dynamicgraph::sot::Dynamic::upperVlSOUT

◆ vrmlDirectory

std::string dynamicgraph::sot::Dynamic::vrmlDirectory

Fields to access the humanoid model.

Directory where the VRML humanoid model is stored

◆ vrmlMainFile

std::string dynamicgraph::sot::Dynamic::vrmlMainFile

Name of the root's robot model file.

◆ xmlRankFile

std::string dynamicgraph::sot::Dynamic::xmlRankFile

Name of the name specifying which end-effector is the head, the feet and so on...

◆ xmlSpecificityFile

std::string dynamicgraph::sot::Dynamic::xmlSpecificityFile

Name of the name specifying which end-effector is the head, the feet and so on...

◆ zmpSOUT

dg::SignalTimeDependent<ml::Vector,int> dynamicgraph::sot::Dynamic::zmpSOUT