23 std::ofstream update_log(
"update.log");
27 static double update_start_time = 0.0;
31 double max_condition_number = -1.0;
32 Joint* max_condition_number_joint = 0;
33 double max_sigma_ratio = -1.0;
34 Joint* max_sigma_ratio_joint = 0;
35 fVec condition_numbers;
37 double total_gamma_error = 0.0;
43 update_log <<
"Update no contact" << endl;
46 update_start_time = MPI_Wtime();
49 max_condition_number = -1.0;
50 max_sigma_ratio = -1.0;
51 max_condition_number_joint = 0;
52 max_sigma_ratio_joint = 0;
55 condition_numbers.
zero();
57 total_gamma_error = 0.0;
78 cerr <<
"[" << rank <<
"] disassembly t = " << MPI_Wtime()-update_start_time << endl;
84 cerr <<
"--- max condition number = " << max_condition_number <<
" at " << max_condition_number_joint->
name << endl;
85 cerr <<
"--- max sigma ratio = " << max_sigma_ratio <<
" at " << max_sigma_ratio_joint->
name << endl;
86 cerr <<
"--- total_gamma_error = " << total_gamma_error << endl;
98 void pSim::scatter_acc()
101 for(i=0; i<
size; i++)
103 MPI_Bcast(MPI_BOTTOM, 1, all_acc_types[i], i, MPI_COMM_WORLD);
108 void pSubChain::scatter_acc()
111 if(last_joint && last_joint->t_given)
113 switch(last_joint->j_type)
117 last_joint->SetJointAcc(acc_final(0));
121 last_joint->SetJointAcc(acc_final(0), acc_final(1), acc_final(2));
125 last_joint->SetJointAcc(acc_final(0), acc_final(1), acc_final(2),
126 acc_final(3), acc_final(4), acc_final(5));
132 sendbuf = last_pjoints[0]->f_final.data();
133 MPI_Bcast(sendbuf, 6, MPI_DOUBLE, rank, MPI_COMM_WORLD);
134 sendbuf = last_pjoints[1]->f_final.data();
135 MPI_Bcast(sendbuf, 6, MPI_DOUBLE, rank, MPI_COMM_WORLD);
138 if(children[0]) children[0]->scatter_acc();
139 if(children[1] && children[0] != children[1]) children[1]->scatter_acc();
168 static fVec3 rel_pos;
170 if(link_side == joint->real)
172 rel_pos.
set(joint->rpos_real);
173 rel_att.
set(joint->ratt_real);
177 rel_pos.
set(joint->rel_pos);
178 rel_att.
set(joint->rel_att);
180 static fMat33 tcross, tmpT;
181 tcross.
cross(rel_pos);
182 tmpT.
mul(tcross, rel_att);
183 J(0,0) = rel_att(0,0), J(0,1) = rel_att(1,0), J(0,2) = rel_att(2,0);
184 J(1,0) = rel_att(0,1), J(1,1) = rel_att(1,1), J(1,2) = rel_att(2,1);
185 J(2,0) = rel_att(0,2), J(2,1) = rel_att(1,2), J(2,2) = rel_att(2,2);
186 J(0,3) = tmpT(0,0), J(0,4) = tmpT(1,0), J(0,5) = tmpT(2,0);
187 J(1,3) = tmpT(0,1), J(1,4) = tmpT(1,1), J(1,5) = tmpT(2,1);
188 J(2,3) = tmpT(0,2), J(2,4) = tmpT(1,2), J(2,5) = tmpT(2,2);
189 J(3,0) = 0.0, J(3,1) = 0.0, J(3,2) = 0.0;
190 J(4,0) = 0.0, J(4,1) = 0.0, J(4,2) = 0.0;
191 J(5,0) = 0.0, J(5,1) = 0.0, J(5,2) = 0.0;
192 J(3,3) = rel_att(0,0), J(3,4) = rel_att(1,0), J(3,5) = rel_att(2,0);
193 J(4,3) = rel_att(0,1), J(4,4) = rel_att(1,1), J(4,5) = rel_att(2,1);
194 J(5,3) = rel_att(0,2), J(5,4) = rel_att(1,2), J(5,5) = rel_att(2,2);
209 children[0]->calc_inertia();
210 if(children[1] != children[0])
212 children[1]->calc_inertia();
219 void pSubChain::recv_inertia()
225 for(i=0; i<n_outer_joints; i++)
227 for(j=i; j<n_outer_joints; j++)
229 double*
buf = Lambda[
i][j].data();
230 MPI_Recv(buf, 36, MPI_DOUBLE, rank, PSIM_TAG_LAMBDA, MPI_COMM_WORLD, &status);
233 Lambda[j][
i].tran(Lambda[i][j]);
239 double time1 = MPI_Wtime();
241 MPI_Recv(MPI_BOTTOM, 1, parent_lambda_type, rank, PSIM_TAG_LAMBDA, MPI_COMM_WORLD, &status);
243 double time2 = MPI_Wtime();
244 sim->inertia_wait_time += time2-time1;
249 void pSubChain::send_inertia(
int dest)
254 for(i=0; i<n_outer_joints; i++)
256 for(j=i; j<n_outer_joints; j++)
258 double*
buf = Lambda[
i][j].data();
259 MPI_Send(buf, 36, MPI_DOUBLE, dest, PSIM_TAG_LAMBDA, MPI_COMM_WORLD);
263 MPI_Send(MPI_BOTTOM, 1, parent_lambda_type, dest, PSIM_TAG_LAMBDA, MPI_COMM_WORLD);
271 if(
sim->rank != rank)
return;
276 for(i=0; i<n_outer_joints; i++)
278 static fMat JM(6, 6);
279 if(outer_joints[i]->parent_side)
281 JM.
mul(outer_joints[i]->J, outer_joints[i]->plink->Minv);
285 JM.
set(outer_joints[i]->plink->Minv);
287 for(j=i; j<n_outer_joints; j++)
289 static fMat tJ(6, 6);
290 if(outer_joints[j]->parent_side)
292 tJ.
tran(outer_joints[j]->J);
293 Lambda[
i][j].
mul(JM, tJ);
297 Lambda[
i][j].set(JM);
301 Lambda[j][
i].tran(Lambda[i][j]);
305 if(parent &&
sim->rank != parent->rank)
308 send_inertia(parent->rank);
318 if(
sim->rank != rank)
return;
319 if(children[0] &&
sim->rank != children[0]->rank)
322 children[0]->recv_inertia();
324 if(children[1] && children[0] != children[1] &&
sim->rank != children[1]->rank)
327 children[1]->recv_inertia();
335 P.add(children[0]->Lambda[last_index[0]][last_index[0]], children[1]->Lambda[last_index[1]][last_index[1]]);
339 P.set(children[0]->Lambda[last_index[0]][last_index[0]]);
345 fMat U1(6,6), V1T(6,6), U2(6,6), V2T(6,6);
346 fVec sigma1(6), sigma2(6);
347 children[0]->Lambda[last_index[0]][last_index[0]].svd(U1, sigma1, V1T);
348 children[1]->Lambda[last_index[1]][last_index[1]].svd(U2, sigma2, V2T);
349 double s1 = sigma1.length(),
s2 = sigma2.
length();
350 if(s1 > 1e-8 &&
s2 > 1e-8)
352 double ratio = (s1 <
s2) ?
s2/s1 : s1/
s2;
353 if(max_sigma_ratio < 0.0 || ratio > max_sigma_ratio)
355 max_sigma_ratio = ratio;
356 max_sigma_ratio_joint = last_joint;
358 sigma_ratios(last_joint->i_dof) = ratio;
363 if(children[0] == children[1])
365 P -= children[0]->Lambda[last_index[0]][last_index[1]];
366 P -= children[0]->Lambda[last_index[1]][last_index[0]];
376 for(i=0; i<n_const; i++)
378 for(j=0; j<n_const; j++)
379 Gamma(i, j) = P(const_index[i], const_index[j]);
381 if(children[0] != children[1])
384 if(Gamma_inv.inv_posv(Gamma))
385 Gamma_inv.inv_svd(Gamma);
388 fMat U(n_const, n_const), VT(n_const, n_const);
390 Gamma.svd(U, sigma, VT);
391 double cn = sigma(0) / sigma(n_const-1);
392 if(max_condition_number < 0.0 || cn > max_condition_number)
394 max_condition_number = cn;
395 max_condition_number_joint = last_joint;
397 condition_numbers(last_joint->i_dof) = cn;
417 for(i=0; i<n_const; i++)
419 for(
int j=0; j<n_const; j++)
421 W(const_index[i], const_index[j]) = -Gamma_inv(i, j);
424 #else // #ifndef USE_DCA 431 for(i=0; i<
n_dof; i++)
433 for(
int j=0; j<
n_dof; j++)
435 SVS(i,j) = Vhat(joint_index[i], joint_index[j]);
437 for(
int j=0; j<6; j++)
439 SV(i,j) = Vhat(joint_index[i], j);
465 for(i=0; i<n_outer_joints; i++)
467 int org_i = outer_joints_origin[
i];
468 int index_i = outer_joints_index[
i];
469 for(j=i; j<n_outer_joints; j++)
471 int org_j = outer_joints_origin[j];
472 int index_j = outer_joints_index[j];
473 if(children[org_i] == children[org_j])
475 Lambda[
i][j].set(children[org_i]->Lambda[index_i][index_j]);
479 Lambda[j][
i].tran(Lambda[i][j]);
486 for(i=0; i<n_outer_joints; i++)
488 int org_i = outer_joints_origin[
i];
489 int index_i = outer_joints_index[
i];
490 fMat& Lambda_i = children[org_i]->Lambda[index_i][last_index[org_i]];
493 static fMat LKi, KLj, GKLj;
499 for(n=0; n<n_const; n++)
500 LKi(m, n) = Lambda_i(m, const_index[n]);
502 for(j=i; j<n_outer_joints; j++)
504 int org_j = outer_joints_origin[j];
505 int index_j = outer_joints_index[j];
506 fMat& Lambda_j = children[org_j]->Lambda[last_index[org_j]][index_j];
507 for(m=0; m<n_const; m++)
510 KLj(m, n) = Lambda_j(const_index[m], n);
512 GKLj.
mul(Gamma_inv, KLj);
514 Lambda[
i][j].mul(LKi, GKLj);
515 if(children[org_i] == children[org_j])
517 Lambda[
i][j] -= children[org_i]->Lambda[index_i][index_j];
518 Lambda[
i][j] *= -1.0;
522 Lambda[j][
i].tran(Lambda[i][j]);
526 Lambda[
i][j].symmetric();
529 #else // #ifndef USE_DCA 530 for(j=i; j<n_outer_joints; j++)
532 int org_j = outer_joints_origin[j];
533 int index_j = outer_joints_index[j];
534 fMat& Lambda_j = children[org_j]->Lambda[last_index[org_j]][index_j];
538 Lambda[
i][j].
mul(Lambda_i, WL);
539 if(children[org_i] == children[org_j])
541 Lambda[
i][j] -= children[org_i]->Lambda[index_i][index_j];
542 Lambda[
i][j] *= -1.0;
546 Lambda[j][
i].tran(Lambda[i][j]);
550 Lambda[
i][j].symmetric();
557 if(parent &&
sim->rank != parent->rank)
560 send_inertia(parent->rank);
590 v(0) = link_side->loc_lin_vel(0);
591 v(1) = link_side->loc_lin_vel(1);
592 v(2) = link_side->loc_lin_vel(2);
593 v(3) = link_side->loc_ang_vel(0);
594 v(4) = link_side->loc_ang_vel(1);
595 v(5) = link_side->loc_ang_vel(2);
600 dvel(0) = joint->loc_lin_vel(0);
601 dvel(1) = joint->loc_lin_vel(1);
602 dvel(2) = joint->loc_lin_vel(2);
603 dvel(3) = joint->loc_ang_vel(0);
604 dvel(4) = joint->loc_ang_vel(1);
605 dvel(5) = joint->loc_ang_vel(2);
619 children[0]->calc_dvel();
620 if(children[1] != children[0]) children[1]->calc_dvel();
628 for(i=0; i<n_outer_joints; i++)
630 vel_temp[
i].set(outer_joints[i]->dvel);
636 if(!children[1])
return;
639 static fVec dv6(6), dv;
645 for(j=0; j<
n_dof; j++)
646 PK(i, j) = P(i, joint_index[j]);
649 dv6.sub(children[0]->vel_temp[last_index[0]], children[1]->vel_temp[last_index[1]]);
652 for(i=0; i<n_const; i++)
653 dv(i) = -dv6(const_index[i]);
654 #ifndef USE_DCA // TODO: allow dca 655 colf_temp.mul(Gamma_inv, dv);
660 for(i=0; i<n_const; i++)
661 f(const_index[i]) = colf_temp(i);
662 for(i=0; i<n_outer_joints; i++)
664 int org = outer_joints_origin[
i];
665 int index = outer_joints_index[
i];
666 int ilast = last_index[org];
667 vel_temp[
i].mul(children[org]->Lambda[index][ilast], f);
672 vel_temp[
i] += children[org]->vel_temp[index];
686 col_disassembly_body();
688 children[0]->col_disassembly();
689 if(children[1] != children[0]) children[1]->col_disassembly();
696 if(!children[1])
return;
699 static fVec KLf, Lf(6), Lf_temp[2], v(6), colf, colf_final(6);
706 for(i=0; i<n_outer_joints; i++)
708 int org = outer_joints_origin[
i];
709 int index = outer_joints_index[
i];
710 fMat& Lambda_i = children[org]->Lambda[last_index[org]][index];
712 v.
mul(Lambda_i, children[org]->outer_joints[index]->colf_final);
715 Lf.
sub(Lf_temp[0], Lf_temp[1]);
717 for(i=0; i<n_const; i++)
718 KLf(i) = Lf(const_index[i]);
719 #ifndef USE_DCA // TODO: allow DCA 720 colf.
mul(Gamma_inv, KLf);
724 for(i=0; i<n_const; i++)
725 colf_final(const_index[i]) = colf_temp(i);
726 last_pjoints[0]->colf_final.set(colf_final);
727 last_pjoints[1]->colf_final.neg(colf_final);
729 last_pjoints[0]->vel_final.mul(children[0]->Lambda[last_index[0]][last_index[0]], last_pjoints[0]->colf_final);
730 last_pjoints[0]->vel_final += Lf_temp[0];
731 last_pjoints[0]->vel_final += children[0]->vel_temp[last_index[0]];
734 last_pjoints[1]->vel_final.
mul(children[1]->Lambda[last_index[1]][last_index[1]], last_pjoints[1]->colf_final);
735 last_pjoints[1]->vel_final += Lf_temp[1];
736 last_pjoints[1]->vel_final += children[1]->vel_temp[last_index[1]];
738 if(children[0] == children[1])
740 v.
mul(children[1]->Lambda[last_index[0]][last_index[1]], last_pjoints[1]->colf_final);
741 last_pjoints[0]->vel_final += v;
742 v.mul(children[0]->Lambda[last_index[1]][last_index[0]], last_pjoints[0]->colf_final);
743 last_pjoints[1]->vel_final += v;
746 v.sub(last_pjoints[0]->vel_final, last_pjoints[1]->vel_final);
748 switch(last_joint->j_type)
752 last_joint->SetJointVel(v(axis));
755 last_joint->SetJointVel(
fVec3(v(3), v(4), v(5)));
758 last_joint->SetJointVel(
fVec3(v(0), v(1), v(2)),
fVec3(v(3), v(4), v(5)));
798 cerr <<
"[" << rank <<
"] update_velocity end t = " << MPI_Wtime()-update_start_time << endl;
806 static fVec3 v1, v2, v3;
807 static fVec3 rel_pos;
809 if(link_side == joint->real)
811 rel_pos.
set(joint->rpos_real);
812 rel_att.
set(joint->ratt_real);
816 rel_pos.
set(joint->rel_pos);
817 rel_att.
set(joint->rel_att);
819 v1.
cross(link_side->loc_ang_vel, rel_pos);
820 v2.
cross(link_side->loc_ang_vel, v1);
826 v1.
mul(link_side->loc_ang_vel, rel_att);
828 v2.
cross(v1, joint->rel_lin_vel);
832 v2.
cross(v1, joint->rel_ang_vel);
853 static fVec3 a, c1, c2, g;
855 g.
mul(g0, joint->abs_att);
857 v1.
cross(joint->loc_ang_vel, joint->loc_com);
858 a.
cross(joint->loc_ang_vel, v1);
861 c1.
mul(joint->mass, a);
863 v1.
mul(joint->inertia, joint->loc_ang_vel);
864 v2.
cross(joint->loc_ang_vel, v1);
865 c2.
cross(joint->loc_com, c1);
868 c1 -= joint->ext_force;
869 c2 -= joint->ext_moment;
871 update_log << joint->name <<
": external force/moment = " << joint->ext_force <<
"/" << joint->ext_moment << endl;
897 children[0]->calc_acc();
898 if(children[1] != children[0])
900 children[1]->calc_acc();
907 void pSubChain::recv_acc()
912 for(i=0; i<n_outer_joints; i++)
914 double*
buf = acc_temp[
i].data();
915 MPI_Recv(buf, 6, MPI_DOUBLE, rank, PSIM_TAG_ACC, MPI_COMM_WORLD, &status);
919 double time1 = MPI_Wtime();
920 cerr <<
"[" <<
sim->rank <<
"] recv_acc(0) t = " << MPI_Wtime()-update_start_time << endl;
922 MPI_Recv(MPI_BOTTOM, 1, parent_acc_type, rank, PSIM_TAG_ACC, MPI_COMM_WORLD, &status);
924 cerr <<
"[" <<
sim->rank <<
"] recv_acc(1) t = " << MPI_Wtime()-update_start_time << endl;
925 double time2 = MPI_Wtime();
926 sim->acc_wait_time += time2-time1;
931 void pSubChain::send_acc(
int dest)
935 for(i=0; i<n_outer_joints; i++)
937 double*
buf = acc_temp[
i].data();
938 MPI_Send(buf, 6, MPI_DOUBLE, dest, PSIM_TAG_ACC, MPI_COMM_WORLD);
942 cerr <<
"[" <<
sim->rank <<
"] send_acc(0) t = " << MPI_Wtime()-update_start_time << endl;
944 MPI_Send(MPI_BOTTOM, 1, parent_acc_type, dest, PSIM_TAG_ACC, MPI_COMM_WORLD);
946 cerr <<
"[" <<
sim->rank <<
"] send_acc(1) t = " << MPI_Wtime()-update_start_time << endl;
955 if(
sim->rank != rank)
return;
960 for(i=0; i<n_outer_joints; i++)
962 if(outer_joints[i]->parent_side)
964 acc_temp[
i].mul(outer_joints[i]->J, links[0]->acc);
965 acc_temp[
i] += outer_joints[
i]->Jdot;
970 acc_temp[
i].add(links[0]->acc, outer_joints[i]->Jdot);
975 if(parent &&
sim->rank != parent->rank)
977 send_acc(parent->rank);
986 if(
sim->rank != rank)
return;
987 if(children[0] &&
sim->rank != children[0]->rank)
989 children[0]->recv_acc();
991 if(children[1] && children[0] != children[1] &&
sim->rank != children[1]->rank)
993 children[1]->recv_acc();
1005 for(j=0; j<
n_dof; j++)
1006 PK(i, j) = P(i, joint_index[j]);
1008 if(last_joint->n_dof > 0)
1010 switch(last_joint->j_type)
1014 tau(0) = last_joint->tau;
1017 tau(0) = last_joint->tau_n(0);
1018 tau(1) = last_joint->tau_n(1);
1019 tau(2) = last_joint->tau_n(2);
1022 tau(0) = last_joint->tau_f(0);
1023 tau(1) = last_joint->tau_f(1);
1024 tau(2) = last_joint->tau_f(2);
1025 tau(3) = last_joint->tau_n(0);
1026 tau(4) = last_joint->tau_n(1);
1027 tau(5) = last_joint->tau_n(2);
1038 da6 += children[0]->acc_temp[last_index[0]];
1041 da6 -= children[1]->acc_temp[last_index[1]];
1044 if(!last_joint->t_given)
1046 switch(last_joint->j_type)
1050 da6(axis) -= last_joint->qdd;
1054 da6(3) -= last_joint->rel_ang_acc(0);
1055 da6(4) -= last_joint->rel_ang_acc(1);
1056 da6(5) -= last_joint->rel_ang_acc(2);
1059 da6(0) -= last_joint->rel_lin_acc(0);
1060 da6(1) -= last_joint->rel_lin_acc(1);
1061 da6(2) -= last_joint->rel_lin_acc(2);
1062 da6(3) -= last_joint->rel_ang_acc(0);
1063 da6(4) -= last_joint->rel_ang_acc(1);
1064 da6(5) -= last_joint->rel_ang_acc(2);
1076 for(i=0; i<n_const; i++)
1077 da(i) = -da6(const_index[i]);
1078 f_temp.mul(Gamma_inv, da);
1081 for(i=0; i<
n_dof; i++)
1082 f(joint_index[i]) = tau(i);
1083 for(i=0; i<n_const; i++)
1084 f(const_index[i]) = f_temp(i);
1091 for(i=0; i<
n_dof; i++)
1093 f(joint_index[i]) += tau(i);
1096 static fVec db(6), Wdb(6), IWRtau(6);
1099 db.set(children[0]->acc_temp[last_index[0]]);
1101 db -= children[1]->acc_temp[last_index[1]];
1105 for(j=0; j<
n_dof; j++)
1107 IWR(i, j) = IW(joint_index[j], i);
1110 IWRtau.
mul(IWR, tau);
1119 for(i=0; i<n_const; i++)
1122 da(i) = -da6(const_index[i]);
1123 f_temp(i) =
f(const_index[i]);
1126 total_gamma_error += (Gamma*f_temp-da) * (Gamma*f_temp-da);
1131 for(i=0; i<n_outer_joints; i++)
1133 int org = outer_joints_origin[
i];
1134 int index = outer_joints_index[
i];
1135 int ilast = last_index[org];
1136 acc_temp[
i].mul(children[org]->Lambda[index][ilast], f);
1139 acc_temp[
i] *= -1.0;
1141 acc_temp[
i] += children[org]->acc_temp[index];
1145 if(parent &&
sim->rank != parent->rank)
1147 send_acc(parent->rank);
1167 children[0]->disassembly();
1168 if(children[1] != children[0]) children[1]->disassembly();
1177 void pSubChain::recv_force()
1182 for(i=0; i<n_outer_joints; i++)
1184 double*
buf = outer_joints[
i]->f_final.data();
1185 MPI_Recv(buf, 6, MPI_DOUBLE, rank, PSIM_TAG_FORCE, MPI_COMM_WORLD, &status);
1188 buf = last_pjoints[0]->f_final.data();
1189 MPI_Recv(buf, 6, MPI_DOUBLE, rank, PSIM_TAG_FORCE, MPI_COMM_WORLD, &status);
1190 buf = last_pjoints[1]->f_final.data();
1191 MPI_Recv(buf, 6, MPI_DOUBLE, rank, PSIM_TAG_FORCE, MPI_COMM_WORLD, &status);
1194 double time1 = MPI_Wtime();
1196 MPI_Recv(MPI_BOTTOM, 1, parent_force_type, rank, PSIM_TAG_FORCE, MPI_COMM_WORLD, &status);
1198 double time2 = MPI_Wtime();
1199 sim->force_wait_time += time2-time1;
1204 void pSubChain::send_force(
int dest)
1208 for(i=0; i<n_outer_joints; i++)
1210 double*
buf = outer_joints[
i]->f_final.data();
1211 MPI_Send(buf, 6, MPI_DOUBLE, dest, PSIM_TAG_FORCE, MPI_COMM_WORLD);
1214 buf = last_pjoints[0]->f_final.data();
1215 MPI_Send(buf, 6, MPI_DOUBLE, dest, PSIM_TAG_FORCE, MPI_COMM_WORLD);
1216 buf = last_pjoints[1]->f_final.data();
1217 MPI_Send(buf, 6, MPI_DOUBLE, dest, PSIM_TAG_FORCE, MPI_COMM_WORLD);
1219 MPI_Send(MPI_BOTTOM, 1, parent_force_type, dest, PSIM_TAG_FORCE, MPI_COMM_WORLD);
1226 Joint* target_joint = links[0]->joint;
1229 cerr <<
"---- " << target_joint->
name <<
": disassembly_leaf" << endl;
1231 static fVec3 total_f, total_n;
1233 static fMat33 att, t_att;
1235 static fVec allf(6);
1242 for(i=0; i<n_outer_joints; i++)
1244 static fVec3 loc_f, loc_n,
f,
n, fn;
1245 static fVec3 jpos, rel_pos, pp;
1246 static fMat33 jatt, rel_att;
1247 cerr <<
"outer[" << i <<
"]: " << outer_joints[
i]->joint->name << endl;
1248 cerr <<
"f_final = " <<
tran(outer_joints[i]->f_final) << endl;
1249 loc_f(0) = outer_joints[
i]->f_final(0);
1250 loc_f(1) = outer_joints[
i]->f_final(1);
1251 loc_f(2) = outer_joints[
i]->f_final(2);
1252 loc_n(0) = outer_joints[
i]->f_final(3);
1253 loc_n(1) = outer_joints[
i]->f_final(4);
1254 loc_n(2) = outer_joints[
i]->f_final(5);
1255 jpos.
set(outer_joints[i]->joint->abs_pos);
1256 jatt.
set(outer_joints[i]->joint->abs_att);
1258 rel_pos.
mul(t_att, pp);
1259 rel_att.
mul(t_att, jatt);
1260 f.
mul(rel_att, loc_f);
1261 n.
mul(rel_att, loc_n);
1262 fn.
cross(rel_pos, f);
1264 cerr <<
"(f n) = " << f << n << endl;
1268 allf(0) = total_f(0);
1269 allf(1) = total_f(1);
1270 allf(2) = total_f(2);
1271 allf(3) = total_n(0);
1272 allf(4) = total_n(1);
1273 allf(5) = total_n(2);
1274 cerr <<
"total_f = " << total_f << endl;
1275 cerr <<
"total_n = " << total_n << endl;
1277 acc += links[0]->acc;
1278 cerr <<
"Minv = " << links[0]->Minv << endl;
1279 cerr <<
"acc = " <<
tran(links[0]->acc) << endl;
1280 cerr <<
"link acc = " <<
tran(acc) << endl;
1286 if(!children[1])
return;
1288 update_log <<
"disassembly_body" << endl;
1291 if(
sim->rank != rank)
return;
1292 if(parent &&
sim->rank != parent->rank)
1295 cerr <<
"[" <<
sim->rank <<
"] " << last_joint->name <<
": recv force from " << parent->last_joint->name <<
" [" << parent->rank <<
"] t = " << MPI_Wtime()-update_start_time << endl;
1297 parent->recv_force();
1302 if(children[1] && children[0] != children[1] &&
sim->rank != children[1]->rank)
1303 cerr <<
"[" <<
sim->rank <<
"] " << last_joint->name <<
" enter disassembly t = " << MPI_Wtime()-update_start_time << endl;
1306 static fVec KLf, Lf(6), Lf_temp[2], v(6),
f, f_final(6);
1313 for(i=0; i<n_outer_joints; i++)
1315 int org = outer_joints_origin[
i];
1316 int index = outer_joints_index[
i];
1317 fMat& Lambda_i = children[org]->Lambda[last_index[org]][index];
1320 v.
mul(Lambda_i, outer_joints[i]->f_final);
1323 update_log << outer_joints[
i]->joint->name <<
": f_final[" << i <<
"] = " <<
tran(outer_joints[i]->f_final) << endl;
1327 Lf.
sub(Lf_temp[0], Lf_temp[1]);
1336 for(i=0; i<
n_dof; i++)
1337 f_final(joint_index[i]) += tau(i);
1338 last_pjoints[0]->f_final.set(f_final);
1339 last_pjoints[1]->f_final.neg(f_final);
1341 for(i=0; i<
n_dof; i++)
1343 acc_final(i) = v(joint_index[i]);
1345 last_joint->joint_f.set(
fVec3(f_final(0), f_final(1), f_final(2)));
1346 last_joint->joint_n.set(
fVec3(f_final(3), f_final(4), f_final(5)));
1347 #else // #ifndef USE_DCA (DCA test) 1348 static fVec vp(6), svp;
1353 for(i=0; i<
n_dof; i++)
1355 svp(i) = tau(i) + vp(joint_index[i]);
1357 acc_final.lineq_posv(SVS, svp);
1362 switch(last_joint->j_type)
1366 v(axis) = acc_final(0);
1369 v(3) = acc_final(0);
1370 v(4) = acc_final(1);
1371 v(5) = acc_final(2);
1378 f_final.
mul(Vhat, pp);
1379 last_pjoints[0]->f_final.neg(f_final);
1380 last_pjoints[1]->f_final.set(f_final);
1383 if(last_joint->t_given) {
1384 switch(last_joint->j_type) {
1387 last_joint->SetJointAcc(v(axis));
1391 last_joint->SetJointAcc(v(3), v(4), v(5));
1394 last_joint->SetJointAcc(v(0), v(1), v(2), v(3), v(4), v(5));
1396 update_log << last_joint->name <<
": " <<
tran(v) << endl;
1405 if(children[0] &&
sim->rank != children[0]->rank)
1408 cerr <<
"[" <<
sim->rank <<
"] " << last_joint->name <<
": send force to " << children[0]->last_joint->name <<
" [" << children[0]->rank <<
"] t = " << MPI_Wtime()-update_start_time << endl;
1410 send_force(children[0]->rank);
1412 if(children[1] && children[0] != children[1] &&
sim->rank != children[1]->rank)
1415 cerr <<
"[" <<
sim->rank <<
"] " << last_joint->name <<
": send force to " << children[1]->last_joint->name <<
" [" << children[1]->rank <<
"] t = " << MPI_Wtime()-update_start_time << endl;
1417 send_force(children[1]->rank);
int resize(int i, int j)
Changes the matrix size.
void zero()
Creates a zero vector.
void set(const fMat33 &mat)
Copies a matrix.
void mul(const fMat33 &mat1, const fMat33 &mat2)
friend fMat33 tran(const fMat33 &m)
Returns the transpose.
void cross(const fVec3 &vec1, const fVec3 &vec2)
Cross product.
Forward dynamics computation based on Assembly-Disassembly Algorithm.
void calc_acc(const fVec3 &g0)
int Update()
Compute joint accelerations.
void set(double *v)
Set element values from array or three values.
void mul(const fMat &mat1, const fMat &mat2)
friend fMat lineq(const fMat &A, const fMat &b)
solve linear equation Ax = b
void set(double *_d)
Sets all elements.
void mul(const fVec &vec, double d)
int inv_svd(const fMat &, int lwork=-1)
inverse
def j(str, encoding="cp932")
void sub(const fVec &vec1, const fVec &vec2)
fMat33 abs_att
absolute orientation
void cross(const fVec3 &p)
Sets spectial matrices.
int do_connect
true after Connect() was called; application (or subclass) must reset the flag
char * name
joint name (including the character name)
int lineq_posv(const fMat &A, const fVec &b)
void resize(int i)
Change the size.
fMat tran(const fMat &mat)
void col_disassembly_body()
void zero()
Creates a zero vector.
void sub(const fVec3 &vec1, const fVec3 &vec2)
friend fMat tran(const fMat &mat)
Returns the transpose of a matrix.
void set(double *_d)
Sets the values from an array.
void symmetric(char t= 'U')
Change to symmetric matrix.
friend double length(const fVec &v)
Length of the vector.
fVec3 abs_pos
absolute position
void mul(const fVec3 &vec, double d)
The class for representing a joint.
void add(const fVec &vec1, const fVec &vec2)
Matrix of generic size. The elements are stored in a one-dimensional array in row-major order...