iCub-main
|
A class for defining the 6-DOF iCub Leg. More...
#include <iDyn.h>
Public Member Functions | |
iCubLegDynV2 () | |
Default constructor. More... | |
iCubLegDynV2 (const std::string &_type, const ChainComputationMode _mode=KINFWD_WREBWD) | |
Constructor. More... | |
iCubLegDynV2 (const iCubLegDyn &leg) | |
Creates a new Leg from an already existing Leg object. More... | |
virtual bool | alignJointsBounds (const std::deque< yarp::dev::IControlLimits * > &lim) |
Alignes the Leg joints bounds with current values set aboard the iCub. More... | |
Public Member Functions inherited from iCub::iDyn::iDynLimb | |
iDynLimb () | |
Default constructor: right arm is default. More... | |
iDynLimb (const std::string &_type) | |
Constructor. More... | |
iDynLimb (const iDynLimb &limb) | |
Creates a new Limb from an already existing Limb object. More... | |
iDynLimb (const yarp::os::Property &option) | |
Creates a new Limb from a list of properties wherein links parameters are specified. More... | |
bool | fromLinksProperties (const yarp::os::Property &option) |
Initializes the Limb from a list of properties wherein links parameters are specified. More... | |
bool | isValid () |
Checks if the limb has been properly configured. More... | |
iDynLimb & | operator= (const iDynLimb &limb) |
Copies a Limb object into the current one. More... | |
iDynChain * | asChain () |
Returns a pointer to the Limb seen as Chain object. More... | |
std::string | getType () |
Returns the Limb type as a string. More... | |
virtual | ~iDynLimb () |
Destructor. More... | |
Public Member Functions inherited from iCub::iDyn::iDynChain | |
iDynChain () | |
Default constructor. More... | |
iDynChain (const iDynChain &c) | |
Creates a new Chain from an already existing Chain object. More... | |
iDynChain & | operator= (const iDynChain &c) |
Copies a Chain object into the current one. More... | |
yarp::sig::Vector | setAng (const yarp::sig::Vector &q) |
Sets the free joint angles to values of q[i]. More... | |
yarp::sig::Vector | setDAng (const yarp::sig::Vector &dq) |
Sets the free joint angles velocity to values of dq[i]. More... | |
yarp::sig::Vector | setD2Ang (const yarp::sig::Vector &ddq) |
Sets the free joint angles acceleration to values of ddq[i]. More... | |
yarp::sig::Vector | getDAng () |
Returns the current free joint angles velocity. More... | |
yarp::sig::Vector | getD2Ang () |
Returns the current free joint angles acceleration. More... | |
yarp::sig::Vector | getJointBoundMin () |
Returns a list containing the min value for each joint. More... | |
yarp::sig::Vector | getJointBoundMax () |
Returns a list containing the max value for each joint. More... | |
double | setAng (const unsigned int i, double q) |
Sets the ith joint angle. More... | |
double | setDAng (const unsigned int i, double dq) |
Sets the ith joint angle velocity. More... | |
double | setD2Ang (const unsigned int i, double ddq) |
Sets the ith joint angle acceleration. More... | |
double | getDAng (const unsigned int i) |
Returns the current angle velocity of ith joint. More... | |
double | getD2Ang (const unsigned int i) |
Returns the current angle acceleration of ith joint. More... | |
yarp::sig::Vector | getMasses () const |
Returns the link masses as a vector. More... | |
bool | setMasses (yarp::sig::Vector _m) |
Set the link masses at once. More... | |
double | getMass (const unsigned int i) const |
Returns the i-th link mass. More... | |
bool | setMass (const unsigned int i, const double _m) |
Set the i-th link mass. More... | |
yarp::sig::Matrix | getInertia (const unsigned int i) const |
Returns the i-th link inertia matrix. More... | |
yarp::sig::Matrix | getForces () const |
Returns the links forces as a matrix, where the i-th col is the i-th force. More... | |
yarp::sig::Matrix | getMoments () const |
Returns the links moments as a matrix, where the i-th col is the i-th moment. More... | |
yarp::sig::Vector | getTorques () const |
Returns the links torque as a vector. More... | |
const yarp::sig::Vector & | getForce (const unsigned int iLink) const |
Returns the i-th link force. More... | |
const yarp::sig::Vector & | getMoment (const unsigned int iLink) const |
Returns the i-th link moment. More... | |
double | getTorque (const unsigned int iLink) const |
Returns the i-th link torque. More... | |
yarp::sig::Vector | getLinVel (const unsigned int i) const |
Returns the i-th link linear velocity. More... | |
yarp::sig::Vector | getLinVelCOM (const unsigned int i) const |
Returns the i-th link linear velocity of the COM. More... | |
yarp::sig::Vector | getLinAcc (const unsigned int i) const |
Returns the i-th link linear acceleration. More... | |
const yarp::sig::Vector & | getLinAccCOM (const unsigned int i) const |
Returns the i-th link linear acceleration of the COM. More... | |
yarp::sig::Vector | getAngVel (const unsigned int i) const |
Returns the i-th link angular velocity. More... | |
yarp::sig::Vector | getAngAcc (const unsigned int i) const |
Returns the i-th link angular acceleration. More... | |
bool | setDynamicParameters (const unsigned int i, const double _m, const yarp::sig::Matrix &_HC, const yarp::sig::Matrix &_I, const double _kr, const double _Fv, const double _Fs, const double _Im) |
Set the dynamic parameters of the i-th Link with motor. More... | |
bool | setDynamicParameters (const unsigned int i, const double _m, const yarp::sig::Matrix &_HC, const yarp::sig::Matrix &_I) |
Set the dynamic parameters of the i-th Link. More... | |
bool | setStaticParameters (const unsigned int i, const double _m, const yarp::sig::Matrix &_HC) |
Set the dynamic parameters of the i-th Link if the chain is in a static situation (inertia is null). More... | |
void | prepareNewtonEuler (const NewEulMode NewEulMode_s=DYNAMIC) |
Prepare for the Newton-Euler recursive computation of forces and torques. More... | |
bool | computeNewtonEuler (const yarp::sig::Vector &w0, const yarp::sig::Vector &dw0, const yarp::sig::Vector &ddp0, const yarp::sig::Vector &Fend, const yarp::sig::Vector &Muend) |
Compute forces and torques with the Newton-Euler recursive algorithm: forward and backward phase are performed, and results are stored in the links; to get resulting forces and torques, one can call getForces() and getMoments() methods. More... | |
bool | computeNewtonEuler () |
Compute forces and torques with the Newton-Euler recursive algorithm: forward and backward phase are performed, and results are stored in the links; to get resulting forces and torques, one can call getForces() and getMoments() methods; before calling this method, initNewtonEuler() must be called. More... | |
bool | initNewtonEuler (const yarp::sig::Vector &w0, const yarp::sig::Vector &dw0, const yarp::sig::Vector &ddp0, const yarp::sig::Vector &Fend, const yarp::sig::Vector &Muend) |
Initialize the Newton-Euler method by setting the base (virtual link) velocity and accelerations ( w0, dw0 and ddp0 ) and the final (virtual link) forces and moments Fend and Muend. More... | |
bool | initNewtonEuler () |
Initialize the Newton-Euler method by setting the base (virtual link) velocity and accelerations ( w0, dw0 and ddp0 ) and the final (virtual link) forces and moments Fend and Muend all to zero. More... | |
void | setModeNewtonEuler (const NewEulMode NewEulMode_s=DYNAMIC) |
Set the computation mode for Newton-Euler (static/dynamic/etc) More... | |
yarp::sig::Matrix | getForcesNewtonEuler () const |
Returns the links forces as a matrix, where the (i+1)-th col is the i-th force. More... | |
yarp::sig::Matrix | getMomentsNewtonEuler () const |
Returns the links moments as a matrix, where the (i+1)-th col is the i-th moment. More... | |
yarp::sig::Vector | getTorquesNewtonEuler () const |
Returns the links torque as a vector. More... | |
yarp::sig::Vector | getForceMomentEndEff () const |
Returns the end effector force-moment as a single (6x1) vector. More... | |
void | setIterModeKinematic (const ChainIterationMode _iterateMode_kinematics=FORWARD) |
Set the iteration direction during recursive computation of kinematics variables (w,dw,d2p,d2pC). More... | |
void | setIterModeWrench (const ChainIterationMode _iterateMode_wrench=BACKWARD) |
Set the iteration direction during recursive computation of wrench variables (F,Mu,Tau). More... | |
void | setIterMode (const ChainComputationMode mode=KINFWD_WREBWD) |
Set the computation mode during recursive computation of kinematics (w,dw,d2p,d2pC) and wrench variables(F,Mu,Tau). More... | |
ChainIterationMode | getIterModeKinematic () const |
Get the iteration direction during recursive computation of kinematics variables (w,dw,d2p,d2pC). More... | |
ChainIterationMode | getIterModeWrench () const |
Get the iteration direction during recursive computation of wrench variables (F,Mu,Tau). More... | |
void | computeKinematicNewtonEuler () |
Calls the proper method to compute kinematics variables: either ForwardKinematicFromBase() or BackwardKinematicFromEnd(). More... | |
void | computeWrenchNewtonEuler () |
Calls the proper method to compute wrench variables: either BackwardWrenchFromEnd() or ForwardWrenchFromBase(). More... | |
bool | initKinematicNewtonEuler (const yarp::sig::Vector &w0, const yarp::sig::Vector &dw0, const yarp::sig::Vector &ddp0) |
Calls the proper method to set kinematics variables in OneChainNewtonEuler: either initKinematicBase() or initKinematicEnd(). More... | |
bool | initWrenchNewtonEuler (const yarp::sig::Vector &Fend, const yarp::sig::Vector &Muend) |
Calls the proper method to set wrench variables in OneChainNewtonEuler: either initKinematicBase() or initKinematicEnd(). More... | |
void | getKinematicNewtonEuler (yarp::sig::Vector &w, yarp::sig::Vector &dw, yarp::sig::Vector &ddp) |
Calls the proper method to get kinematics variables in OneChainNewtonEuler either in the base or in the final link. More... | |
void | getFrameKinematic (unsigned int i, yarp::sig::Vector &w, yarp::sig::Vector &dw, yarp::sig::Vector &ddp) |
Get the kinematic information of the i-th frame in the OneChainNewtonEuler associated to the current iDynChain, i.e. More... | |
void | getFrameWrench (unsigned int i, yarp::sig::Vector &F, yarp::sig::Vector &Mu) |
Get the wrench information of the i-th frame in the OneChainNewtonEuler associated to the current iDynChain, i.e. More... | |
void | getWrenchNewtonEuler (yarp::sig::Vector &F, yarp::sig::Vector &Mu) |
Calls the proper method to get wrench variables in OneChainNewtonEuler either in the base or in the final link. More... | |
virtual | ~iDynChain () |
Destructor. More... | |
yarp::sig::Matrix | computeGeoJacobian (const unsigned int iLinkN, const yarp::sig::Matrix &Pn) |
Compute the Jacobian from link 0 to iLinkN. More... | |
yarp::sig::Matrix | computeGeoJacobian (const unsigned int iLinkN, const yarp::sig::Matrix &Pn, const yarp::sig::Matrix &_H0) |
Compute the Jacobian from link 0 to iLinkN. More... | |
yarp::sig::Matrix | computeGeoJacobian (const yarp::sig::Matrix &Pn) |
Compute the Jacobian of the chain, from link 0 to N. More... | |
yarp::sig::Matrix | computeGeoJacobian (const yarp::sig::Matrix &Pn, const yarp::sig::Matrix &_H0) |
Compute the Jacobian of the chain, from link 0 to N. More... | |
yarp::sig::Matrix | getDenHart (unsigned int i) |
Return the Denavit-Hartenberg matrix of the i-th link in the chain. More... | |
yarp::sig::Matrix | TESTING_computeCOMJacobian (const unsigned int iLink) |
Compute the Jacobian of the COM of link indexed iLink. More... | |
yarp::sig::Matrix | TESTING_computeCOMJacobian (const unsigned int iLink, const yarp::sig::Matrix &Pn) |
Compute the Jacobian of the COM of link iLink (considering chain 0-iLink). More... | |
yarp::sig::Matrix | TESTING_computeCOMJacobian (const unsigned int iLink, const yarp::sig::Matrix &Pn, const yarp::sig::Matrix &_H0) |
Compute the Jacobian of the COM of link iLink (considering chain 0-iLink). More... | |
yarp::sig::Matrix | getCOM (unsigned int iLink) |
Return the COM matrix of the i-th link. More... | |
yarp::sig::Matrix | getHCOM (unsigned int iLink) |
Return the H matrix until the COM of the i-th link. More... | |
yarp::sig::Matrix | computeMassMatrix () |
Compute the joint space mass matrix considering only the active joints. More... | |
yarp::sig::Matrix | computeMassMatrix (const yarp::sig::Vector &q) |
Compute the joint space mass matrix considering only the active joints. More... | |
yarp::sig::Vector | computeCcTorques () |
Compute the torques due to centrifugal and coriolis effects considering only the active joints. More... | |
yarp::sig::Vector | computeCcTorques (const yarp::sig::Vector &q, const yarp::sig::Vector &dq) |
Compute the torques due to centrifugal and coriolis effects considering only the active joints. More... | |
yarp::sig::Vector | computeGravityTorques (const yarp::sig::Vector &ddp0) |
Compute the torques generated by gravity considering only the active joints. More... | |
yarp::sig::Vector | computeGravityTorques (const yarp::sig::Vector &ddp0, const yarp::sig::Vector &q) |
Compute the torques generated by gravity considering only the active joints. More... | |
yarp::sig::Vector | computeCcGravityTorques (const yarp::sig::Vector &ddp0) |
Compute the torques generated by gravity and centrifugal and coriolis forces, considering only the active joints. More... | |
yarp::sig::Vector | computeCcGravityTorques (const yarp::sig::Vector &ddp0, const yarp::sig::Vector &q, const yarp::sig::Vector &dq) |
Compute the torques generated by gravity and centrifugal and coriolis forces, considering only the active joints. More... | |
Public Member Functions inherited from iCub::iKin::iKinChain | |
iKinChain () | |
Default constructor. More... | |
iKinChain (const iKinChain &c) | |
Creates a new Chain from an already existing Chain object. More... | |
iKinChain & | operator= (const iKinChain &c) |
Copies a Chain object into the current one. More... | |
iKinChain & | operator<< (iKinLink &l) |
Adds a Link at the bottom of the Chain. More... | |
iKinChain & | operator-- (int) |
Removes a Link from the bottom of the Chain. More... | |
iKinLink & | operator[] (const unsigned int i) |
Returns a reference to the ith Link of the Chain. More... | |
iKinLink & | operator() (const unsigned int i) |
Returns a reference to the ith Link of the Chain considering only those Links related to DOF. More... | |
bool | addLink (const unsigned int i, iKinLink &l) |
Adds a Link at the position ith within the Chain. More... | |
bool | rmLink (const unsigned int i) |
Removes the ith Link from the Chain. More... | |
void | pushLink (iKinLink &l) |
Adds a Link at the bottom of the Chain. More... | |
void | clear () |
Removes all Links. More... | |
void | popLink () |
Removes a Link from the bottom of the Chain. More... | |
bool | blockLink (const unsigned int i, double Ang) |
Blocks the ith Link at the a certain value of its joint angle. More... | |
bool | blockLink (const unsigned int i) |
Blocks the ith Link at the current value of its joint angle. More... | |
bool | setBlockingValue (const unsigned int i, double Ang) |
Changes the value of the ith blocked Link. More... | |
bool | releaseLink (const unsigned int i) |
Releases the ith Link. More... | |
bool | isLinkBlocked (const unsigned int i) |
Queries whether the ith Link is blocked. More... | |
void | setAllConstraints (bool _constrained) |
Sets the constraint status of all chain links. More... | |
void | setConstraint (unsigned int i, bool _constrained) |
Sets the constraint status of ith link. More... | |
bool | getConstraint (unsigned int i) |
Returns the constraint status of ith link. More... | |
void | setAllLinkVerbosity (unsigned int _verbose) |
Sets the verbosity level of all Links belonging to the Chain. More... | |
void | setVerbosity (unsigned int _verbose) |
Sets the verbosity level of the Chain. More... | |
unsigned int | getVerbosity () const |
Returns the current Chain verbosity level. More... | |
unsigned int | getN () const |
Returns the number of Links belonging to the Chain. More... | |
unsigned int | getDOF () const |
Returns the current number of Chain's DOF. More... | |
yarp::sig::Matrix | getH0 () const |
Returns H0, the rigid roto-translation matrix from the root reference frame to the 0th frame. More... | |
bool | setH0 (const yarp::sig::Matrix &_H0) |
Sets H0, the rigid roto-translation matrix from the root reference frame to the 0th frame. More... | |
yarp::sig::Matrix | getHN () const |
Returns HN, the rigid roto-translation matrix from the Nth frame to the end-effector. More... | |
bool | setHN (const yarp::sig::Matrix &_HN) |
Sets HN, the rigid roto-translation matrix from the Nth frame to the end-effector. More... | |
yarp::sig::Vector | setAng (const yarp::sig::Vector &q) |
Sets the free joint angles to values of q[i]. More... | |
yarp::sig::Vector | getAng () |
Returns the current free joint angles values. More... | |
double | setAng (const unsigned int i, double _Ang) |
Sets the ith joint angle. More... | |
double | getAng (const unsigned int i) |
Returns the current angle of ith joint. More... | |
yarp::sig::Matrix | getH (const unsigned int i, const bool allLink=false) |
Returns the rigid roto-translation matrix from the root reference frame to the ith frame in Denavit-Hartenberg notation. More... | |
yarp::sig::Matrix | getH () |
Returns the rigid roto-translation matrix from the root reference frame to the end-effector frame in Denavit-Hartenberg notation (HN is taken into account). More... | |
yarp::sig::Matrix | getH (const yarp::sig::Vector &q) |
Returns the rigid roto-translation matrix from the root reference frame to the end-effector frame in Denavit-Hartenberg notation (HN is taken into account). More... | |
yarp::sig::Vector | Pose (const unsigned int i, const bool axisRep=true) |
Returns the coordinates of ith Link. More... | |
yarp::sig::Vector | Position (const unsigned int i) |
Returns the 3D position coordinates of ith Link. More... | |
yarp::sig::Vector | EndEffPose (const bool axisRep=true) |
Returns the coordinates of end-effector. More... | |
yarp::sig::Vector | EndEffPose (const yarp::sig::Vector &q, const bool axisRep=true) |
Returns the coordinates of end-effector computed in q. More... | |
yarp::sig::Vector | EndEffPosition () |
Returns the 3D coordinates of end-effector position. More... | |
yarp::sig::Vector | EndEffPosition (const yarp::sig::Vector &q) |
Returns the 3D coordinates of end-effector position computed in q. More... | |
yarp::sig::Matrix | AnaJacobian (const unsigned int i, unsigned int col) |
Returns the analitical Jacobian of the ith link. More... | |
yarp::sig::Matrix | AnaJacobian (unsigned int col=3) |
Returns the analitical Jacobian of the end-effector. More... | |
yarp::sig::Matrix | AnaJacobian (const yarp::sig::Vector &q, unsigned int col=3) |
Returns the analitical Jacobian of the end-effector computed in q. More... | |
yarp::sig::Matrix | GeoJacobian (const unsigned int i) |
Returns the geometric Jacobian of the ith link. More... | |
yarp::sig::Matrix | GeoJacobian () |
Returns the geometric Jacobian of the end-effector. More... | |
yarp::sig::Matrix | GeoJacobian (const yarp::sig::Vector &q) |
Returns the geometric Jacobian of the end-effector computed in q. More... | |
yarp::sig::Vector | Hessian_ij (const unsigned int i, const unsigned int j) |
Returns the 6x1 vector \( \partial{^2}F\left(q\right)/\partial q_i \partial q_j, \) where \( F\left(q\right) \) is the forward kinematic function and \( \left(q_i,q_j\right) \) is the DOF couple. More... | |
void | prepareForHessian () |
Prepares computation for a successive call to fastHessian_ij(). More... | |
yarp::sig::Vector | fastHessian_ij (const unsigned int i, const unsigned int j) |
Returns the 6x1 vector \( \partial{^2}F\left(q\right)/\partial q_i \partial q_j, \) where \( F\left(q\right) \) is the forward kinematic function and \( \left(q_i,q_j\right) \) is the DOF couple. More... | |
yarp::sig::Vector | Hessian_ij (const unsigned int lnk, const unsigned int i, const unsigned int j) |
Returns the 6x1 vector \( \partial{^2}F\left(q\right)/\partial q_i \partial q_j, \) where \( F\left(q\right) \) is the forward kinematic function and \( \left(q_i,q_j\right) \) is the couple of links. More... | |
void | prepareForHessian (const unsigned int lnk) |
Prepares computation for a successive call to fastHessian_ij() (link version). More... | |
yarp::sig::Vector | fastHessian_ij (const unsigned int lnk, const unsigned int i, const unsigned int j) |
Returns the 6x1 vector \( \partial{^2}F\left(q\right)/\partial q_i \partial q_j, \) where \( F\left(q\right) \) is the forward kinematic function and \( \left(q_i,q_j\right) \) is the couple of links. More... | |
yarp::sig::Matrix | DJacobian (const yarp::sig::Vector &dq) |
Compute the time derivative of the geometric Jacobian. More... | |
yarp::sig::Matrix | DJacobian (const unsigned int lnk, const yarp::sig::Vector &dq) |
Compute the time derivative of the geometric Jacobian (link version). More... | |
virtual | ~iKinChain () |
Destructor. More... | |
Protected Member Functions | |
virtual void | allocate (const std::string &_type) |
commented by Traversaro, 2 sept 2013 void iCubLegDynV2::allocate(const string &_type) { iDynLimb::allocate(_type); More... | |
Protected Member Functions inherited from iCub::iDyn::iDynLimb | |
virtual void | clone (const iDynLimb &limb) |
virtual void | dispose () |
Dispose. More... | |
iDynChain & | operator= (const iDynChain &c) |
iKin::iKinChain & | operator<< (iKin::iKinLink &l) |
iKin::iKinChain & | operator-- (int) |
iKin::iKinLink & | operator[] (const unsigned int i) |
iKin::iKinLink & | operator() (const unsigned int i) |
bool | addLink (const unsigned int i, iKin::iKinLink &l) |
bool | rmLink (const unsigned int i) |
void | pushLink (iKin::iKinLink &l) |
void | clear () |
void | popLink () |
void | pushLink (iDynLink *pl) |
Protected Member Functions inherited from iCub::iDyn::iDynChain | |
virtual void | clone (const iDynChain &c) |
Clone function. More... | |
virtual void | build () |
Build chains and lists. More... | |
iDynLink * | refLink (const unsigned int i) |
Returns a pointer to the ith iDynLink. More... | |
Protected Member Functions inherited from iCub::iKin::iKinChain | |
virtual void | clone (const iKinChain &c) |
yarp::sig::Vector | RotAng (const yarp::sig::Matrix &R) |
yarp::sig::Vector | dRotAng (const yarp::sig::Matrix &R, const yarp::sig::Matrix &dR) |
yarp::sig::Vector | d2RotAng (const yarp::sig::Matrix &R, const yarp::sig::Matrix &dRi, const yarp::sig::Matrix &dRj, const yarp::sig::Matrix &d2R) |
Additional Inherited Members | |
Protected Attributes inherited from iCub::iDyn::iDynLimb | |
std::deque< iDynLink * > | linkList |
std::string | type |
bool | configured |
Protected Attributes inherited from iCub::iDyn::iDynChain | |
ChainIterationMode | iterateMode_kinematics |
specifies the 'direction' of recursive computation of kinematics variables (w,dw,d2p): FORWARD, BACKWARD More... | |
ChainIterationMode | iterateMode_wrench |
specifies the 'direction' of recursive computation of wrenches (F,Mu): FORWARD, BACKWARD More... | |
yarp::sig::Vector | curr_dq |
q vel More... | |
yarp::sig::Vector | curr_ddq |
q acc More... | |
OneChainNewtonEuler * | NE |
pointer to OneChainNewtonEuler class, to be used for computing forces and torques More... | |
const yarp::sig::Vector | zero0 |
Protected Attributes inherited from iCub::iKin::iKinChain | |
unsigned int | N |
unsigned int | DOF |
unsigned int | verbose |
yarp::sig::Matrix | H0 |
yarp::sig::Matrix | HN |
yarp::sig::Vector | curr_q |
std::deque< iKinLink * > | allList |
std::deque< iKinLink * > | quickList |
std::deque< unsigned int > | hash |
std::deque< unsigned int > | hash_dof |
yarp::sig::Matrix | hess_J |
yarp::sig::Matrix | hess_Jlnk |
iCubLegDynV2::iCubLegDynV2 | ( | const std::string & | _type, |
const ChainComputationMode | _mode = KINFWD_WREBWD |
||
) |
iCubLegDynV2::iCubLegDynV2 | ( | const iCubLegDyn & | leg | ) |
|
virtual |
Alignes the Leg joints bounds with current values set aboard the iCub.
lim | is the ordered list of control interfaces that allows to access the Leg limits. |
Reimplemented from iCub::iDyn::iDynLimb.
|
protectedvirtual |
commented by Traversaro, 2 sept 2013 void iCubLegDynV2::allocate(const string &_type) { iDynLimb::allocate(_type);
Matrix H0(4,4); H0.eye();
setH0(H0);
#ifdef LEGS_NO_WEIGHT if(getType()="right") { create iDynLink from parameters calling pushLink(new iDynLink(mass,HC,I,A,D,alfa,offset,min,max)); m rcx rcy rcZ I1 I2 I3 I4 I5 I6 A D alpha offset
pushLink(new iDynLink(0, 80.4310e-6, -6.91643e-3, 2.30470e-3, 0, 0, 0, 0, 0, 0, 0.0, 0.0, M_PI/2.0, M_PI/2.0, -44.0*CTRL_DEG2RAD, 132.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0, -31.3229e-6, -1.09640e-3, 59.8624e-3, 0, 0, 0, 0, 0, 0, 0.0, M_PI/2.0, M_PI/2.0, -17.0*CTRL_DEG2RAD, 119.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0, 3.1143e-3, 60.0431e-3, -1.3437e-3, 0, 0, 0, 0, 0, 0, -0.0009175, 0.234545, -M_PI/2.0, -M_PI/2.0, -79.0*CTRL_DEG2RAD, 79.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0, 124.3956e-3, -45.0091e-6, -6.2408e-3, 0, 0, 0, 0, 0, 0, -0.2005, 0.0, M_PI, M_PI/2.0, -125.0*CTRL_DEG2RAD, 23.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0, -5.3995e-6, -0.858761e-3, -10.2169e-3, 0, 0, 0, 0, 0, 0, 0.0, 0.0, M_PI/2.0, 0.0, -42.0*CTRL_DEG2RAD, 21.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0, 32.41539-3, 613.9310e-6, 24.0690e-3, 0, 0, 0, 0, 0, 0, -0.0685, 0.0035, M_PI, 0.0, -24.0*CTRL_DEG2RAD, 24.0*CTRL_DEG2RAD));
} else { pushLink(new iDynLink(0, 80.4310e-6, -6.91643e-3, -2.30470e-3, 0, 0, 0, 0, 0, 0, 0.0, 0.0, M_PI/2.0, M_PI/2.0, -44.0*CTRL_DEG2RAD, 132.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0, 31.3229e-6, -1.09640e-3, -59.8624e-3, 0, 0, 0, 0, 0, 0, 0.0, 0.0, M_PI/2.0, M_PI/2.0, -17.0*CTRL_DEG2RAD, 119.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0, 3.1143e-3, 60.0431e-3, 1.3437e-3, 0, 0, 0, 0, 0, 0, -0.0009175, 0.234545, -M_PI/2.0, -M_PI/2.0, -79.0*CTRL_DEG2RAD, 79.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0, 124.3956e-3, -45.0091e-6, 6.2408e-3, 0, 0, 0, 0, 0, 0, -0.2005, 0.0, M_PI, M_PI/2.0, -125.0*CTRL_DEG2RAD, 23.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0, 5.3995e-6, -0.858761e-3, 10.2169e-3, 0, 0, 0, 0, 0, 0, 0.0, 0.0, M_PI/2.0, 0.0, -42.0*CTRL_DEG2RAD, 21.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0, 32.41539-3, -613.9310e-6, 24.0690e-3, 0, 0, 0, 0, 0, 0, -0.0685, 0.0035, M_PI, 0.0, -24.0*CTRL_DEG2RAD, 24.0*CTRL_DEG2RAD));
} #else if(getType()=="right") { create iDynLink from parameters calling pushLink(new iDynLink(mass,HC,I,A,D,alfa,offset,min,max));
pushLink(new iDynLink(0.695, 80.4310e-6, -6.91643e-3, 2.30470e-3, 4470.534e-6, -22.209e-6, -13.9712e-6, 3250.8524e-6, -47.7629e-6, 4904.8747e-6, 0.0, 0.0, M_PI/2.0, M_PI/2.0, -44.0*CTRL_DEG2RAD, 132.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0.982, -31.3229e-6, -1.09640e-3, 59.8624e-3, 27271.4e-6, -1.2116e-6, 11.5713e-6, 25364.6e-6, -491.0806e-6, 4173.9e-6, 0.0, 0.0, M_PI/2.0, M_PI/2.0, -17.0*CTRL_DEG2RAD, 119.0*CTRL_DEG2RAD)); pushLink(new iDynLink(1.522, 3.1143e-3, 60.0431e-3, -1.3437e-3, 45491.7e-6, -940.9711e-6, -53.7405e-6, 10040.0e-6, -1203.0e-6, 45825.5e-6, -0.0009175, 0.234545, -M_PI/2.0, -M_PI/2.0, -79.0*CTRL_DEG2RAD, 79.0*CTRL_DEG2RAD)); pushLink(new iDynLink(2.032, 124.3956e-3, -45.0091e-6, -6.2408e-3, 15455.9e-6, -1390.3e-6, 3945.4e-6, 70277.0e-6, -719.9501e-6, 65964.5e-6, -0.2005, 0.0, M_PI, M_PI/2.0, -125.0*CTRL_DEG2RAD, 23.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0.643, -26.5892e-6, -0.82253e-3, -10.2574e-3, 4765.926e-3, 9.7426e-6, -26.8085e-6, 4093.5e-6, 353.7961e-6, 3668.8e-6, 0.0, 0.0, M_PI/2.0, 0.0, -42.0*CTRL_DEG2RAD, 21.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0.861, 32.41539e-3, 613.9310e-6, 24.0690e-3, 1584.66e-6, 14.357686e-6, 21.079452e-6, 2014.6957e-6, 17.241674e-6, 977.22556e-6, -0.0685, 0.0035, M_PI, 0.0, -24.0*CTRL_DEG2RAD, 24.0*CTRL_DEG2RAD)); } else { pushLink(new iDynLink(0.695, 80.4310e-6, -6.91643e-3, -2.30470e-3, 4470.534e-6, -22.209e-6, 13.9712e-6, 3250.8524e-6, 47.7629e-6, 4904.8747e-6, 0.0, 0.0, M_PI/2.0, M_PI/2.0, -44.0*CTRL_DEG2RAD, 132.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0.982, 31.3229e-6, -1.09640e-3, -59.8624e-3, 27271.4e-6, 1.2116e-6, 11.5713e-6, 25364.6e-6, 491.0806e-6, 4173.9e-6, 0.0, 0.0, M_PI/2.0, M_PI/2.0, -17.0*CTRL_DEG2RAD, 119.0*CTRL_DEG2RAD)); pushLink(new iDynLink(1.522, 3.1143e-3, 60.0431e-3, 1.3437e-3, 45491.7e-6, -940.9711e-6, 53.7405e-6, 10040.0e-6, 1203.0e-6, 45825.5e-6, -0.0009175, 0.234545, -M_PI/2.0, -M_PI/2.0, -79.0*CTRL_DEG2RAD, 79.0*CTRL_DEG2RAD)); pushLink(new iDynLink(2.032, 124.3956e-3, -45.0091e-6, 6.2408e-3, 15455.9e-6, -1390.3e-6, -3945.4e-6, 70277.0e-6, 719.9501e-6, 65964.5e-6, -0.2005, 0.0, M_PI, M_PI/2.0, -125.0*CTRL_DEG2RAD, 23.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0.643, 26.5892e-6, -0.82253e-3, 10.2574e-3, 4765.926e-3, 9.7426e-6, 26.8085e-6, 4093.5e-6, -353.7961e-6, 3668.8e-6, 0.0, 0.0, M_PI/2.0, 0.0, -42.0*CTRL_DEG2RAD, 21.0*CTRL_DEG2RAD)); pushLink(new iDynLink(0.861, 32.4154e-3, -613.9310e-6, 24.0690e-3, 1584.66e-6, -14.357866e-6, 21.079452e-6, 2014.6957e-6, -17.241674e-6, 977.22556e-6, -0.0685, 0.0035, M_PI, 0.0, -24.0*CTRL_DEG2RAD, 24.0*CTRL_DEG2RAD)); }
#endif
#ifdef NO_JOINT_COSTRAINTS this->setAllConstraints(false); #endif }
Reimplemented from iCub::iDyn::iDynLimb.