Go to the documentation of this file.
33 dq0(body->numLinks()),
83 Matrix33::ColXpr x = R.col(0);
84 Matrix33::ColXpr y = R.col(1);
85 Matrix33::ColXpr z = R.col(2);
87 z = x.cross(y).normalized();
97 body->setVirtualJointForces();
122 int n =
body->numLinks();
123 for(
int i=1;
i <
n; ++
i){
139 root->
w =
w0 + root->
dw * dt;
147 int n =
body->numLinks();
148 for(
int i=1;
i <
n; ++
i){
152 link->
q =
q0[
i] + dt * link->
dq;
155 dq[
i] += r * link->
dq;
177 int n =
body->numLinks();
178 for(
int i=1;
i <
n; ++
i){
213 for(
int i=1;
i <
n; ++
i){
226 for(
int i=0;
i <
n; ++
i){
227 Link* link = traverse[
i];
235 link->
p = parent->
R * link->
b + parent->
p;
236 link->
sw.noalias() = parent->
R * link->
a;
237 link->
sv = link->
p.cross(link->
sw);
238 link->
w = link->
dq * link->
sw + parent->
w;
242 link->
p = parent->
R * (link->
b + link->
q * link->
d) + parent->
p;
245 link->
sv.noalias() = parent->
R * link->
d;
251 link->
p = parent->
R * link->
b + parent->
p;
254 link->
vo = parent->
vo;
259 goto COMMON_CALCS_FOR_ALL_JOINT_TYPES;
263 link->
vo = link->
dq * link->
sv + parent->
vo;
264 Vector3 dsv(parent->
w.cross(link->
sv) + parent->
vo.cross(link->
sw));
266 link->
cv = link->
dq * dsv;
267 link->
cw = link->
dq * dsw;
270 COMMON_CALCS_FOR_ALL_JOINT_TYPES:
272 link->
v = link->
vo + link->
w.cross(link->
p);
274 link->
wc = link->
R * link->
c + link->
p;
277 Matrix33 Iw(link->
R * link->
I * link->
R.transpose());
280 link->
Iww = link->
m * (c_hat * c_hat.transpose()) + Iw;
287 link->
Iwv = link->
m * c_hat;
293 link->
pf = link->
w.cross(P);
294 link->
ptau = link->
vo.cross(P) + link->
w.cross(L);
310 for(
int i =
n-1;
i >= 0; --
i){
311 Link* link = traverse[
i];
320 link->
Ivv += child->Ivv;
321 link->
Iwv += child->Iwv;
322 link->
Iww += child->Iww;
325 Vector3 hhv_dd(child->hhv / child->dd);
326 link->
Ivv += child->Ivv - child->hhv * hhv_dd.transpose();
327 link->
Iwv += child->Iwv - child->hhw * hhv_dd.transpose();
328 link->
Iww += child->Iww - child->hhw * (child->hhw / child->dd).transpose();
331 link->
pf += child->Ivv * child->cv + child->Iwv.transpose() * child->cw + child->pf;
332 link->
ptau += child->Iwv * child->cv + child->Iww * child->cw + child->ptau;
335 double uu_dd = child->uu / child->dd;
336 link->
pf += uu_dd * child->hhv;
337 link->
ptau += uu_dd * child->hhw;
344 link->
hhv = link->
Ivv * link->
sv + link->
Iwv.transpose() * link->
sw;
347 link->
dd = link->
sv.dot(link->
hhv) + link->
sw.dot(link->
hhw) + link->
Jm2;
349 link->
uu = link->
u - (link->
hhv.dot(link->
cv) + link->
hhw.dot(link->
cw)
350 + link->
sv.dot(link->
pf) + link->
sw.dot(link->
ptau));
363 for(
int i =
n-1;
i >= 0; --
i){
364 Link* link = traverse[
i];
369 link->
Ivv += child->Ivv;
370 link->
Iwv += child->Iwv;
371 link->
Iww += child->Iww;
374 Vector3 hhv_dd(child->hhv / child->dd);
375 link->
Ivv += child->Ivv - child->hhv * hhv_dd.transpose();
376 link->
Iwv += child->Iwv - child->hhw * hhv_dd.transpose();
377 link->
Iww += child->Iww - child->hhw * (child->hhw / child->dd).transpose();
380 link->
pf += child->Ivv * child->cv + child->Iwv.transpose() * child->cw;
381 link->
ptau += child->Iwv * child->cv + child->Iww * child->cw;
386 link->
hhv = link->
Ivv * link->
sv + link->
Iwv.transpose() * link->
sw;
388 link->
dd = link->
sv.dot(link->
hhv) + link->
sw.dot(link->
hhw) + link->
Jm2;
389 link->
uu = - (link->
hhv.dot(link->
cv) + link->
hhw.dot(link->
cw));
402 for(
int i =
n-1;
i >= 0; --
i){
403 Link* link = traverse[
i];
409 link->
pf += child->pf;
410 link->
ptau += child->ptau;
413 double uu_dd = child->uu / child->dd;
414 link->
pf += uu_dd * child->hhv;
415 link->
ptau += uu_dd * child->hhw;
421 link->
uu += link->
u - (link->
sv.dot(link->
pf) + link->
sw.dot(link->
ptau));
431 Link* root = traverse[0];
439 Ia << root->
Ivv, root->
Iwv.transpose(),
443 p << root->
pf, root->
ptau;
446 dvector pm(Ia.colPivHouseholderQr().solve(p));
448 root->
dvo = pm.head(3);
449 root->
dw = pm.tail(3);
457 for(
int i=1;
i <
n; ++
i){
458 Link* link = traverse[
i];
461 link->
ddq = (link->
uu - (link->
hhv.dot(parent->
dvo) + link->
hhw.dot(parent->
dw))) / link->
dd;
463 link->
dw = parent->
dw + link->
cw + link->
sw * link->
ddq;
467 link->
dw = parent->
dw;
476 for(
int i=0;
i <
n; ++
i){
493 Vector3 fs(sensorR.transpose() *
f);
495 Vector3 ts(sensorR.transpose() * (tau - sensorPos.cross(
f)));
501 cout <<
"sensor " << sensor->
name <<
": ";
503 cout <<
"R = " << sensorR;
504 cout <<
"sensor->f = " << sensor->
f;
virtual void initializeSensors()
Vector3 hhw
bottom bock of Ia*s
@ ROTATIONAL_JOINT
6-DOF root link
Matrix33 Iww
bottm right block of the articulated inertia
Matrix33 Ivv
top left block of the articulated inertia
void calcMotionWithEulerMethod()
void updateForceSensor(ForceSensor *sensor)
Vector3 ptau
bias force (torque element)
Vector3 pf
bias force (linear element)
Matrix33 rodrigues(const Vector3 &axis, double q)
Vector3 fext
external force
static void SE3exp(Vector3 &out_p, Matrix33 &out_R, const Vector3 &p0, const Matrix33 &R0, const Vector3 &w, const Vector3 &vo, double dt)
update position/orientation using spatial velocity
double Jm2
Equivalent rotor inertia: n^2*Jm [kg.m^2].
double ddq
joint acceleration
std::vector< double > dq0
std::vector< double > ddq
void calcABMPhase2Part2()
static const bool rootAttitudeNormalizationEnabled
Vector3 vo
translation elements of spacial velocity
virtual void updateSensorsFinal()
Vector3 w
angular velocity, omega
enum hrp::ForwardDynamics::@2 integrationMode
void updateForceSensors()
@ SLIDE_JOINT
translational joint (1 dof)
virtual void calcNextState()
Vector3 b
relative position (parent local)
Matrix33 hat(const Vector3 &c)
The header file of the LinkTraverse class.
void integrateRungeKuttaOneStep(double r, double dt)
unsigned int numLinks() const
Vector3 tauext
external torque (around the world origin)
virtual void initialize()
boost::shared_ptr< Body > BodyPtr
void calcABMPhase2Part1()
Matrix33 I
inertia tensor (self local, around c)
Vector3 hhv
top block of Ia*s
static const bool debugMode
Vector3 dvo
derivative of vo
Vector3 cw
dsw * dq (cross velocity term)
Vector3 dw
derivative of omega
Vector3 a
rotational joint axis (self local)
Vector3 d
translation joint axis (self local)
@ FIXED_JOINT
fixed joint(0 dof)
void calcMotionWithRungeKuttaMethod()
Vector3 c
center of mass (self local)
Vector3 cv
dsv * dq (cross velocity term)
Matrix33 Iwv
bottom left block (transpose of top right block) of the articulated inertia
ForwardDynamicsABM(BodyPtr body)
openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Wed Sep 7 2022 02:51:02