Go to the documentation of this file.
21 #include <yarp/math/SVD.h>
25 using namespace yarp::sig;
26 using namespace yarp::math;
40 :
iDynSensor(_c, _info, _mode, verb), bodyPart(_bodyPart){}
44 :
iDynSensor(_c, _info, _mode, verb), bodyPart(_bodyPart)
51 const Matrix &_I,
const string &_info,
const NewEulMode _mode,
BodyPart _bodyPart,
unsigned int verb)
52 :
iDynSensor(_c, sensLink, _H, _HC, _m, _I, _info, _mode, verb), bodyPart(_bodyPart){}
73 for(dynContactList::const_iterator it=contacts.begin();it!=contacts.end();it++)
112 unsigned int firstContactLink, lastContactLink;
117 if(firstContactLink<
lSens)
120 fprintf(stderr,
"Contacts before the sensor link. Impossible to compute the external contacts!\n");
126 if(firstContactLink==
lSens)
132 else if(firstContactLink>
lSens+1)
141 Matrix
A =
buildA(firstContactLink, lastContactLink);
142 Vector B =
buildB(firstContactLink, lastContactLink);
144 Vector X = pinv_A * B;
147 unsigned int unknownInd = 0;
151 if(it->isForceDirectionKnown())
152 it->setForceModule( X(unknownInd++));
156 R =
H.submatrix(0,2,0,2);
157 it->setForce( R * X.subVector(unknownInd, unknownInd+2));
159 if(!it->isMomentKnown())
161 it->setMoment(R * X.subVector(unknownInd, unknownInd+2));
168 if(firstContactLink==
lSens)
191 Matrix
A(6, unknownNum);
198 unsigned int colInd = 0;
200 Matrix eye3x3 = eye(3,3);
201 Matrix zero3x3 =
zeros(3,3);
202 Vector r, temp1, temp2;
203 dynContactList::const_iterator it =
contactList.begin();
209 R =
H.submatrix(0,2,0,2);
212 if(it->isForceDirectionKnown())
214 temp1 = R*it->getForceDirection();
215 temp2 = R*it->getCoP();
217 A.setSubcol(temp1, 0, colInd);
218 A.setSubcol(
cross(temp2, temp1), 3, colInd++);
222 temp1 = R*it->getCoP();
224 A.setSubmatrix(eye3x3, 0, colInd);
225 A.setSubmatrix(crossProductMatrix(temp1), 3, colInd);
228 if(!it->isMomentKnown())
230 A.setSubmatrix(zero3x3, 0, colInd);
231 A.setSubmatrix(eye3x3, 3, colInd);
247 Matrix Hlast =
getHFromAtoB(firstContactLink-1, lastContactLink);
248 Matrix Rlast = Hlast.submatrix(0,2,0,2);
249 Vector rLast = Hlast.subcol(0,3,3);
255 for(
unsigned int i=firstContactLink; i<=lastContactLink; i++)
258 R =
H.submatrix(0,2,0,2);
276 for(
unsigned int i=firstContactLink; i<=lastContactLink; i++)
282 R =
H.submatrix(0,2,0,2);
290 return cat(Bforce, Bmoment);
303 if(it->getLinkNumber() == eeInd)
304 return it->getForceMoment();
310 dynContactList::const_iterator it=
contactList.begin();
316 unsigned int l = it->getLinkNumber();
336 for(
unsigned int i=a+2; i<=b; i++)
346 Matrix R_r2L = H_r20.submatrix(0,2,0,2) * H_02L.submatrix(0,2,0,2);
352 dynContactList::const_iterator it=
contactList.begin();
353 unsigned int unknowns=0;
357 if(it->isMomentKnown())
359 if(it->isForceDirectionKnown())
OneChainNewtonEuler * NE
pointer to OneChainNewtonEuler class, to be used for computing forces and torques
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...
const yarp::sig::Vector & getdW() const
Get the angular acceleration of the link.
bool BackwardWrenchFromAtoB(unsigned int lA, unsigned int lB)
Base function for inverse Newton-Euler: from the lA-th link to the lB-th, backward of forces and mome...
void computeKinematicNewtonEuler()
Calls the proper method to compute kinematics variables: either ForwardKinematicFromBase() or Backwar...
bool initWrenchEnd(const yarp::sig::Vector &F0, const yarp::sig::Vector &Mu0)
[classic] Initialize the end-effector finalLink with measured or known wrench
const yarp::sig::Vector & getLinAccC() const
Get the linear acceleration of the COM.
double getMass(const unsigned int i) const
Returns the i-th link mass.
const yarp::sig::Matrix & getH()
Redefine the getH of iKinLink so that it does not compute the H matrix if the joint angles have not c...
bool BackwardWrenchToBase(unsigned int lSens)
[classic/inverse] Base function for inverse Newton-Euler: from the i-th link to the base,...
SensorLinkNewtonEuler * sens
the sensor
void prepareNewtonEuler(const NewEulMode NewEulMode_s=DYNAMIC)
Prepare for the Newton-Euler recursive computation of forces and torques.
static const double TOLLERANCE
unsigned int verbose
verbosity flag
bool ForwardWrenchFromAtoB(unsigned int lA, unsigned int lB)
Base function for inverse Newton-Euler: from the lA-th link to the lB-th, forward of forces and momen...
iDynLink * refLink(const unsigned int i)
Returns a pointer to the ith iDynLink.
unsigned int getN() const
Returns the number of Links belonging to the Chain.
const yarp::sig::Vector & getMoment(const unsigned int iLink) const
Returns the i-th link moment.
yarp::sig::Matrix getH0() const
Returns H0, the rigid roto-translation matrix from the root reference frame to the 0th frame.
NewEulMode mode
static/dynamic/etc..
iDynChain * chain
the iDynChain describing the robotic chain
void computeTorques()
Computes all the torques in the chain, assuming that all the internal wrenches have been already comp...
yarp::sig::Vector cross(const yarp::sig::Matrix &A, int colA, const yarp::sig::Matrix &B, int colB)
void ForwardAttachToLink(iDynLink *link)
Compute w,dw,ddp,dppC given the reference frame of the link where the sensor is.
const yarp::sig::Vector & getForce(const unsigned int iLink) const
Returns the i-th link force.
const yarp::sig::Matrix & getInertia() const
Get the inertia matrix.
const std::string BodyPart_s[]
const yarp::sig::Vector & getLinAccCOM(const unsigned int i) const
Returns the i-th link linear acceleration of the COM.
unsigned int lSens
the link where the sensor is attached to
void ForwardForcesMomentsToLink(iDynLink *link)
Forward the sensor forces and moments, measured by the sensor, to the reference frame of the link whe...
const yarp::sig::Vector & getW() const
Get the angular velocity of the link.
const yarp::sig::Matrix & getCOM() const
Get the roto-translational matrix describing the COM.
bool setSensorMeasures(const yarp::sig::Vector &F, const yarp::sig::Vector &Mu)
Set the sensor measured force and moment.
double getMass() const
Get the link mass.