iCub-main
|
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. | |
~RigidBodyTransformation () | |
Destructor. | |
bool | setRBT (const yarp::sig::Matrix &_H) |
Set the roto-translational matrix between the limb and the node, defining the rigid body transformation. | |
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. | |
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). | |
bool | setWrench (const yarp::sig::Vector &F0, const yarp::sig::Vector &Mu0) |
Set the wrench variables (F,Mu) of the limb. | |
bool | setWrenchMeasure (const yarp::sig::Vector &F0, const yarp::sig::Vector &Mu0) |
Set the wrench variables (F,Mu) of the limb. | |
bool | setWrenchMeasure (iDyn::iDynSensor *sensor, const yarp::sig::Vector &Fsens, const yarp::sig::Vector &Musens) |
Set the wrench variables in the sensor. | |
yarp::sig::Matrix | getRBT () const |
Return the the (4x4) roto-translational matrix defining the rigid body transformation. | |
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. | |
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. | |
void | setInfoFlow (const FlowType kin, const FlowType wre) |
Set the flow of kinematic/wrench information: input to node or output from node. | |
FlowType | getKinematicFlow () const |
Return the kinematic flow type. | |
FlowType | getWrenchFlow () const |
return the wrench flow type | |
std::string | toString () const |
Return some information. | |
bool | isSensorized () const |
Return a boolean, depending if the limb attached to the RBT has a FT sensor or not. | |
void | computeLimbKinematic () |
Calls the compute kinematic of the limb. | |
void | computeLimbWrench () |
Calls the compute wrench of the limb. | |
unsigned int | getNLinks () const |
Return the number of links of the limb (N) | |
unsigned int | getDOF () const |
Return the number of DOF of the limb (DOF <= N) | |
yarp::sig::Matrix | getH (const unsigned int i, const bool allLink=false) |
Return the i-th roto-translational matrix of the chain. | |
yarp::sig::Matrix | getH () |
Return the end-effector roto-translational matrix of the end-effector H of the end-effector. | |
yarp::sig::Vector | getEndEffPose (const bool axisRep=true) |
Return the end-effector pose: x-y-z Cartesian position and 3/4 angles of orientation. | |
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. | |
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. | |
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. | |
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. | |
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. | |
yarp::sig::Matrix | getR6 () const |
Return a 6x6 diagonal matrix with the rotational matrix of the RBT. | |
yarp::sig::Matrix | getH0 () const |
Return the H0 matrix of the limb attached to the RBT. | |
bool | setH0 (const yarp::sig::Matrix &_H0) |
Set a new H0 matrix in the limb attached to the RBT. | |
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. | |
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. | |
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. | |
yarp::sig::Matrix | getHCOM (unsigned int iLink) |
Returns the COM matrix of the selected link (index = iLink) in the chain. | |
Protected Member Functions | |
yarp::sig::Matrix | getR () |
Return the rotational 3x3 matrix of the RBT. | |
yarp::sig::Vector | getr (bool proj=false) |
Return the translational part of the RBT matrix. | |
void | computeKinematic () |
Basic computations for applying RBT on kinematic variables. | |
void | computeWrench () |
Basic computations for applying RBT on wrench variables. | |
Protected Attributes | |
iDyn::iDynLimb * | limb |
the limb attached to the RigidBodyTransformation | |
FlowType | kinFlow |
kinematic flow: in-to/out-from node (RBT_NODE_IN/RBT_NODE_OUT) | |
FlowType | wreFlow |
wrench flow: in-to/out-from node (RBT_NODE_IN/RBT_NODE_OUT) | |
yarp::sig::Matrix | H |
the roto-translation between the limb and the node | |
NewEulMode | mode |
STATIC/DYNAMIC/DYNAMIC_W_ROTOR/DYNAMIC_CORIOLIS_GRAVITY. | |
std::string | info |
info or useful notes | |
unsigned int | verbose |
verbosity flag | |
bool | hasSensor |
flag for sensor or not - only used for setWrenchMeasures() | |
yarp::sig::Vector | w |
angular velocity | |
yarp::sig::Vector | dw |
angular acceleration | |
yarp::sig::Vector | ddp |
linear acceleration | |
yarp::sig::Vector | F |
force | |
yarp::sig::Vector | Mu |
moment | |
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.
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.
_limb | pointer to a iDynLimb |
_H | a (4x4) roto-translational matrix defining the rigid body transformation |
_info | a string with information |
kin | the kinematic flow |
wre | the wrench flow |
_mode | the NewEulMode for computations |
verb | verbosity flag |
Definition at line 44 of file iDynBody.cpp.
RigidBodyTransformation::~RigidBodyTransformation | ( | ) |
Destructor.
Definition at line 61 of file iDynBody.cpp.
Matrix RigidBodyTransformation::computeGeoJacobian | ( | bool | rbtRoto = false | ) |
rbtRoto | if false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT |
Definition at line 345 of file iDynBody.cpp.
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.
iLink | the index of the link, in the chain |
rbtRoto | if false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT |
Definition at line 353 of file iDynBody.cpp.
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.
iLink | the index of the link, in the chain, being the base frame for the Jacobian computation |
Pn | the matrix describing the roto-translational matrix between base and end-effector (in two different limbs) |
rbtRoto | if false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT |
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.
iLink | the index of the link, in the chain, being the base frame for the Jacobian computation |
Pn | the matrix describing the roto-translational matrix between base and end-effector (in two different limbs) |
H0 | the H0 matrix of the base to be used for the Jacobian computation |
rbtRoto | if false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT |
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.
Pn | the matrix describing the roto-translational matrix between base and end-effector (in two different limbs) |
rbtRoto | if false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT |
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.
Pn | the matrix describing the roto-translational matrix between base and end-effector (in two different limbs) |
H0 | the H0 matrix of the base to be used for the Jacobian computation |
rbtRoto | if false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT |
|
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.
void RigidBodyTransformation::computeLimbKinematic | ( | ) |
Calls the compute kinematic of the limb.
Definition at line 278 of file iDynBody.cpp.
void RigidBodyTransformation::computeLimbWrench | ( | ) |
Calls the compute wrench of the limb.
Definition at line 283 of file iDynBody.cpp.
|
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.
unsigned int RigidBodyTransformation::getDOF | ( | ) | const |
Return the number of DOF of the limb (DOF <= N)
Definition at line 293 of file iDynBody.cpp.
Vector RigidBodyTransformation::getEndEffPose | ( | const bool | axisRep = true | ) |
Return the end-effector pose: x-y-z Cartesian position and 3/4 angles of orientation.
axisRep | a flag for the axis representation |
Definition at line 308 of file iDynBody.cpp.
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.
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)
i | the link index in the chain (0<=i<N) |
allLink | if all the links are considered |
Definition at line 298 of file iDynBody.cpp.
Matrix RigidBodyTransformation::getH0 | ( | ) | const |
Return the H0 matrix of the limb attached to the RBT.
Definition at line 361 of file iDynBody.cpp.
Matrix RigidBodyTransformation::getHCOM | ( | unsigned int | iLink | ) |
Returns the COM matrix of the selected link (index = iLink) in the chain.
iLink | the index of the link, in the chain |
Definition at line 401 of file iDynBody.cpp.
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.
wNode | the angular velocity of the Node - it is modified! |
dwNode | the angular acceleration of the Node - it is modified! |
ddpNode | the linear acceleration of the Node - it is modified! |
Definition at line 152 of file iDynBody.cpp.
FlowType RigidBodyTransformation::getKinematicFlow | ( | ) | const |
Return the kinematic flow type.
Definition at line 185 of file iDynBody.cpp.
unsigned int RigidBodyTransformation::getNLinks | ( | ) | const |
Return the number of links of the limb (N)
Definition at line 288 of file iDynBody.cpp.
|
protected |
Return the rotational 3x3 matrix of the RBT.
Definition at line 126 of file iDynBody.cpp.
|
protected |
Return the translational part of the RBT matrix.
proj=true/false |
Definition at line 145 of file iDynBody.cpp.
Matrix RigidBodyTransformation::getR6 | ( | ) | const |
Return a 6x6 diagonal matrix with the rotational matrix of the RBT.
Definition at line 131 of file iDynBody.cpp.
Matrix RigidBodyTransformation::getRBT | ( | ) | const |
Return the the (4x4) roto-translational matrix defining the rigid body transformation.
Definition at line 121 of file iDynBody.cpp.
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.
Definition at line 166 of file iDynBody.cpp.
FlowType RigidBodyTransformation::getWrenchFlow | ( | ) | const |
bool RigidBodyTransformation::isSensorized | ( | ) | const |
Return a boolean, depending if the limb attached to the RBT has a FT sensor or not.
Definition at line 273 of file iDynBody.cpp.
bool RigidBodyTransformation::setH0 | ( | const yarp::sig::Matrix & | _H0 | ) |
Set a new H0 matrix in the limb attached to the RBT.
_H0 | the new H0 matrix of the limb attached to the RBT |
Definition at line 366 of file iDynBody.cpp.
Set the flow of kinematic/wrench information: input to node or output from node.
kin | the kinematic flow |
wre | the wrench flow |
Definition at line 179 of file iDynBody.cpp.
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.
w0 | the angular velocity |
dw0 | the angular acceleration |
ddp0 | the linear acceleration |
Definition at line 83 of file iDynBody.cpp.
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.
w0 | the angular velocity |
dw0 | the angular acceleration |
ddp0 | the linear acceleration |
Definition at line 95 of file iDynBody.cpp.
bool RigidBodyTransformation::setRBT | ( | const yarp::sig::Matrix & | _H | ) |
Set the roto-translational matrix between the limb and the node, defining the rigid body transformation.
_H | a (4x4) roto-translational matrix |
Definition at line 67 of file iDynBody.cpp.
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.
F0 | the force |
Mu0 | the moment |
Definition at line 100 of file iDynBody.cpp.
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.
F0 | the force |
Mu0 | the moment |
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.
sensor | the sensor attached to the limb |
Fsens | the force |
Musens | the moment |
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.
iLink | the index of the link, in the chain |
rbtRoto | if false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT |
Definition at line 377 of file iDynBody.cpp.
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.
Pn | the matrix describing the roto-translational matrix between base and end-effector (in two different limbs) |
iLink | the index of the link, in the chain |
rbtRoto | if false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT |
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.
Pn | the matrix describing the roto-translational matrix between base and end-effector (in two different limbs) |
H0 | the H0 matrix of the base to be used for the Jacobian computation |
iLink | the index of the link, in the chain |
rbtRoto | if false, simply return Jacobian; if true return T * Jacobian, where T is a 6x6 diagonal matrix with the rotational part of the RBT |
std::string iCub::iDyn::RigidBodyTransformation::toString | ( | ) | const |
Return some information.
|
protected |
linear acceleration
Definition at line 167 of file iDynBody.h.
|
protected |
angular acceleration
Definition at line 165 of file iDynBody.h.
|
protected |
force
Definition at line 169 of file iDynBody.h.
|
protected |
the roto-translation between the limb and the node
Definition at line 145 of file iDynBody.h.
|
protected |
flag for sensor or not - only used for setWrenchMeasures()
Definition at line 157 of file iDynBody.h.
|
protected |
info or useful notes
Definition at line 151 of file iDynBody.h.
|
protected |
kinematic flow: in-to/out-from node (RBT_NODE_IN/RBT_NODE_OUT)
Definition at line 139 of file iDynBody.h.
|
protected |
the limb attached to the RigidBodyTransformation
Definition at line 136 of file iDynBody.h.
|
protected |
STATIC/DYNAMIC/DYNAMIC_W_ROTOR/DYNAMIC_CORIOLIS_GRAVITY.
Definition at line 148 of file iDynBody.h.
|
protected |
moment
Definition at line 171 of file iDynBody.h.
|
protected |
verbosity flag
Definition at line 154 of file iDynBody.h.
|
protected |
angular velocity
Definition at line 163 of file iDynBody.h.
|
protected |
wrench flow: in-to/out-from node (RBT_NODE_IN/RBT_NODE_OUT)
Definition at line 142 of file iDynBody.h.