iCub-main
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
iCub::iDyn::RigidBodyTransformation Class Reference

A class for setting a rigid body transformation between iDynLimb and iDynNode. More...

#include <iDynBody.h>

Public Member Functions

 RigidBodyTransformation (iDyn::iDynLimb *_limb, const yarp::sig::Matrix &_H, const std::string &_info, bool _hasSensor=false, const FlowType kin=RBT_NODE_OUT, const FlowType wre=RBT_NODE_IN, const NewEulMode _mode=DYNAMIC, unsigned int verb=iCub::skinDynLib::VERBOSE)
 Constructor, defining the limb attached to the node. More...
 
 ~RigidBodyTransformation ()
 Destructor. More...
 
bool setRBT (const yarp::sig::Matrix &_H)
 Set the roto-translational matrix between the limb and the node, defining the rigid body transformation. More...
 
bool setKinematic (const yarp::sig::Vector &w0, const yarp::sig::Vector &dw0, const yarp::sig::Vector &ddp0)
 Set the kinematic variables (w,dw,ddp) of the limb. More...
 
bool setKinematicMeasure (const yarp::sig::Vector &w0, const yarp::sig::Vector &dw0, const yarp::sig::Vector &ddp0)
 Set the kinematic variables (w,dw,ddp) of the limb, coming from external measurements (ie a sensor). More...
 
bool setWrench (const yarp::sig::Vector &F0, const yarp::sig::Vector &Mu0)
 Set the wrench variables (F,Mu) of the limb. More...
 
bool setWrenchMeasure (const yarp::sig::Vector &F0, const yarp::sig::Vector &Mu0)
 Set the wrench variables (F,Mu) of the limb. More...
 
bool setWrenchMeasure (iDyn::iDynSensor *sensor, const yarp::sig::Vector &Fsens, const yarp::sig::Vector &Musens)
 Set the wrench variables in the sensor. More...
 
yarp::sig::Matrix getRBT () const
 Return the the (4x4) roto-translational matrix defining the rigid body transformation. More...
 
void getKinematic (yarp::sig::Vector &wNode, yarp::sig::Vector &dwNode, yarp::sig::Vector &ddpNode)
 Get the kinematic variables (w,dw,ddp) of the limb, applies the RBT transformation and compute the kinematic variables of the node. More...
 
void getWrench (yarp::sig::Vector &FNode, yarp::sig::Vector &MuNode)
 Get the wrench variables (F,Mu) of the limb, transform it according to the RBT and add it to the node wrench. More...
 
void setInfoFlow (const FlowType kin, const FlowType wre)
 Set the flow of kinematic/wrench information: input to node or output from node. More...
 
FlowType getKinematicFlow () const
 Return the kinematic flow type. More...
 
FlowType getWrenchFlow () const
 return the wrench flow type More...
 
std::string toString () const
 Return some information. More...
 
bool isSensorized () const
 Return a boolean, depending if the limb attached to the RBT has a FT sensor or not. More...
 
void computeLimbKinematic ()
 Calls the compute kinematic of the limb. More...
 
void computeLimbWrench ()
 Calls the compute wrench of the limb. More...
 
unsigned int getNLinks () const
 Return the number of links of the limb (N) More...
 
unsigned int getDOF () const
 Return the number of DOF of the limb (DOF <= N) More...
 
yarp::sig::Matrix getH (const unsigned int i, const bool allLink=false)
 Return the i-th roto-translational matrix of the chain. More...
 
yarp::sig::Matrix getH ()
 Return the end-effector roto-translational matrix of the end-effector H of the end-effector. More...
 
yarp::sig::Vector getEndEffPose (const bool axisRep=true)
 Return the end-effector pose: x-y-z Cartesian position and 3/4 angles of orientation. More...
 
