21 #include <boost/test/unit_test.hpp>
22 #include <boost/utility/binary.hpp>
24 #ifdef PINOCCHIO_WITH_SDFORMAT
28 #endif // PINOCCHIO_WITH_SDFORMAT
33 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
35 using namespace Eigen;
40 using namespace Eigen;
47 model.lowerPositionLimit.head<3>().
fill(-1.);
48 model.upperPositionLimit.head<3>().
fill(1.);
51 VectorXd
v = VectorXd::Random(
model.nv);
52 VectorXd
tau = VectorXd::Random(
model.nv);
58 const double mu0 = 0.;
64 data.M.triangularView<Eigen::StrictlyLower>() =
65 data.M.transpose().triangularView<Eigen::StrictlyLower>();
72 BOOST_CHECK(data_ref.
ddq.isApprox(
data.ddq));
74 for (
size_t k = 1; k < (size_t)
model.njoints; ++k)
76 BOOST_CHECK(data_ref.oMi[k].isApprox(
data.oMi[k]));
77 BOOST_CHECK(data_ref.ov[k].isApprox(
data.ov[k]));
78 BOOST_CHECK(data_ref.v[k].isApprox(
data.v[k]));
79 BOOST_CHECK(data_ref.a[k].isApprox(
data.a[k]));
80 BOOST_CHECK(data_ref.oa[k].isApprox(
data.oa[k]));
83 BOOST_CHECK(data_ref.
ddq.isApprox(
data.ddq));
84 BOOST_CHECK(data_ref.
dVdq.isApprox(
data.dVdq));
85 BOOST_CHECK(data_ref.
J.isApprox(
data.J));
86 BOOST_CHECK(data_ref.
dAdq.isApprox(
data.dAdq));
87 BOOST_CHECK(data_ref.
dAdv.isApprox(
data.dAdv));
88 BOOST_CHECK(data_ref.
dFdq.isApprox(
data.dFdq));
89 BOOST_CHECK(data_ref.
dFdv.isApprox(
data.dFdv));
91 BOOST_CHECK(data_ref.
dtau_dq.isApprox(
data.dtau_dq));
92 BOOST_CHECK(data_ref.
dtau_dv.isApprox(
data.dtau_dv));
94 BOOST_CHECK(data_ref.
ddq_dq.isApprox(
data.ddq_dq));
95 BOOST_CHECK(data_ref.
ddq_dv.isApprox(
data.ddq_dv));
96 BOOST_CHECK(data_ref.
Minv.isApprox(
data.ddq_dtau));
101 using namespace Eigen;
107 model.lowerPositionLimit.head<3>().
fill(-1.);
108 model.upperPositionLimit.head<3>().
fill(1.);
111 VectorXd
v = VectorXd::Random(
model.nv);
112 VectorXd
tau = VectorXd::Random(
model.nv);
114 const std::string RF =
"rleg6_joint";
116 const std::string LF =
"lleg6_joint";
124 ci_LF.joint1_placement.setRandom();
126 ci_RF.joint1_placement.setRandom();
137 const double mu0 = 0.;
142 data.M.triangularView<Eigen::StrictlyLower>() =
143 data.M.transpose().triangularView<Eigen::StrictlyLower>();
149 data_ref.
M.triangularView<Eigen::StrictlyLower>() =
150 data_ref.
M.transpose().triangularView<Eigen::StrictlyLower>();
156 fext[
cmodel.joint1_id] =
cmodel.joint1_placement.act(cdata.contact_force);
158 BOOST_CHECK(cdata.oMc1.isApprox(data_ref.oMi[
cmodel.joint1_id] *
cmodel.joint1_placement));
164 BOOST_CHECK(
data.ddq.isApprox(data_ref.
ddq));
165 BOOST_CHECK(
data.dVdq.isApprox(data_ref.
dVdq));
166 BOOST_CHECK(
data.J.isApprox(data_ref.
J));
167 BOOST_CHECK(
data.dAdq.isApprox(data_ref.
dAdq));
168 BOOST_CHECK(
data.dAdv.isApprox(data_ref.
dAdv));
169 BOOST_CHECK(
data.dFdq.isApprox(data_ref.
dFdq));
170 BOOST_CHECK(
data.dFdv.isApprox(data_ref.
dFdv));
172 MatrixXd vLF_partial_dq(MatrixXd::Zero(6,
model.nv)), aLF_partial_dq(MatrixXd::Zero(6,
model.nv)),
173 aLF_partial_dv(MatrixXd::Zero(6,
model.nv)), aLF_partial_da(MatrixXd::Zero(6,
model.nv));
175 MatrixXd vRF_partial_dq(MatrixXd::Zero(6,
model.nv)), aRF_partial_dq(MatrixXd::Zero(6,
model.nv)),
176 aRF_partial_dv(MatrixXd::Zero(6,
model.nv)), aRF_partial_da(MatrixXd::Zero(6,
model.nv));
179 model, data_ref, LF_id, ci_LF.joint1_placement,
LOCAL, vLF_partial_dq, aLF_partial_dq,
180 aLF_partial_dv, aLF_partial_da);
182 model, data_ref, RF_id, ci_RF.joint1_placement,
LOCAL, vRF_partial_dq, aRF_partial_dq,
183 aRF_partial_dv, aRF_partial_da);
186 Jc << aLF_partial_da, aRF_partial_da.topRows<3>();
190 const MatrixXd Kinv = K.inverse();
192 MatrixXd osim((Jc * data_ref.
M.inverse() * Jc.transpose()).inverse());
193 BOOST_CHECK(
data.osim.isApprox(osim));
197 BOOST_CHECK(
data.ov[RF_id].isApprox(data_ref.oMi[RF_id].act(data_ref.v[RF_id])));
198 aRF_partial_dq.topRows<3>() +=
199 cross(ci_RF.joint1_placement.actInv(data_ref.v[RF_id]).angular(), vRF_partial_dq.topRows<3>())
201 ci_RF.joint1_placement.actInv(data_ref.v[RF_id]).linear(), vRF_partial_dq.bottomRows<3>());
203 BOOST_CHECK(
data.ov[LF_id].isApprox(data_ref.oMi[LF_id].act(data_ref.v[LF_id])));
205 ac_partial_dq << aLF_partial_dq, aRF_partial_dq.topRows<3>();
207 MatrixXd dac_dq = ac_partial_dq;
209 BOOST_CHECK(
data.dac_dq.isApprox(dac_dq, 1e-8));
217 BOOST_CHECK(
df_dq.isApprox(
data.dlambda_dq));
240 switch (reference_frame)
246 res.angular() = oa.angular();
262 return oMc.actInv(oa);
283 const Motion v = v1 - c1Mc2.act(v2);
288 return a1 - c1Mc2.act(a2) +
v.cross(c1Mc2.act(v2));
293 using namespace Eigen;
300 model.lowerPositionLimit.head<3>().
fill(-1.);
301 model.upperPositionLimit.head<3>().
fill(1.);
304 VectorXd
v = VectorXd::Random(
model.nv);
305 VectorXd
tau = VectorXd::Random(
model.nv);
307 const std::string LF =
"lleg6_joint";
315 ci_LF.joint1_placement.setRandom();
316 ci_LF.corrector.Kp.array() =
KP;
317 ci_LF.corrector.Kd.array() =
KD;
326 const double mu0 = 0.;
338 MatrixXd ddq_partial_dq_fd(
model.nv,
model.nv);
339 ddq_partial_dq_fd.setZero();
340 MatrixXd ddq_partial_dv_fd(
model.nv,
model.nv);
341 ddq_partial_dv_fd.setZero();
342 MatrixXd ddq_partial_dtau_fd(
model.nv,
model.nv);
343 ddq_partial_dtau_fd.setZero();
346 lambda_partial_dtau_fd.setZero();
348 lambda_partial_dq_fd.setZero();
350 lambda_partial_dv_fd.setZero();
354 const VectorXd lambda0 = data_fd.
lambda_c;
355 VectorXd v_eps(VectorXd::Zero(
model.nv));
356 VectorXd q_plus(
model.nq);
357 VectorXd ddq_plus(
model.nv);
361 const double alpha = 1e-8;
364 for (
int k = 0; k <
model.nv; ++k)
370 ddq_partial_dq_fd.col(k) = (ddq_plus - ddq0) /
alpha;
371 lambda_partial_dq_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
375 BOOST_CHECK(ddq_partial_dq_fd.isApprox(
data.ddq_dq, sqrt(
alpha)));
376 BOOST_CHECK(lambda_partial_dq_fd.isApprox(
data.dlambda_dq, sqrt(
alpha)));
379 for (
int k = 0; k <
model.nv; ++k)
384 ddq_partial_dv_fd.col(k) = (ddq_plus - ddq0) /
alpha;
385 lambda_partial_dv_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
389 BOOST_CHECK(ddq_partial_dv_fd.isApprox(
data.ddq_dv, sqrt(
alpha)));
390 BOOST_CHECK(lambda_partial_dv_fd.isApprox(
data.dlambda_dv, sqrt(
alpha)));
392 VectorXd tau_plus(
tau);
393 for (
int k = 0; k <
model.nv; ++k)
395 tau_plus[k] +=
alpha;
398 ddq_partial_dtau_fd.col(k) = (ddq_plus - ddq0) /
alpha;
399 lambda_partial_dtau_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
400 tau_plus[k] -=
alpha;
403 BOOST_CHECK(lambda_partial_dtau_fd.isApprox(
data.dlambda_dtau, sqrt(
alpha)));
404 BOOST_CHECK(ddq_partial_dtau_fd.isApprox(
data.ddq_dtau, sqrt(
alpha)));
421 using namespace Eigen;
428 model.lowerPositionLimit.head<3>().
fill(-1.);
429 model.upperPositionLimit.head<3>().
fill(1.);
432 VectorXd
v = VectorXd::Random(
model.nv);
433 VectorXd
tau = VectorXd::Random(
model.nv);
434 const double mu = 0.;
437 const std::string RF =
"rleg6_joint";
439 const std::string LF =
"lleg6_joint";
446 ci_RF.joint1_placement.setRandom();
447 ci_RF.joint2_placement.setRandom();
448 ci_RF.corrector.Kp.array() =
KP;
449 ci_RF.corrector.Kd.array() =
KD;
453 ci_LF.joint1_placement.setRandom();
454 ci_LF.joint2_placement.setRandom();
455 ci_LF.corrector.Kp.array() =
KP;
456 ci_LF.corrector.Kd.array() =
KD;
466 const Eigen::VectorXd ddq0 =
476 dlambda_dq, dlambda_dv, dlambda_dtau);
482 model,
data, ci_RF.joint1_id, ci_RF.joint1_placement, ci_RF.reference_frame, dv_RF_dq_L,
488 model,
data, ci_LF.joint1_id, ci_LF.joint1_placement, ci_LF.reference_frame, dv_LF_dq_L,
491 const double eps = 1e-8;
493 dacc_corrector_RF_dq.setZero();
495 dacc_corrector_RF_dv.setZero();
497 dacc_corrector_LF_dq.setZero();
499 dacc_corrector_LF_dv.setZero();
503 dacc_corrector_RF_dq = -(ci_RF.corrector.Kp.asDiagonal() * Jlog * dv_RF_dv_L);
504 dacc_corrector_RF_dq -= ci_RF.corrector.Kd.asDiagonal() * dv_RF_dq_L;
506 dacc_corrector_RF_dv = -(ci_RF.corrector.Kd.asDiagonal() * dv_RF_dv_L);
507 BOOST_CHECK(dv_RF_dv_L.isApprox(
data.contact_chol.matrix().topRightCorner(6,
model.nv)));
511 dacc_corrector_LF_dq = -(ci_LF.corrector.Kp.asDiagonal() * dv_LF_dv_L.topRows<3>());
512 dacc_corrector_LF_dq -= ci_LF.corrector.Kd.asDiagonal() * dv_LF_dq_L.topRows<3>();
513 for (Eigen::DenseIndex k = 0; k <
model.nv; ++k)
515 dacc_corrector_LF_dq.col(k) +=
516 ci_LF.corrector.Kp.asDiagonal()
520 dacc_corrector_LF_dv = -(ci_LF.corrector.Kd.asDiagonal() * dv_LF_dv_L.topRows<3>());
521 BOOST_CHECK(dv_LF_dv_L.topRows<3>().isApprox(
522 data.contact_chol.matrix().topRightCorner(9,
model.nv).bottomRows<3>()));
537 for (Eigen::DenseIndex k = 0; k <
model.nv; ++k)
539 Eigen::VectorXd v_eps = Eigen::VectorXd::Zero(
model.nv);
545 dacc_corrector_RF_dq_fd.col(k) = (constraint_datas_fd[0].contact_acceleration_error
549 dacc_corrector_LF_dq_fd.col(k) = (constraint_datas_fd[1].contact_acceleration_error.linear()
553 ddq_dq_fd.col(k) = (ddq_plus - ddq0) /
eps;
556 BOOST_CHECK(ddq_dq_fd.isApprox(
ddq_dq, sqrt(
eps)));
559 BOOST_CHECK(dacc_corrector_RF_dq.isApprox(dacc_corrector_RF_dq_fd, sqrt(
eps)));
560 BOOST_CHECK(dacc_corrector_LF_dq.isApprox(dacc_corrector_LF_dq_fd, sqrt(
eps)));
566 for (Eigen::DenseIndex k = 0; k <
model.nv; ++k)
568 Eigen::VectorXd v_plus(
v);
573 dacc_corrector_RF_dv_fd.col(k) = (constraint_datas_fd[0].contact_acceleration_error
577 dacc_corrector_LF_dv_fd.col(k) = (constraint_datas_fd[1].contact_acceleration_error.linear()
581 ddq_dv_fd.col(k) = (ddq_plus - ddq0) /
eps;
583 BOOST_CHECK(ddq_dv_fd.isApprox(
ddq_dv, sqrt(
eps)));
584 BOOST_CHECK(dacc_corrector_RF_dv.isApprox(dacc_corrector_RF_dv_fd, sqrt(
eps)));
585 BOOST_CHECK(dacc_corrector_LF_dv.isApprox(dacc_corrector_LF_dv_fd, sqrt(
eps)));
589 for (Eigen::DenseIndex k = 0; k <
model.nv; ++k)
591 Eigen::VectorXd tau_plus(
tau);
596 dacc_corrector_RF_dtau_fd.col(k) = (constraint_datas_fd[0].contact_acceleration_error
600 dacc_corrector_LF_dtau_fd.col(k) = (constraint_datas_fd[1].contact_acceleration_error.linear()
604 ddq_dtau_fd.col(k) = (ddq_plus - ddq0) /
eps;
606 BOOST_CHECK(ddq_dtau_fd.isApprox(
ddq_dtau, sqrt(
eps)));
607 BOOST_CHECK(dacc_corrector_RF_dtau_fd.isZero(sqrt(
eps)));
608 BOOST_CHECK(dacc_corrector_LF_dtau_fd.isZero(sqrt(
eps)));
613 using namespace Eigen;
620 model.lowerPositionLimit.head<3>().
fill(-1.);
621 model.upperPositionLimit.head<3>().
fill(1.);
624 VectorXd
v = VectorXd::Random(
model.nv);
625 VectorXd
tau = VectorXd::Random(
model.nv);
627 const std::string RF =
"rleg6_joint";
629 const std::string LF =
"lleg6_joint";
637 ci_RF.joint1_placement.setRandom();
638 ci_RF.corrector.Kp.array() =
KP;
639 ci_RF.corrector.Kd.array() =
KD;
647 const double mu0 = 0.;
653 data.M.triangularView<Eigen::StrictlyLower>() =
654 data.M.transpose().triangularView<Eigen::StrictlyLower>();
661 MatrixXd ddq_partial_dq_fd(
model.nv,
model.nv);
662 ddq_partial_dq_fd.setZero();
663 MatrixXd ddq_partial_dv_fd(
model.nv,
model.nv);
664 ddq_partial_dv_fd.setZero();
665 MatrixXd ddq_partial_dtau_fd(
model.nv,
model.nv);
666 ddq_partial_dtau_fd.setZero();
669 lambda_partial_dtau_fd.setZero();
671 lambda_partial_dq_fd.setZero();
673 lambda_partial_dv_fd.setZero();
677 const VectorXd lambda0 = data_fd.
lambda_c;
678 VectorXd v_eps(VectorXd::Zero(
model.nv));
679 VectorXd q_plus(
model.nq);
680 VectorXd ddq_plus(
model.nv);
684 const double alpha = 1e-8;
687 for (
int k = 0; k <
model.nv; ++k)
693 ddq_partial_dq_fd.col(k) = (ddq_plus - ddq0) /
alpha;
694 lambda_partial_dq_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
698 BOOST_CHECK(ddq_partial_dq_fd.isApprox(
data.ddq_dq, sqrt(
alpha)));
699 BOOST_CHECK(lambda_partial_dq_fd.isApprox(
data.dlambda_dq, sqrt(
alpha)));
702 for (
int k = 0; k <
model.nv; ++k)
707 ddq_partial_dv_fd.col(k) = (ddq_plus - ddq0) /
alpha;
708 lambda_partial_dv_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
712 BOOST_CHECK(ddq_partial_dv_fd.isApprox(
data.ddq_dv, sqrt(
alpha)));
713 BOOST_CHECK(lambda_partial_dv_fd.isApprox(
data.dlambda_dv, sqrt(
alpha)));
715 VectorXd tau_plus(
tau);
716 for (
int k = 0; k <
model.nv; ++k)
718 tau_plus[k] +=
alpha;
721 ddq_partial_dtau_fd.col(k) = (ddq_plus - ddq0) /
alpha;
722 lambda_partial_dtau_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
723 tau_plus[k] -=
alpha;
726 BOOST_CHECK(lambda_partial_dtau_fd.isApprox(
data.dlambda_dtau, sqrt(
alpha)));
727 BOOST_CHECK(ddq_partial_dtau_fd.isApprox(
data.ddq_dtau, sqrt(
alpha)));
732 using namespace Eigen;
739 model.lowerPositionLimit.head<3>().
fill(-1.);
740 model.upperPositionLimit.head<3>().
fill(1.);
743 VectorXd
v = VectorXd::Random(
model.nv);
744 VectorXd
tau = VectorXd::Random(
model.nv);
746 const std::string RF =
"rleg6_joint";
748 const std::string LF =
"lleg6_joint";
756 ci_RF.joint1_placement.setRandom();
757 ci_RF.corrector.Kp.array() =
KP;
758 ci_RF.corrector.Kd.array() =
KD;
766 const double mu0 = 1e-4;
774 data.M.triangularView<Eigen::StrictlyLower>() =
775 data.M.transpose().triangularView<Eigen::StrictlyLower>();
783 MatrixXd ddq_partial_dq_fd(
model.nv,
model.nv);
784 ddq_partial_dq_fd.setZero();
785 MatrixXd ddq_partial_dv_fd(
model.nv,
model.nv);
786 ddq_partial_dv_fd.setZero();
787 MatrixXd ddq_partial_dtau_fd(
model.nv,
model.nv);
788 ddq_partial_dtau_fd.setZero();
791 lambda_partial_dtau_fd.setZero();
793 lambda_partial_dq_fd.setZero();
795 lambda_partial_dv_fd.setZero();
799 BOOST_CHECK(a_res.isApprox(ddq0));
800 const VectorXd lambda0 = data_fd.
lambda_c;
806 VectorXd v_eps(VectorXd::Zero(
model.nv));
807 VectorXd q_plus(
model.nq);
808 VectorXd ddq_plus(
model.nv);
812 const double alpha = 1e-8;
815 for (
int k = 0; k <
model.nv; ++k)
821 ddq_partial_dq_fd.col(k) = (ddq_plus - ddq0) /
alpha;
822 lambda_partial_dq_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
826 BOOST_CHECK(ddq_partial_dq_fd.isApprox(
data.ddq_dq, sqrt(
alpha)));
827 BOOST_CHECK(lambda_partial_dq_fd.isApprox(
data.dlambda_dq, sqrt(
alpha)));
830 for (
int k = 0; k <
model.nv; ++k)
835 ddq_partial_dv_fd.col(k) = (ddq_plus - ddq0) /
alpha;
836 lambda_partial_dv_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
840 BOOST_CHECK(ddq_partial_dv_fd.isApprox(
data.ddq_dv, sqrt(
alpha)));
841 BOOST_CHECK(lambda_partial_dv_fd.isApprox(
data.dlambda_dv, sqrt(
alpha)));
843 VectorXd tau_plus(
tau);
844 for (
int k = 0; k <
model.nv; ++k)
846 tau_plus[k] +=
alpha;
849 ddq_partial_dtau_fd.col(k) = (ddq_plus - ddq0) /
alpha;
850 lambda_partial_dtau_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
851 tau_plus[k] -=
alpha;
854 BOOST_CHECK(lambda_partial_dtau_fd.isApprox(
data.dlambda_dtau, sqrt(
alpha)));
855 BOOST_CHECK(ddq_partial_dtau_fd.isApprox(
data.ddq_dtau, sqrt(
alpha)));
860 using namespace Eigen;
867 model.lowerPositionLimit.head<3>().
fill(-1.);
868 model.upperPositionLimit.head<3>().
fill(1.);
871 VectorXd
v = VectorXd::Random(
model.nv);
872 VectorXd
tau = VectorXd::Random(
model.nv);
874 const std::string RF =
"rleg6_joint";
876 const std::string LF =
"lleg6_joint";
884 ci_RF.corrector.Kp.array() =
KP;
885 ci_RF.corrector.Kd.array() =
KD;
886 ci_RF.joint1_placement.setRandom();
889 ci_RF.joint2_placement =
data.oMi[LF_id].inverse() *
data.oMi[RF_id] * ci_RF.joint1_placement;
898 const double mu0 = 1e-4;
906 data.M.triangularView<Eigen::StrictlyLower>() =
907 data.M.transpose().triangularView<Eigen::StrictlyLower>();
915 MatrixXd ddq_partial_dq_fd(
model.nv,
model.nv);
916 ddq_partial_dq_fd.setZero();
917 MatrixXd ddq_partial_dv_fd(
model.nv,
model.nv);
918 ddq_partial_dv_fd.setZero();
919 MatrixXd ddq_partial_dtau_fd(
model.nv,
model.nv);
920 ddq_partial_dtau_fd.setZero();
923 lambda_partial_dtau_fd.setZero();
925 lambda_partial_dq_fd.setZero();
927 lambda_partial_dv_fd.setZero();
931 BOOST_CHECK(a_res.isApprox(ddq0));
932 const VectorXd lambda0 = data_fd.
lambda_c;
938 VectorXd v_eps(VectorXd::Zero(
model.nv));
939 VectorXd q_plus(
model.nq);
940 VectorXd ddq_plus(
model.nv);
944 const double alpha = 1e-8;
947 for (
int k = 0; k <
model.nv; ++k)
953 ddq_partial_dq_fd.col(k) = (ddq_plus - ddq0) /
alpha;
954 lambda_partial_dq_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
958 BOOST_CHECK(ddq_partial_dq_fd.isApprox(
data.ddq_dq, sqrt(
alpha)));
959 BOOST_CHECK(lambda_partial_dq_fd.isApprox(
data.dlambda_dq, sqrt(
alpha)));
962 for (
int k = 0; k <
model.nv; ++k)
967 ddq_partial_dv_fd.col(k) = (ddq_plus - ddq0) /
alpha;
968 lambda_partial_dv_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
972 BOOST_CHECK(ddq_partial_dv_fd.isApprox(
data.ddq_dv, sqrt(
alpha)));
973 BOOST_CHECK(lambda_partial_dv_fd.isApprox(
data.dlambda_dv, sqrt(
alpha)));
975 VectorXd tau_plus(
tau);
976 for (
int k = 0; k <
model.nv; ++k)
978 tau_plus[k] +=
alpha;
981 ddq_partial_dtau_fd.col(k) = (ddq_plus - ddq0) /
alpha;
982 lambda_partial_dtau_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
983 tau_plus[k] -=
alpha;
986 BOOST_CHECK(lambda_partial_dtau_fd.isApprox(
data.dlambda_dtau, sqrt(
alpha)));
987 BOOST_CHECK(ddq_partial_dtau_fd.isApprox(
data.ddq_dtau, sqrt(
alpha)));
992 using namespace Eigen;
999 model.lowerPositionLimit.head<3>().
fill(-1.);
1000 model.upperPositionLimit.head<3>().
fill(1.);
1003 VectorXd
v = VectorXd::Random(
model.nv);
1004 VectorXd
tau = VectorXd::Random(
model.nv);
1006 const std::string RF =
"rleg6_joint";
1008 const std::string LF =
"lleg6_joint";
1017 const std::string RA =
"rarm5_joint";
1019 const std::string LA =
"larm5_joint";
1024 ci_closure.corrector.Kp.array() =
KP;
1025 ci_closure.corrector.Kd.array() =
KD;
1034 const double mu0 = 0.;
1040 data.M.triangularView<Eigen::StrictlyLower>() =
1041 data.M.transpose().triangularView<Eigen::StrictlyLower>();
1048 MatrixXd ddq_partial_dq_fd(
model.nv,
model.nv);
1049 ddq_partial_dq_fd.setZero();
1050 MatrixXd ddq_partial_dv_fd(
model.nv,
model.nv);
1051 ddq_partial_dv_fd.setZero();
1052 MatrixXd ddq_partial_dtau_fd(
model.nv,
model.nv);
1053 ddq_partial_dtau_fd.setZero();
1056 lambda_partial_dtau_fd.setZero();
1058 lambda_partial_dq_fd.setZero();
1060 lambda_partial_dv_fd.setZero();
1064 const VectorXd lambda0 = data_fd.
lambda_c;
1065 VectorXd v_eps(VectorXd::Zero(
model.nv));
1066 VectorXd q_plus(
model.nq);
1067 VectorXd ddq_plus(
model.nv);
1071 const double alpha = 1e-8;
1074 for (
int k = 0; k <
model.nv; ++k)
1080 ddq_partial_dq_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1081 lambda_partial_dq_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1085 BOOST_CHECK(ddq_partial_dq_fd.isApprox(
data.ddq_dq, sqrt(
alpha)));
1086 BOOST_CHECK(lambda_partial_dq_fd.isApprox(
data.dlambda_dq, sqrt(
alpha)));
1089 for (
int k = 0; k <
model.nv; ++k)
1094 ddq_partial_dv_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1095 lambda_partial_dv_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1099 BOOST_CHECK(ddq_partial_dv_fd.isApprox(
data.ddq_dv, sqrt(
alpha)));
1100 BOOST_CHECK(lambda_partial_dv_fd.isApprox(
data.dlambda_dv, sqrt(
alpha)));
1102 VectorXd tau_plus(
tau);
1103 for (
int k = 0; k <
model.nv; ++k)
1105 tau_plus[k] +=
alpha;
1108 ddq_partial_dtau_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1109 lambda_partial_dtau_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1110 tau_plus[k] -=
alpha;
1113 BOOST_CHECK(lambda_partial_dtau_fd.isApprox(
data.dlambda_dtau, sqrt(
alpha)));
1114 BOOST_CHECK(ddq_partial_dtau_fd.isApprox(
data.ddq_dtau, sqrt(
alpha)));
1125 const VectorXd & Kp,
1126 const VectorXd & Kd)
1134 const SE3 c1Mc2 = oMc1.actInv(oMc2);
1142 v_error = v1 - c1Mc2.act(v2);
1143 a_error = a1 - c1Mc2.act(a2) + v_error.cross(c1Mc2.act(v2));
1144 a_error.toVector() +=
1145 Kd.asDiagonal() * v_error.toVector() + Kp.asDiagonal() * (-
log6(c1Mc2).toVector());
1150 using namespace Eigen;
1157 model.lowerPositionLimit.head<3>().
fill(-1.);
1158 model.upperPositionLimit.head<3>().
fill(1.);
1161 VectorXd
v = VectorXd::Random(
model.nv);
1162 VectorXd
tau = VectorXd::Random(
model.nv);
1170 const std::string RA =
"rarm5_joint";
1175 ci_closure.corrector.Kp.array() =
KP;
1176 ci_closure.corrector.Kd.array() =
KD;
1185 const double mu0 = 0.;
1189 const VectorXd ddq0 =
1196 const VectorXd
a =
data.ddq;
1197 data.M.triangularView<Eigen::StrictlyLower>() =
1198 data.M.transpose().triangularView<Eigen::StrictlyLower>();
1204 model, ci_closure,
q,
v, ddq0, v_error, a_error, ci_closure.corrector.Kp,
1205 ci_closure.corrector.Kd);
1206 BOOST_CHECK(a_error.isZero());
1209 const VectorXd constraint_acceleration_error = -
data.primal_rhs_contact.head(
constraint_dim);
1210 BOOST_CHECK(constraint_velocity_error.isApprox(v_error));
1211 BOOST_CHECK(constraint_acceleration_error.isApprox(a_error.toVector() -
data.dac_da * ddq0));
1213 const VectorXd lambda0 =
data.lambda_c;
1214 VectorXd v_eps(VectorXd::Zero(
model.nv));
1215 VectorXd q_plus(
model.nq);
1216 VectorXd ddq_plus(
model.nv);
1218 const double alpha = 1e-8;
1221 MatrixXd ddq_partial_dq_fd(
model.nv,
model.nv);
1222 ddq_partial_dq_fd.setZero();
1224 lambda_partial_dq_fd.setZero();
1225 MatrixXd dconstraint_velocity_error_dq_fd(6,
model.nv);
1226 dconstraint_velocity_error_dq_fd.setZero();
1227 MatrixXd dconstraint_velocity_error_dq2_fd(6,
model.nv);
1228 dconstraint_velocity_error_dq2_fd.setZero();
1229 MatrixXd dconstraint_acceleration_error_dq_fd(6,
model.nv);
1230 dconstraint_acceleration_error_dq_fd.setZero();
1233 for (
int k = 0; k <
model.nv; ++k)
1240 ddq_partial_dq_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1241 lambda_partial_dq_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1243 Motion v_error_plus, a_error_plus;
1245 model, ci_closure, q_plus,
v, ddq0, v_error_plus, a_error_plus, ci_closure.corrector.Kp,
1246 ci_closure.corrector.Kd);
1248 const Motion & constraint_velocity_error_plus = constraint_data_fd[0].contact_velocity_error;
1249 const VectorXd constraint_acceleration_error_plus =
1251 dconstraint_velocity_error_dq_fd.col(k) =
1252 (constraint_velocity_error_plus - constraint_velocity_error).toVector() /
alpha;
1253 dconstraint_velocity_error_dq2_fd.col(k) = (v_error_plus - v_error).toVector() /
alpha;
1254 dconstraint_acceleration_error_dq_fd.col(k) = (a_error_plus - a_error).toVector() /
alpha;
1259 BOOST_CHECK(dconstraint_velocity_error_dq_fd.isApprox(
data.dvc_dq, sqrt(
alpha)));
1260 BOOST_CHECK(dconstraint_acceleration_error_dq_fd.isApprox(
data.dac_dq, sqrt(
alpha)));
1261 BOOST_CHECK(ddq_partial_dq_fd.isApprox(
data.ddq_dq, sqrt(
alpha)));
1262 BOOST_CHECK(lambda_partial_dq_fd.isApprox(
data.dlambda_dq, sqrt(
alpha)));
1265 MatrixXd ddq_partial_dv_fd(
model.nv,
model.nv);
1266 ddq_partial_dv_fd.setZero();
1268 lambda_partial_dv_fd.setZero();
1269 MatrixXd dconstraint_velocity_error_dv_fd(6,
model.nv);
1270 dconstraint_velocity_error_dv_fd.setZero();
1271 MatrixXd dconstraint_acceleration_error_dv_fd(6,
model.nv);
1272 dconstraint_acceleration_error_dv_fd.setZero();
1275 for (
int k = 0; k <
model.nv; ++k)
1281 ddq_partial_dv_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1282 lambda_partial_dv_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1284 Motion v_error_plus, a_error_plus;
1286 model, ci_closure,
q, v_plus, ddq0, v_error_plus, a_error_plus, ci_closure.corrector.Kp,
1287 ci_closure.corrector.Kd);
1289 const Motion & constraint_velocity_error_plus = constraint_data_fd[0].contact_velocity_error;
1290 dconstraint_velocity_error_dv_fd.col(k) =
1291 (constraint_velocity_error_plus - constraint_velocity_error).toVector() /
alpha;
1292 dconstraint_acceleration_error_dv_fd.col(k) = (a_error_plus - a_error).toVector() /
alpha;
1297 BOOST_CHECK(dconstraint_velocity_error_dv_fd.isApprox(
data.dac_da, sqrt(
alpha)));
1298 BOOST_CHECK(dconstraint_acceleration_error_dv_fd.isApprox(
data.dac_dv, sqrt(
alpha)));
1299 BOOST_CHECK(ddq_partial_dv_fd.isApprox(
data.ddq_dv, sqrt(
alpha)));
1300 BOOST_CHECK(lambda_partial_dv_fd.isApprox(
data.dlambda_dv, sqrt(
alpha)));
1303 MatrixXd ddq_partial_dtau_fd(
model.nv,
model.nv);
1304 ddq_partial_dtau_fd.setZero();
1306 lambda_partial_dtau_fd.setZero();
1308 VectorXd tau_plus(
tau);
1309 for (
int k = 0; k <
model.nv; ++k)
1311 tau_plus[k] +=
alpha;
1314 ddq_partial_dtau_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1315 lambda_partial_dtau_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1316 tau_plus[k] -=
alpha;
1319 BOOST_CHECK(lambda_partial_dtau_fd.isApprox(
data.dlambda_dtau, sqrt(
alpha)));
1320 BOOST_CHECK(ddq_partial_dtau_fd.isApprox(
data.ddq_dtau, sqrt(
alpha)));
1325 using namespace Eigen;
1332 model.lowerPositionLimit.head<3>().
fill(-1.);
1333 model.upperPositionLimit.head<3>().
fill(1.);
1336 VectorXd
v = VectorXd::Random(
model.nv);
1337 VectorXd
tau = VectorXd::Random(
model.nv);
1339 const std::string RF =
"rleg6_joint";
1340 const std::string LF =
"lleg6_joint";
1347 const std::string RA =
"rarm5_joint";
1349 const std::string LA =
"larm5_joint";
1355 ci_closure.corrector.Kp.array() =
KP;
1356 ci_closure.corrector.Kd.array() =
KD;
1366 const double mu0 = 0.;
1370 const VectorXd ddq0 =
1372 const VectorXd lambda0 =
data.lambda_c;
1379 model, ci_closure,
q,
v, ddq0, v_error, a_error, ci_closure.corrector.Kp,
1380 ci_closure.corrector.Kd);
1381 BOOST_CHECK(a_error.isZero());
1384 const VectorXd constraint_acceleration_error = -
data.primal_rhs_contact.head(
constraint_dim);
1385 BOOST_CHECK(constraint_velocity_error.isApprox(v_error));
1386 BOOST_CHECK(constraint_acceleration_error.isApprox(a_error.toVector() -
data.dac_da * ddq0));
1391 VectorXd v_eps(VectorXd::Zero(
model.nv));
1392 VectorXd q_plus(
model.nq);
1393 VectorXd ddq_plus(
model.nv);
1397 const double alpha = 1e-8;
1400 MatrixXd ddq_partial_dq_fd(
model.nv,
model.nv);
1401 ddq_partial_dq_fd.setZero();
1403 lambda_partial_dq_fd.setZero();
1404 MatrixXd dconstraint_velocity_error_dq_fd(6,
model.nv);
1405 dconstraint_velocity_error_dq_fd.setZero();
1406 MatrixXd dconstraint_acceleration_error_dq_fd(6,
model.nv);
1407 dconstraint_acceleration_error_dq_fd.setZero();
1409 for (
int k = 0; k <
model.nv; ++k)
1416 ddq_partial_dq_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1417 lambda_partial_dq_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1419 Motion v_error_plus, a_error_plus;
1421 model, ci_closure, q_plus,
v, ddq0, v_error_plus, a_error_plus, ci_closure.corrector.Kp,
1422 ci_closure.corrector.Kd);
1424 const Motion & constraint_velocity_error_plus = constraint_data_fd[0].contact_velocity_error;
1425 const VectorXd constraint_acceleration_error_plus =
1427 dconstraint_velocity_error_dq_fd.col(k) =
1428 (constraint_velocity_error_plus - constraint_velocity_error).toVector() /
alpha;
1429 dconstraint_acceleration_error_dq_fd.col(k) = (a_error_plus - a_error).toVector() /
alpha;
1434 BOOST_CHECK(dconstraint_velocity_error_dq_fd.isApprox(
data.dvc_dq, sqrt(
alpha)));
1435 BOOST_CHECK(dconstraint_acceleration_error_dq_fd.isApprox(
data.dac_dq, sqrt(
alpha)));
1437 BOOST_CHECK(ddq_partial_dq_fd.isApprox(
data.ddq_dq, sqrt(
alpha)));
1438 BOOST_CHECK(lambda_partial_dq_fd.isApprox(
data.dlambda_dq, sqrt(
alpha)));
1441 MatrixXd ddq_partial_dv_fd(
model.nv,
model.nv);
1442 ddq_partial_dv_fd.setZero();
1444 lambda_partial_dv_fd.setZero();
1445 MatrixXd dconstraint_velocity_error_dv_fd(6,
model.nv);
1446 dconstraint_velocity_error_dv_fd.setZero();
1447 MatrixXd dconstraint_acceleration_error_dv_fd(6,
model.nv);
1448 dconstraint_acceleration_error_dv_fd.setZero();
1451 for (
int k = 0; k <
model.nv; ++k)
1457 ddq_partial_dv_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1458 lambda_partial_dv_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1460 Motion v_error_plus, a_error_plus;
1462 model, ci_closure,
q, v_plus, ddq0, v_error_plus, a_error_plus, ci_closure.corrector.Kp,
1463 ci_closure.corrector.Kd);
1465 const Motion & constraint_velocity_error_plus = constraint_data_fd[0].contact_velocity_error;
1466 dconstraint_velocity_error_dv_fd.col(k) =
1467 (constraint_velocity_error_plus - constraint_velocity_error).toVector() /
alpha;
1468 dconstraint_acceleration_error_dv_fd.col(k) = (a_error_plus - a_error).toVector() /
alpha;
1473 BOOST_CHECK(dconstraint_velocity_error_dv_fd.isApprox(
data.dac_da, sqrt(
alpha)));
1474 BOOST_CHECK(dconstraint_acceleration_error_dv_fd.isApprox(
data.dac_dv, sqrt(
alpha)));
1476 BOOST_CHECK(ddq_partial_dv_fd.isApprox(
data.ddq_dv, sqrt(
alpha)));
1477 BOOST_CHECK(lambda_partial_dv_fd.isApprox(
data.dlambda_dv, sqrt(
alpha)));
1480 MatrixXd ddq_partial_dtau_fd(
model.nv,
model.nv);
1481 ddq_partial_dtau_fd.setZero();
1483 lambda_partial_dtau_fd.setZero();
1485 VectorXd tau_plus(
tau);
1486 for (
int k = 0; k <
model.nv; ++k)
1488 tau_plus[k] +=
alpha;
1491 ddq_partial_dtau_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1492 lambda_partial_dtau_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1493 tau_plus[k] -=
alpha;
1496 BOOST_CHECK(lambda_partial_dtau_fd.isApprox(
data.dlambda_dtau, sqrt(
alpha)));
1497 BOOST_CHECK(ddq_partial_dtau_fd.isApprox(
data.ddq_dtau, sqrt(
alpha)));
1501 test_constraint_dynamics_derivatives_LOCAL_WORL_ALIGNED_6D_loop_closure_j1j2_fd)
1503 using namespace Eigen;
1510 model.lowerPositionLimit.head<3>().
fill(-1.);
1511 model.upperPositionLimit.head<3>().
fill(1.);
1514 VectorXd
v = VectorXd::Random(
model.nv);
1515 VectorXd
tau = VectorXd::Random(
model.nv);
1517 const std::string RF =
"rleg6_joint";
1519 const std::string LF =
"lleg6_joint";
1528 const std::string RA =
"rarm5_joint";
1530 const std::string LA =
"larm5_joint";
1535 ci_closure.corrector.Kp.array() = 0.;
1536 ci_closure.corrector.Kd.array() = 0;
1546 const double mu0 = 0.;
1552 data.M.triangularView<Eigen::StrictlyLower>() =
1553 data.M.transpose().triangularView<Eigen::StrictlyLower>();
1560 MatrixXd ddq_partial_dq_fd(
model.nv,
model.nv);
1561 ddq_partial_dq_fd.setZero();
1562 MatrixXd ddq_partial_dv_fd(
model.nv,
model.nv);
1563 ddq_partial_dv_fd.setZero();
1564 MatrixXd ddq_partial_dtau_fd(
model.nv,
model.nv);
1565 ddq_partial_dtau_fd.setZero();
1568 lambda_partial_dtau_fd.setZero();
1570 lambda_partial_dq_fd.setZero();
1572 lambda_partial_dv_fd.setZero();
1576 const VectorXd lambda0 = data_fd.
lambda_c;
1577 VectorXd v_eps(VectorXd::Zero(
model.nv));
1578 VectorXd q_plus(
model.nq);
1579 VectorXd ddq_plus(
model.nv);
1583 const double alpha = 1e-8;
1586 for (
int k = 0; k <
model.nv; ++k)
1592 ddq_partial_dq_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1593 lambda_partial_dq_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1597 BOOST_CHECK(ddq_partial_dq_fd.isApprox(
data.ddq_dq, sqrt(
alpha)));
1598 BOOST_CHECK(lambda_partial_dq_fd.isApprox(
data.dlambda_dq, sqrt(
alpha)));
1601 for (
int k = 0; k <
model.nv; ++k)
1606 ddq_partial_dv_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1607 lambda_partial_dv_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1611 BOOST_CHECK(ddq_partial_dv_fd.isApprox(
data.ddq_dv, sqrt(
alpha)));
1612 BOOST_CHECK(lambda_partial_dv_fd.isApprox(
data.dlambda_dv, sqrt(
alpha)));
1614 VectorXd tau_plus(
tau);
1615 for (
int k = 0; k <
model.nv; ++k)
1617 tau_plus[k] +=
alpha;
1620 ddq_partial_dtau_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1621 lambda_partial_dtau_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1622 tau_plus[k] -=
alpha;
1625 BOOST_CHECK(lambda_partial_dtau_fd.isApprox(
data.dlambda_dtau, sqrt(
alpha)));
1626 BOOST_CHECK(ddq_partial_dtau_fd.isApprox(
data.ddq_dtau, sqrt(
alpha)));
1631 using namespace Eigen;
1638 model.lowerPositionLimit.head<3>().
fill(-1.);
1639 model.upperPositionLimit.head<3>().
fill(1.);
1642 VectorXd
v = VectorXd::Random(
model.nv);
1643 VectorXd
tau = VectorXd::Random(
model.nv);
1645 const std::string RF =
"rleg6_joint";
1647 const std::string LF =
"lleg6_joint";
1656 const std::string RA =
"rarm5_joint";
1658 const std::string LA =
"larm5_joint";
1663 ci_closure.corrector.Kp.array() =
KP;
1664 ci_closure.corrector.Kd.array() =
KD;
1673 const double mu0 = 0.;
1679 data.M.triangularView<Eigen::StrictlyLower>() =
1680 data.M.transpose().triangularView<Eigen::StrictlyLower>();
1687 MatrixXd ddq_partial_dq_fd(
model.nv,
model.nv);
1688 ddq_partial_dq_fd.setZero();
1689 MatrixXd ddq_partial_dv_fd(
model.nv,
model.nv);
1690 ddq_partial_dv_fd.setZero();
1691 MatrixXd ddq_partial_dtau_fd(
model.nv,
model.nv);
1692 ddq_partial_dtau_fd.setZero();
1695 lambda_partial_dtau_fd.setZero();
1697 lambda_partial_dq_fd.setZero();
1699 lambda_partial_dv_fd.setZero();
1703 const VectorXd lambda0 = data_fd.
lambda_c;
1704 VectorXd v_eps(VectorXd::Zero(
model.nv));
1705 VectorXd q_plus(
model.nq);
1706 VectorXd ddq_plus(
model.nv);
1710 const double alpha = 1e-8;
1713 for (
int k = 0; k <
model.nv; ++k)
1719 ddq_partial_dq_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1720 lambda_partial_dq_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1724 BOOST_CHECK(ddq_partial_dq_fd.isApprox(
data.ddq_dq, sqrt(
alpha)));
1725 BOOST_CHECK(lambda_partial_dq_fd.isApprox(
data.dlambda_dq, sqrt(
alpha)));
1727 for (
int k = 0; k <
model.nv; ++k)
1732 ddq_partial_dv_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1733 lambda_partial_dv_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1737 BOOST_CHECK(ddq_partial_dv_fd.isApprox(
data.ddq_dv, sqrt(
alpha)));
1738 BOOST_CHECK(lambda_partial_dv_fd.isApprox(
data.dlambda_dv, sqrt(
alpha)));
1740 VectorXd tau_plus(
tau);
1741 for (
int k = 0; k <
model.nv; ++k)
1743 tau_plus[k] +=
alpha;
1746 ddq_partial_dtau_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1747 lambda_partial_dtau_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1748 tau_plus[k] -=
alpha;
1751 BOOST_CHECK(lambda_partial_dtau_fd.isApprox(
data.dlambda_dtau, sqrt(
alpha)));
1752 BOOST_CHECK(ddq_partial_dtau_fd.isApprox(
data.ddq_dtau, sqrt(
alpha)));
1756 test_constraint_dynamics_derivatives_LOCAL_WORLD_ALIGNED_3D_loop_closure_j1j2_fd)
1758 using namespace Eigen;
1765 model.lowerPositionLimit.head<3>().
fill(-1.);
1766 model.upperPositionLimit.head<3>().
fill(1.);
1769 VectorXd
v = VectorXd::Random(
model.nv);
1770 VectorXd
tau = VectorXd::Random(
model.nv);
1772 const std::string RF =
"rleg6_joint";
1774 const std::string LF =
"lleg6_joint";
1783 const std::string RA =
"rarm5_joint";
1785 const std::string LA =
"larm5_joint";
1791 ci_closure.corrector.Kp.array() =
KP;
1792 ci_closure.corrector.Kd.array() =
KD;
1802 const double mu0 = 0.;
1808 data.M.triangularView<Eigen::StrictlyLower>() =
1809 data.M.transpose().triangularView<Eigen::StrictlyLower>();
1816 MatrixXd ddq_partial_dq_fd(
model.nv,
model.nv);
1817 ddq_partial_dq_fd.setZero();
1818 MatrixXd ddq_partial_dv_fd(
model.nv,
model.nv);
1819 ddq_partial_dv_fd.setZero();
1820 MatrixXd ddq_partial_dtau_fd(
model.nv,
model.nv);
1821 ddq_partial_dtau_fd.setZero();
1824 lambda_partial_dtau_fd.setZero();
1826 lambda_partial_dq_fd.setZero();
1828 lambda_partial_dv_fd.setZero();
1832 const VectorXd lambda0 = data_fd.
lambda_c;
1833 VectorXd v_eps(VectorXd::Zero(
model.nv));
1834 VectorXd q_plus(
model.nq);
1835 VectorXd ddq_plus(
model.nv);
1839 const double alpha = 1e-8;
1842 for (
int k = 0; k <
model.nv; ++k)
1848 ddq_partial_dq_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1849 lambda_partial_dq_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1853 BOOST_CHECK(ddq_partial_dq_fd.isApprox(
data.ddq_dq, sqrt(
alpha)));
1854 BOOST_CHECK(lambda_partial_dq_fd.isApprox(
data.dlambda_dq, sqrt(
alpha)));
1857 for (
int k = 0; k <
model.nv; ++k)
1862 ddq_partial_dv_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1863 lambda_partial_dv_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1867 BOOST_CHECK(ddq_partial_dv_fd.isApprox(
data.ddq_dv, sqrt(
alpha)));
1868 BOOST_CHECK(lambda_partial_dv_fd.isApprox(
data.dlambda_dv, sqrt(
alpha)));
1870 VectorXd tau_plus(
tau);
1871 for (
int k = 0; k <
model.nv; ++k)
1873 tau_plus[k] +=
alpha;
1876 ddq_partial_dtau_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1877 lambda_partial_dtau_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1878 tau_plus[k] -=
alpha;
1881 BOOST_CHECK(lambda_partial_dtau_fd.isApprox(
data.dlambda_dtau, sqrt(
alpha)));
1882 BOOST_CHECK(ddq_partial_dtau_fd.isApprox(
data.ddq_dtau, sqrt(
alpha)));
1887 using namespace Eigen;
1894 model.lowerPositionLimit.head<3>().
fill(-1.);
1895 model.upperPositionLimit.head<3>().
fill(1.);
1898 VectorXd
v = VectorXd::Random(
model.nv);
1899 VectorXd
tau = VectorXd::Random(
model.nv);
1901 const std::string RF =
"rleg6_joint";
1903 const std::string LF =
"lleg6_joint";
1911 ci_LF.corrector.Kp.array() = 0;
1912 ci_LF.corrector.Kd.array() =
KD;
1914 ci_LF.joint1_placement.setRandom();
1922 const double mu0 = 0.;
1928 data.M.triangularView<Eigen::StrictlyLower>() =
1929 data.M.transpose().triangularView<Eigen::StrictlyLower>();
1936 MatrixXd ddq_partial_dq_fd(
model.nv,
model.nv);
1937 ddq_partial_dq_fd.setZero();
1938 MatrixXd ddq_partial_dv_fd(
model.nv,
model.nv);
1939 ddq_partial_dv_fd.setZero();
1940 MatrixXd ddq_partial_dtau_fd(
model.nv,
model.nv);
1941 ddq_partial_dtau_fd.setZero();
1944 lambda_partial_dtau_fd.setZero();
1946 lambda_partial_dq_fd.setZero();
1948 lambda_partial_dv_fd.setZero();
1952 const VectorXd lambda0 = data_fd.
lambda_c;
1953 VectorXd v_eps(VectorXd::Zero(
model.nv));
1954 VectorXd q_plus(
model.nq);
1955 VectorXd ddq_plus(
model.nv);
1959 const double alpha = 1e-8;
1960 for (
int k = 0; k <
model.nv; ++k)
1966 ddq_partial_dq_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1967 lambda_partial_dq_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1971 BOOST_CHECK(ddq_partial_dq_fd.isApprox(
data.ddq_dq, sqrt(
alpha)));
1972 BOOST_CHECK(lambda_partial_dq_fd.isApprox(
data.dlambda_dq, sqrt(
alpha)));
1975 for (
int k = 0; k <
model.nv; ++k)
1980 ddq_partial_dv_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1981 lambda_partial_dv_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1985 BOOST_CHECK(ddq_partial_dv_fd.isApprox(
data.ddq_dv, sqrt(
alpha)));
1986 BOOST_CHECK(lambda_partial_dv_fd.isApprox(
data.dlambda_dv, sqrt(
alpha)));
1988 VectorXd tau_plus(
tau);
1989 for (
int k = 0; k <
model.nv; ++k)
1991 tau_plus[k] +=
alpha;
1994 ddq_partial_dtau_fd.col(k) = (ddq_plus - ddq0) /
alpha;
1995 lambda_partial_dtau_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
1996 tau_plus[k] -=
alpha;
1999 BOOST_CHECK(lambda_partial_dtau_fd.isApprox(
data.dlambda_dtau, sqrt(
alpha)));
2000 BOOST_CHECK(ddq_partial_dtau_fd.isApprox(
data.ddq_dtau, sqrt(
alpha)));
2005 using namespace Eigen;
2012 model.lowerPositionLimit.head<3>().
fill(-1.);
2013 model.upperPositionLimit.head<3>().
fill(1.);
2016 VectorXd
v = VectorXd::Random(
model.nv);
2017 VectorXd
tau = VectorXd::Random(
model.nv);
2019 const std::string RF =
"rleg6_joint";
2021 const std::string LF =
"lleg6_joint";
2029 ci_RF.corrector.Kp.array() =
KP;
2030 ci_RF.corrector.Kd.array() =
KD;
2031 ci_RF.joint1_placement.setRandom();
2039 const double mu0 = 0.;
2045 data.M.triangularView<Eigen::StrictlyLower>() =
2046 data.M.transpose().triangularView<Eigen::StrictlyLower>();
2053 MatrixXd ddq_partial_dq_fd(
model.nv,
model.nv);
2054 ddq_partial_dq_fd.setZero();
2055 MatrixXd ddq_partial_dv_fd(
model.nv,
model.nv);
2056 ddq_partial_dv_fd.setZero();
2057 MatrixXd ddq_partial_dtau_fd(
model.nv,
model.nv);
2058 ddq_partial_dtau_fd.setZero();
2061 lambda_partial_dtau_fd.setZero();
2063 lambda_partial_dq_fd.setZero();
2065 lambda_partial_dv_fd.setZero();
2069 const VectorXd lambda0 = data_fd.
lambda_c;
2070 VectorXd v_eps(VectorXd::Zero(
model.nv));
2071 VectorXd q_plus(
model.nq);
2072 VectorXd ddq_plus(
model.nv);
2076 const double alpha = 1e-8;
2077 for (
int k = 0; k <
model.nv; ++k)
2083 ddq_partial_dq_fd.col(k) = (ddq_plus - ddq0) /
alpha;
2084 lambda_partial_dq_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
2088 BOOST_CHECK(ddq_partial_dq_fd.isApprox(
data.ddq_dq, sqrt(
alpha)));
2089 BOOST_CHECK(lambda_partial_dq_fd.isApprox(
data.dlambda_dq, sqrt(
alpha)));
2092 for (
int k = 0; k <
model.nv; ++k)
2097 ddq_partial_dv_fd.col(k) = (ddq_plus - ddq0) /
alpha;
2098 lambda_partial_dv_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
2102 BOOST_CHECK(ddq_partial_dv_fd.isApprox(
data.ddq_dv, sqrt(
alpha)));
2103 BOOST_CHECK(lambda_partial_dv_fd.isApprox(
data.dlambda_dv, sqrt(
alpha)));
2105 VectorXd tau_plus(
tau);
2106 for (
int k = 0; k <
model.nv; ++k)
2108 tau_plus[k] +=
alpha;
2111 ddq_partial_dtau_fd.col(k) = (ddq_plus - ddq0) /
alpha;
2112 lambda_partial_dtau_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
2113 tau_plus[k] -=
alpha;
2116 BOOST_CHECK(lambda_partial_dtau_fd.isApprox(
data.dlambda_dtau, sqrt(
alpha)));
2117 BOOST_CHECK(ddq_partial_dtau_fd.isApprox(
data.ddq_dtau, sqrt(
alpha)));
2122 using namespace Eigen;
2129 model.lowerPositionLimit.head<3>().
fill(-1.);
2130 model.upperPositionLimit.head<3>().
fill(1.);
2133 VectorXd
v = VectorXd::Random(
model.nv);
2134 VectorXd
tau = VectorXd::Random(
model.nv);
2136 const std::string RF =
"rleg6_joint";
2138 const std::string LF =
"lleg6_joint";
2140 const std::string RH =
"rarm6_joint";
2142 const std::string LH =
"larm6_joint";
2150 ci_LF.corrector.Kp.array() = 0;
2151 ci_LF.corrector.Kd.array() =
KD;
2152 ci_LF.joint1_placement.setRandom();
2156 ci_RF.corrector.Kp.array() =
KP;
2157 ci_RF.corrector.Kd.array() =
KD;
2158 ci_RF.joint1_placement.setRandom();
2163 ci_LH.corrector.Kp.array() =
KP;
2164 ci_LH.corrector.Kd.array() =
KD;
2165 ci_LH.joint1_placement.setRandom();
2169 ci_RH.corrector.Kp.array() =
KP;
2170 ci_RH.corrector.Kd.array() =
KD;
2171 ci_RH.joint1_placement.setRandom();
2179 const double mu0 = 0.;
2185 data.M.triangularView<Eigen::StrictlyLower>() =
2186 data.M.transpose().triangularView<Eigen::StrictlyLower>();
2193 MatrixXd ddq_partial_dq_fd(
model.nv,
model.nv);
2194 ddq_partial_dq_fd.setZero();
2195 MatrixXd ddq_partial_dv_fd(
model.nv,
model.nv);
2196 ddq_partial_dv_fd.setZero();
2197 MatrixXd ddq_partial_dtau_fd(
model.nv,
model.nv);
2198 ddq_partial_dtau_fd.setZero();
2201 lambda_partial_dtau_fd.setZero();
2203 lambda_partial_dq_fd.setZero();
2205 lambda_partial_dv_fd.setZero();
2209 const VectorXd lambda0 = data_fd.
lambda_c;
2210 VectorXd v_eps(VectorXd::Zero(
model.nv));
2211 VectorXd q_plus(
model.nq);
2212 VectorXd ddq_plus(
model.nv);
2216 const double alpha = 1e-8;
2219 const Eigen::MatrixXd Jc =
data.dac_da;
2220 const Eigen::MatrixXd Jc_ref =
2223 BOOST_CHECK(Jc.isApprox(Jc_ref));
2225 const Eigen::MatrixXd JMinv = Jc *
data.Minv;
2226 const Eigen::MatrixXd dac_dq =
data.dac_dq;
2231 Eigen::DenseIndex row_id = 0;
2238 const Eigen::DenseIndex
size =
cmodel.size();
2243 contact_acc0.segment<3>(row_id) =
2244 contact_acc.linear() - cdata.contact_acceleration_error.linear();
2246 contact_acc0.segment<6>(row_id) =
2247 contact_acc.toVector() - cdata.contact_acceleration_error.toVector();
2252 for (
int k = 0; k <
model.nv; ++k)
2259 ddq_partial_dq_fd.col(k) = (ddq_plus - ddq0) /
alpha;
2260 lambda_partial_dq_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
2263 Eigen::DenseIndex row_id = 0;
2269 const Eigen::DenseIndex
size =
cmodel.size();
2274 contact_acc_plus.segment<3>(row_id) =
2275 contact_acc.linear() - cdata.contact_acceleration_error.linear();
2277 contact_acc_plus.segment<6>(row_id) =
2278 contact_acc.toVector() - cdata.contact_acceleration_error.toVector();
2283 dac_dq_fd.col(k) = (contact_acc_plus - contact_acc0) /
alpha;
2288 BOOST_CHECK(dac_dq_fd.isApprox(dac_dq, 1e-6));
2290 BOOST_CHECK(ddq_partial_dq_fd.isApprox(
data.ddq_dq, sqrt(
alpha)));
2291 BOOST_CHECK(lambda_partial_dq_fd.isApprox(
data.dlambda_dq, sqrt(
alpha)));
2294 for (
int k = 0; k <
model.nv; ++k)
2299 ddq_partial_dv_fd.col(k) = (ddq_plus - ddq0) /
alpha;
2300 lambda_partial_dv_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
2304 BOOST_CHECK(ddq_partial_dv_fd.isApprox(
data.ddq_dv, sqrt(
alpha)));
2305 BOOST_CHECK(lambda_partial_dv_fd.isApprox(
data.dlambda_dv, sqrt(
alpha)));
2307 VectorXd tau_plus(
tau);
2308 for (
int k = 0; k <
model.nv; ++k)
2310 tau_plus[k] +=
alpha;
2313 ddq_partial_dtau_fd.col(k) = (ddq_plus - ddq0) /
alpha;
2314 lambda_partial_dtau_fd.col(k) = (data_fd.
lambda_c - lambda0) /
alpha;
2315 tau_plus[k] -=
alpha;
2318 BOOST_CHECK(lambda_partial_dtau_fd.isApprox(
data.dlambda_dtau, sqrt(
alpha)));
2319 BOOST_CHECK(ddq_partial_dtau_fd.isApprox(
data.ddq_dtau, sqrt(
alpha)));
2324 using namespace Eigen;
2331 model.lowerPositionLimit.head<3>().
fill(-1.);
2332 model.upperPositionLimit.head<3>().
fill(1.);
2335 VectorXd
v = VectorXd::Random(
model.nv);
2336 VectorXd
tau = VectorXd::Random(
model.nv);
2338 const std::string RH =
"rarm6_joint";
2340 const std::string LH =
"larm6_joint";
2348 ci_RH.corrector.Kp.array() = 0;
2349 ci_RH.corrector.Kd.array() = 0;
2358 const double mu0 = 0.;
2364 data.M.triangularView<Eigen::StrictlyLower>() =
2365 data.M.transpose().triangularView<Eigen::StrictlyLower>();
2373 const VectorXd lambda0 = data_fd.
lambda_c;
2374 VectorXd v_eps(VectorXd::Zero(
model.nv));
2375 VectorXd q_plus(
model.nq);
2376 VectorXd ddq_plus(
model.nv);
2380 const double alpha = 1e-8;
2383 const Eigen::MatrixXd Jc =
data.dac_da;
2384 const Eigen::MatrixXd Jc_ref =
2387 BOOST_CHECK(Jc.isApprox(Jc_ref));
2389 const Eigen::MatrixXd JMinv = Jc *
data.Minv;
2390 const Eigen::MatrixXd dac_dq =
data.dac_dq;
2394 Eigen::DenseIndex row_id = 0;
2401 const Eigen::DenseIndex
size =
cmodel.size();
2406 contact_acc0.segment<3>(row_id) = contact_acc.linear();
2408 contact_acc0.segment<6>(row_id) = contact_acc.toVector();
2413 for (
int k = 0; k <
model.nv; ++k)
2421 Eigen::DenseIndex row_id = 0;
2427 const Eigen::DenseIndex
size =
cmodel.size();
2432 contact_acc_plus.segment<3>(row_id) = contact_acc.linear();
2434 contact_acc_plus.segment<6>(row_id) = contact_acc.toVector();
2439 dac_dq_fd.col(k) = (contact_acc_plus - contact_acc0) /
alpha;
2444 BOOST_CHECK(dac_dq_fd.isApprox(dac_dq, 2e-6));
2450 using namespace Eigen;
2457 model.lowerPositionLimit.head<3>().
fill(-1.);
2458 model.upperPositionLimit.head<3>().
fill(1.);
2461 VectorXd
v = VectorXd::Random(
model.nv);
2462 VectorXd
tau = VectorXd::Random(
model.nv);
2464 const std::string RF =
"rleg6_joint";
2466 const std::string LF =
"lleg6_joint";
2476 ci_LF.corrector.Kp.array() =
KP;
2477 ci_LF.corrector.Kd.array() =
KD;
2478 ci_RF.corrector.Kp.array() =
KP;
2479 ci_RF.corrector.Kd.array() =
KD;
2489 const double mu0 = 0.;
2500 v = VectorXd::Random(
model.nv);
2514 const double alpha = 1e-12;
2524 #ifdef PINOCCHIO_WITH_SDFORMAT
2526 BOOST_AUTO_TEST_CASE_EXPECTED_FAILURES(test_constraint_dynamics_derivatives_cassie_proximal, 6)
2532 + std::string(
"/example-robot-data/robots/cassie_description/robots/cassie.sdf");
2535 + std::string(
"/example-robot-data/robots/cassie_description/srdf/cassie_v2.srdf");
2545 Eigen::VectorXd
q =
model.referenceConfigurations[
"standing"];
2547 VectorXd
v = VectorXd::Random(
model.nv);
2548 VectorXd
tau = VectorXd::Random(
model.nv);
2550 const double mu0 = 1e-5;
2567 data.M.triangularView<Eigen::StrictlyLower>() =
2568 data.M.transpose().triangularView<Eigen::StrictlyLower>();
2573 MatrixXd ddq_partial_dq_fd(
model.nv,
model.nv);
2574 ddq_partial_dq_fd.setZero();
2575 MatrixXd ddq_partial_dv_fd(
model.nv,
model.nv);
2576 ddq_partial_dv_fd.setZero();
2577 MatrixXd ddq_partial_dtau_fd(
model.nv,
model.nv);
2578 ddq_partial_dtau_fd.setZero();
2581 lambda_partial_dtau_fd.setZero();
2583 lambda_partial_dq_fd.setZero();
2585 lambda_partial_dv_fd.setZero();
2589 const VectorXd lambda0 = data_fd.lambda_c;
2590 VectorXd v_eps(VectorXd::Zero(
model.nv));
2591 VectorXd q_plus(
model.nq);
2592 VectorXd ddq_plus(
model.nv);
2595 const double alpha = 1e-8;
2597 for (
int k = 0; k <
model.nv; ++k)
2603 ddq_partial_dq_fd.col(k) = (ddq_plus - ddq0) /
alpha;
2604 lambda_partial_dq_fd.col(k) = (data_fd.lambda_c - lambda0) /
alpha;
2608 BOOST_CHECK(ddq_partial_dq_fd.isApprox(
data.ddq_dq, sqrt(
alpha)));
2610 BOOST_CHECK(lambda_partial_dq_fd.isApprox(
data.dlambda_dq, sqrt(
alpha)));
2613 for (
int k = 0; k <
model.nv; ++k)
2618 ddq_partial_dv_fd.col(k) = (ddq_plus - ddq0) /
alpha;
2619 lambda_partial_dv_fd.col(k) = (data_fd.lambda_c - lambda0) /
alpha;
2623 BOOST_CHECK(ddq_partial_dv_fd.isApprox(
data.ddq_dv, sqrt(
alpha)));
2624 BOOST_CHECK(lambda_partial_dv_fd.isApprox(
data.dlambda_dv, sqrt(
alpha)));
2626 VectorXd tau_plus(
tau);
2627 for (
int k = 0; k <
model.nv; ++k)
2629 tau_plus[k] +=
alpha;
2632 ddq_partial_dtau_fd.col(k) = (ddq_plus - ddq0) /
alpha;
2633 lambda_partial_dtau_fd.col(k) = (data_fd.lambda_c - lambda0) /
alpha;
2634 tau_plus[k] -=
alpha;
2637 BOOST_CHECK(lambda_partial_dtau_fd.isApprox(
data.dlambda_dtau, sqrt(
alpha)));
2638 BOOST_CHECK(ddq_partial_dtau_fd.isApprox(
data.ddq_dtau, sqrt(
alpha)));
2641 #endif // PINOCCHIO_WITH_SDFORMAT
2643 BOOST_AUTO_TEST_SUITE_END()