yarp::sig::Matrix computeGeoJacobian (const unsigned int iLink, const yarp::sig::Matrix &Pn, bool rbtRoto=false)
 This method is used to compute the Jacobian between two links in two different chains (eg from link 4 in chain_A to link 3 in chain_B. More...
 
yarp::sig::Matrix computeGeoJacobian (const unsigned int iLink, const yarp::sig::Matrix &Pn, const yarp::sig::Matrix &H0, bool rbtRoto=false)
 This method is used to compute the Jacobian between two links in two different chains. More...
 
yarp::sig::Matrix computeGeoJacobian (const yarp::sig::Matrix &Pn, bool rbtRoto=false)
 This method is used to compute the Jacobian between two links in two different chains: in this case it returns the jacobian matrix of the whole chain (from base to end-effector) when Pn is an external vector. More...
 
yarp::sig::Matrix computeGeoJacobian (const yarp::sig::Matrix &Pn, const yarp::sig::Matrix &H0, bool rbtRoto=false)
 This method is used to compute the Jacobian between two links in two different chains: in this case it returns the jacobian matrix of the whole chain (from base to end-effector) when Pn is an external vector, and H0 is an external matrix. More...
 
yarp::sig::Matrix computeGeoJacobian (bool rbtRoto=false)
 
yarp::sig::Matrix computeGeoJacobian (const unsigned int iLink, bool rbtRoto=false)
 Returns the Jacobian matrix of the limb until the link whose index is iLink in the chain. More...
 
yarp::sig::Matrix getR6 () const
 Return a 6x6 diagonal matrix with the rotational matrix of the RBT. More...
 
yarp::sig::Matrix getH0 () const
 Return the H0 matrix of the limb attached to the RBT. More...
 
bool setH0 (const yarp::sig::Matrix &_H0)
 Set a new H0 matrix in the limb attached to the RBT. More...
 
yarp::sig::Matrix TESTING_computeCOMJacobian (const unsigned int iLink, bool rbtRoto=false)
 Returns the Jacobian matrix of the COM of the selected link (index = iLink) in the chain. More...
 
yarp::sig::Matrix TESTING_computeCOMJacobian (const unsigned int iLink, const yarp::sig::Matrix &Pn, bool rbtRoto=false)
 Returns the Jacobian matrix of the COM of the selected link (index = iLink) in the chain: in this case Pn is an external vector, that happens when multiple limbs are connected. More...
 
yarp::sig::Matrix TESTING_computeCOMJacobian (const unsigned int iLink, const yarp::sig::Matrix &Pn, const yarp::sig::Matrix &_H0, bool rbtRoto=false)
 Returns the Jacobian matrix of the COM of the selected link (index = iLink) in the chain: in this case Pn is an external vector, that happens when multiple limbs are connected. More...
 
yarp::sig::Matrix getHCOM (unsigned int iLink)
 Returns the COM matrix of the selected link (index = iLink) in the chain. More...
 

Protected Member Functions

yarp::sig::Matrix getR ()
 Return the rotational 3x3 matrix of the RBT. More...
 
yarp::sig::Vector getr (bool proj=false)
 Return the translational part of the RBT matrix. More...
 
void computeKinematic ()
 Basic computations for applying RBT on kinematic variables. More...
 
void computeWrench ()
 Basic computations for applying RBT on wrench variables. More...
 

Protected Attributes

iDyn::iDynLimblimb
 the limb attached to the RigidBodyTransformation More...
 
FlowType kinFlow
 kinematic flow: in-to/out-from node (RBT_NODE_IN/RBT_NODE_OUT) More...
 
FlowType wreFlow
 wrench flow: in-to/out-from node (RBT_NODE_IN/RBT_NODE_OUT) More...
 
yarp::sig::Matrix H
 the roto-translation between the limb and the node More...
 
NewEulMode mode
 STATIC/DYNAMIC/DYNAMIC_W_ROTOR/DYNAMIC_CORIOLIS_GRAVITY. More...
 
std::string info
 info or useful notes More...
 
unsigned int verbose
 verbosity flag More...
 
bool hasSensor
 flag for sensor or not - only used for setWrenchMeasures() More...
 
yarp::sig::Vector w
 angular velocity More...
 
yarp::sig::Vector dw
 angular acceleration More...
 
yarp::sig::Vector ddp
 linear acceleration More...
 
yarp::sig::Vector F
 force More...
 
yarp::sig::Vector Mu
 moment More...
 

Detailed Description

A class for setting a rigid body transformation between iDynLimb and iDynNode.

This class is used by iDynNode to connect two or mutiple limbs and exchanging kinematic and wrench information between limbs.

Definition at line 131 of file iDynBody.h.

Constructor & Destructor Documentation

◆ RigidBodyTransformation()

RigidBodyTransformation::RigidBodyTransformation ( iDyn::iDynLimb _limb,
const yarp::sig::Matrix &  _H,
const std::string &  _info,
bool  _hasSensor = false,
const FlowType  kin = RBT_NODE_OUT,
const FlowType  wre = RBT_NODE_IN,
const NewEulMode  _mode = DYNAMIC,
unsigned int  verb = iCub::skinDynLib::VERBOSE 
)

Constructor, defining the limb attached to the node.

Parameters
_limbpointer to a iDynLimb
_Ha (4x4) roto-translational matrix defining the rigid body transformation
_infoa string with information
kinthe kinematic flow
wrethe wrench flow
_modethe NewEulMode for computations
verbverbosity flag

Definition at line 44 of file iDynBody.cpp.

◆ ~RigidBodyTransformation()

RigidBodyTransformation::~RigidBodyTransformation ( )

Destructor.

Definition at line 61 of file iDynBody.cpp.

Member Function Documentation

◆ computeGeoJacobian() [1/6]

Matrix RigidBodyTransformation::computeGeoJacobian ( bool  rbtRoto = false)
Parameters
rbtRotoif false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT
Returns
the Jacobian matrix of the chain

Definition at line 345 of file iDynBody.cpp.

◆ computeGeoJacobian() [2/6]

Matrix RigidBodyTransformation::computeGeoJacobian ( const unsigned int  iLink,
bool  rbtRoto = false 
)

Returns the Jacobian matrix of the limb until the link whose index is iLink in the chain.

This method basically calls GeoJacobian(iLink) in the iDynChain of the limb.

Parameters
iLinkthe index of the link, in the chain
rbtRotoif false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT
Returns
the Jacobian matrix of the chain - from the base to the i-th link

Definition at line 353 of file iDynBody.cpp.

◆ computeGeoJacobian() [3/6]

yarp::sig::Matrix iCub::iDyn::RigidBodyTransformation::computeGeoJacobian ( const unsigned int  iLink,
const yarp::sig::Matrix &  Pn,
bool  rbtRoto = false 
)

This method is used to compute the Jacobian between two links in two different chains (eg from link 4 in chain_A to link 3 in chain_B.

Parameters
iLinkthe index of the link, in the chain, being the base frame for the Jacobian computation
Pnthe matrix describing the roto-translational matrix between base and end-effector (in two different limbs)
rbtRotoif false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT
Returns
the Jacobian matrix from the base of the chain until the iLink (e.g. from link 0 to 4)

◆ computeGeoJacobian() [4/6]

yarp::sig::Matrix iCub::iDyn::RigidBodyTransformation::computeGeoJacobian ( const unsigned int  iLink,
const yarp::sig::Matrix &  Pn,
const yarp::sig::Matrix &  H0,
bool  rbtRoto = false 
)

This method is used to compute the Jacobian between two links in two different chains.

Parameters
iLinkthe index of the link, in the chain, being the base frame for the Jacobian computation
Pnthe matrix describing the roto-translational matrix between base and end-effector (in two different limbs)
H0the H0 matrix of the base to be used for the Jacobian computation
rbtRotoif false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT
Returns
the Jacobian matrix from the iLink of the chain until the base of the chain (ie from link 4 to 0)

◆ computeGeoJacobian() [5/6]

yarp::sig::Matrix iCub::iDyn::RigidBodyTransformation::computeGeoJacobian ( const yarp::sig::Matrix &  Pn,
bool  rbtRoto = false 
)

This method is used to compute the Jacobian between two links in two different chains: in this case it returns the jacobian matrix of the whole chain (from base to end-effector) when Pn is an external vector.

Parameters
Pnthe matrix describing the roto-translational matrix between base and end-effector (in two different limbs)
rbtRotoif false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT
Returns
the Jacobian matrix of the chain

◆ computeGeoJacobian() [6/6]

yarp::sig::Matrix iCub::iDyn::RigidBodyTransformation::computeGeoJacobian ( const yarp::sig::Matrix &  Pn,
const yarp::sig::Matrix &  H0,
bool  rbtRoto = false 
)

This method is used to compute the Jacobian between two links in two different chains: in this case it returns the jacobian matrix of the whole chain (from base to end-effector) when Pn is an external vector, and H0 is an external matrix.

Parameters
Pnthe matrix describing the roto-translational matrix between base and end-effector (in two different limbs)
H0the H0 matrix of the base to be used for the Jacobian computation
rbtRotoif false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT
Returns
the Jacobian matrix of the chain

◆ computeKinematic()

void RigidBodyTransformation::computeKinematic ( )
protected

Basic computations for applying RBT on kinematic variables.

The computations are similar to the Forward/Backward ones in OneLinkNewtonEuler: compute AngVel/AngAcc/LinAcc. Here they are fastened and adapted to the RBT.

Definition at line 195 of file iDynBody.cpp.

◆ computeLimbKinematic()

void RigidBodyTransformation::computeLimbKinematic ( )

Calls the compute kinematic of the limb.

Definition at line 278 of file iDynBody.cpp.

◆ computeLimbWrench()

void RigidBodyTransformation::computeLimbWrench ( )

Calls the compute wrench of the limb.

Definition at line 283 of file iDynBody.cpp.

◆ computeWrench()

void RigidBodyTransformation::computeWrench ( )
protected

Basic computations for applying RBT on wrench variables.

The computations are similar to the Forward/Backward ones in OneLinkNewtonEuler: compute Force/Moment. Here they are fastened and adapted to the RBT.

Definition at line 246 of file iDynBody.cpp.

◆ getDOF()

unsigned int RigidBodyTransformation::getDOF ( ) const

Return the number of DOF of the limb (DOF <= N)

Returns
the number of DOF in the limb

Definition at line 293 of file iDynBody.cpp.

◆ getEndEffPose()

Vector RigidBodyTransformation::getEndEffPose ( const bool  axisRep = true)

Return the end-effector pose: x-y-z Cartesian position and 3/4 angles of orientation.

Parameters
axisRepa flag for the axis representation
Returns
the end effector pose

Definition at line 308 of file iDynBody.cpp.

◆ getH() [1/2]

Matrix RigidBodyTransformation::getH ( )

Return the end-effector roto-translational matrix of the end-effector H of the end-effector.

Definition at line 303 of file iDynBody.cpp.

◆ getH() [2/2]

Matrix RigidBodyTransformation::getH ( const unsigned int  i,
const bool  allLink = false 
)

Return the i-th roto-translational matrix of the chain.

This method basically calls iKinChain::getH(i,allLink). the boolean allLink specifies if all the links are considered, or only the unblocked ones (DOF)

Parameters
ithe link index in the chain (0<=i<N)
allLinkif all the links are considered
Returns
H of the i-th link

Definition at line 298 of file iDynBody.cpp.

◆ getH0()

Matrix RigidBodyTransformation::getH0 ( ) const

Return the H0 matrix of the limb attached to the RBT.

Returns
the H0 matrix of the limb attached to the RBT

Definition at line 361 of file iDynBody.cpp.

◆ getHCOM()

Matrix RigidBodyTransformation::getHCOM ( unsigned int  iLink)

Returns the COM matrix of the selected link (index = iLink) in the chain.

Parameters
iLinkthe index of the link, in the chain
Returns
the roto-translational matrix of the selected link COM

Definition at line 401 of file iDynBody.cpp.

◆ getKinematic()

void RigidBodyTransformation::getKinematic ( yarp::sig::Vector &  wNode,
yarp::sig::Vector &  dwNode,
yarp::sig::Vector &  ddpNode 
)

Get the kinematic variables (w,dw,ddp) of the limb, applies the RBT transformation and compute the kinematic variables of the node.

The variables are stored into the param vectors, which are accessible. This method calls getKinematicNewtonEuler() in the limb, and the limb itself knows whether to get this information in the base or in the end- effector, depending on its iteration mode for kinematics. This method is used by iDynNode to connect two or multiple limbs.

Parameters
wNodethe angular velocity of the Node - it is modified!
dwNodethe angular acceleration of the Node - it is modified!
ddpNodethe linear acceleration of the Node - it is modified!

Definition at line 152 of file iDynBody.cpp.

◆ getKinematicFlow()

FlowType RigidBodyTransformation::getKinematicFlow ( ) const

Return the kinematic flow type.

Returns
the kinematic flow

Definition at line 185 of file iDynBody.cpp.

◆ getNLinks()

unsigned int RigidBodyTransformation::getNLinks ( ) const

Return the number of links of the limb (N)

Returns
the number of links in the limb

Definition at line 288 of file iDynBody.cpp.

◆ getR()

Matrix RigidBodyTransformation::getR ( )
protected

Return the rotational 3x3 matrix of the RBT.

Returns
the rotational matrix of the RBT

Definition at line 126 of file iDynBody.cpp.

◆ getr()

Vector RigidBodyTransformation::getr ( bool  proj = false)
protected

Return the translational part of the RBT matrix.

Parameters
proj=true/false
Returns
the distance vector of the RBT

Definition at line 145 of file iDynBody.cpp.

◆ getR6()

Matrix RigidBodyTransformation::getR6 ( ) const

Return a 6x6 diagonal matrix with the rotational matrix of the RBT.

Returns
a 6x6 diagonal matrix with the rotational matrix of the RBT

Definition at line 131 of file iDynBody.cpp.

◆ getRBT()

Matrix RigidBodyTransformation::getRBT ( ) const

Return the the (4x4) roto-translational matrix defining the rigid body transformation.

Returns
H, the 4x4 matrix of the RBT

Definition at line 121 of file iDynBody.cpp.

◆ getWrench()

void RigidBodyTransformation::getWrench ( yarp::sig::Vector &  FNode,
yarp::sig::Vector &  MuNode 
)

Get the wrench variables (F,Mu) of the limb, transform it according to the RBT and add it to the node wrench.

The variables are stored into the param vectors, which are accessible. This method calls getWrenchNewtonEuler() in the limb, and the limb itself knows whether to get this information in the base ot in the end-effector, depending on its iteration mode for wrenches. This method is used by iDynNode to connect two or multiple limbs.

Parameters
FNodethe iDynNode force - it is modified!
MuNodethe iDynNode moment - it is modified!

Definition at line 166 of file iDynBody.cpp.

◆ getWrenchFlow()

FlowType RigidBodyTransformation::getWrenchFlow ( ) const

return the wrench flow type

Returns
the wrench flow

Definition at line 190 of file iDynBody.cpp.

◆ isSensorized()

bool RigidBodyTransformation::isSensorized ( ) const

Return a boolean, depending if the limb attached to the RBT has a FT sensor or not.

Returns
true if the limb has a FT sensor, false otherwise

Definition at line 273 of file iDynBody.cpp.

◆ setH0()

bool RigidBodyTransformation::setH0 ( const yarp::sig::Matrix &  _H0)

Set a new H0 matrix in the limb attached to the RBT.

Parameters
_H0the new H0 matrix of the limb attached to the RBT
Returns
true if succeed, false otherwise

Definition at line 366 of file iDynBody.cpp.

◆ setInfoFlow()

void RigidBodyTransformation::setInfoFlow ( const FlowType  kin,
const FlowType  wre 
)

Set the flow of kinematic/wrench information: input to node or output from node.

Parameters
kinthe kinematic flow
wrethe wrench flow

Definition at line 179 of file iDynBody.cpp.

◆ setKinematic()

bool RigidBodyTransformation::setKinematic ( const yarp::sig::Vector &  w0,
const yarp::sig::Vector &  dw0,
const yarp::sig::Vector &  ddp0 
)

Set the kinematic variables (w,dw,ddp) of the limb.

This method calls initKinematicNewtonEuler() in the limb, and the limb itself knows whether to set this information in the base or in the end- effector, depending on its iteration mode for kinematics. This method is used by iDynNode to connect two or multiple limbs.

Parameters
w0the angular velocity
dw0the angular acceleration
ddp0the linear acceleration
Returns
true if succeeds, false otherwise

Definition at line 83 of file iDynBody.cpp.

◆ setKinematicMeasure()

bool RigidBodyTransformation::setKinematicMeasure ( const yarp::sig::Vector &  w0,
const yarp::sig::Vector &  dw0,
const yarp::sig::Vector &  ddp0 
)

Set the kinematic variables (w,dw,ddp) of the limb, coming from external measurements (ie a sensor).

This method calls initKinematicNewtonEuler() in the limb, and the limb itself knows whether to set this information in the base or in the end- effector, depending on its iteration mode for kinematics. This method is used by iDynNode to connect two or multiple limbs.

Parameters
w0the angular velocity
dw0the angular acceleration
ddp0the linear acceleration
Returns
true if succeeds, false otherwise

Definition at line 95 of file iDynBody.cpp.

◆ setRBT()

bool RigidBodyTransformation::setRBT ( const yarp::sig::Matrix &  _H)

Set the roto-translational matrix between the limb and the node, defining the rigid body transformation.

Parameters
_Ha (4x4) roto-translational matrix
Returns
true if succeeds, false otherwise

Definition at line 67 of file iDynBody.cpp.

◆ setWrench()

bool RigidBodyTransformation::setWrench ( const yarp::sig::Vector &  F0,
const yarp::sig::Vector &  Mu0 
)

Set the wrench variables (F,Mu) of the limb.

This method calls initWrenchNewtonEuler() in the limb, and the limb itself knows whether to set this information in the base ot in the end-effector, depending on its iteration mode for wrenches. This method is used by iDynNode to connect two or multiple limbs.

Parameters
F0the force
Mu0the moment
Returns
true if succeeds, false otherwise

Definition at line 100 of file iDynBody.cpp.

◆ setWrenchMeasure() [1/2]

bool iCub::iDyn::RigidBodyTransformation::setWrenchMeasure ( const yarp::sig::Vector &  F0,
const yarp::sig::Vector &  Mu0 
)

Set the wrench variables (F,Mu) of the limb.

This method calls initWrenchNewtonEuler() in the limb, and the limb itself knows whether to set this information in the base ot in the end-effector, depending on its iteration mode for wrenches. This method is used by iDynNode to connect two or multiple limbs.

Parameters
F0the force
Mu0the moment
Returns
true if succeeds, false otherwise

◆ setWrenchMeasure() [2/2]

bool iCub::iDyn::RigidBodyTransformation::setWrenchMeasure ( iDyn::iDynSensor sensor,
const yarp::sig::Vector &  Fsens,
const yarp::sig::Vector &  Musens 
)

Set the wrench variables in the sensor.

Parameters
sensorthe sensor attached to the limb
Fsensthe force
Musensthe moment
Returns
true if succeeds, false otherwise

◆ TESTING_computeCOMJacobian() [1/3]

Matrix RigidBodyTransformation::TESTING_computeCOMJacobian ( const unsigned int  iLink,
bool  rbtRoto = false 
)

Returns the Jacobian matrix of the COM of the selected link (index = iLink) in the chain.

Parameters
iLinkthe index of the link, in the chain
rbtRotoif false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT
Returns
the Jacobian matrix of the selected link COM

Definition at line 377 of file iDynBody.cpp.

◆ TESTING_computeCOMJacobian() [2/3]

yarp::sig::Matrix iCub::iDyn::RigidBodyTransformation::TESTING_computeCOMJacobian ( const unsigned int  iLink,
const yarp::sig::Matrix &  Pn,
bool  rbtRoto = false 
)

Returns the Jacobian matrix of the COM of the selected link (index = iLink) in the chain: in this case Pn is an external vector, that happens when multiple limbs are connected.

Parameters
Pnthe matrix describing the roto-translational matrix between base and end-effector (in two different limbs)
iLinkthe index of the link, in the chain
rbtRotoif false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT
Returns
the Jacobian matrix of the selected link COM

◆ TESTING_computeCOMJacobian() [3/3]

yarp::sig::Matrix iCub::iDyn::RigidBodyTransformation::TESTING_computeCOMJacobian ( const unsigned int  iLink,
const yarp::sig::Matrix &  Pn,
const yarp::sig::Matrix &  _H0,
bool  rbtRoto = false 
)

Returns the Jacobian matrix of the COM of the selected link (index = iLink) in the chain: in this case Pn is an external vector, that happens when multiple limbs are connected.

The H0 matrix used to initialize the Jacobian computation is external too.

Parameters
Pnthe matrix describing the roto-translational matrix between base and end-effector (in two different limbs)
H0the H0 matrix of the base to be used for the Jacobian computation
iLinkthe index of the link, in the chain
rbtRotoif false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT
Returns
the Jacobian matrix of the selected link COM

◆ toString()

std::string iCub::iDyn::RigidBodyTransformation::toString ( ) const

Return some information.

Returns
a string with information

Member Data Documentation

◆ ddp

yarp::sig::Vector iCub::iDyn::RigidBodyTransformation::ddp
protected

linear acceleration

Definition at line 167 of file iDynBody.h.

◆ dw

yarp::sig::Vector iCub::iDyn::RigidBodyTransformation::dw
protected

angular acceleration

Definition at line 165 of file iDynBody.h.

◆ F

yarp::sig::Vector iCub::iDyn::RigidBodyTransformation::F
protected

force

Definition at line 169 of file iDynBody.h.

◆ H

yarp::sig::Matrix iCub::iDyn::RigidBodyTransformation::H
protected

the roto-translation between the limb and the node

Definition at line 145 of file iDynBody.h.

◆ hasSensor

bool iCub::iDyn::RigidBodyTransformation::hasSensor
protected

flag for sensor or not - only used for setWrenchMeasures()

Definition at line 157 of file iDynBody.h.

◆ info

std::string iCub::iDyn::RigidBodyTransformation::info
protected

info or useful notes

Definition at line 151 of file iDynBody.h.

◆ kinFlow

FlowType iCub::iDyn::RigidBodyTransformation::kinFlow
protected

kinematic flow: in-to/out-from node (RBT_NODE_IN/RBT_NODE_OUT)

Definition at line 139 of file iDynBody.h.

◆ limb

iDyn::iDynLimb* iCub::iDyn::RigidBodyTransformation::limb
protected

the limb attached to the RigidBodyTransformation

Definition at line 136 of file iDynBody.h.

◆ mode

NewEulMode iCub::iDyn::RigidBodyTransformation::mode
protected

STATIC/DYNAMIC/DYNAMIC_W_ROTOR/DYNAMIC_CORIOLIS_GRAVITY.

Definition at line 148 of file iDynBody.h.

◆ Mu

yarp::sig::Vector iCub::iDyn::RigidBodyTransformation::Mu
protected

moment

Definition at line 171 of file iDynBody.h.

◆ verbose

unsigned int iCub::iDyn::RigidBodyTransformation::verbose
protected

verbosity flag

Definition at line 154 of file iDynBody.h.

◆ w

yarp::sig::Vector iCub::iDyn::RigidBodyTransformation::w
protected

angular velocity

Definition at line 163 of file iDynBody.h.

◆ wreFlow

FlowType iCub::iDyn::RigidBodyTransformation::wreFlow
protected

wrench flow: in-to/out-from node (RBT_NODE_IN/RBT_NODE_OUT)

Definition at line 142 of file iDynBody.h.


The documentation for this class was generated from the following files: