| Directory: | ./ |
|---|---|
| File: | unittest/spatial.cpp |
| Date: | 2025-02-12 21:03:38 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 681 | 681 | 100.0% |
| Branches: | 3029 | 6030 | 50.2% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // | ||
| 2 | // Copyright (c) 2015-2021 CNRS INRIA | ||
| 3 | // | ||
| 4 | |||
| 5 | #include <iostream> | ||
| 6 | |||
| 7 | #include "pinocchio/spatial/force.hpp" | ||
| 8 | #include "pinocchio/spatial/motion.hpp" | ||
| 9 | #include "pinocchio/spatial/se3.hpp" | ||
| 10 | #include "pinocchio/spatial/inertia.hpp" | ||
| 11 | #include "pinocchio/spatial/act-on-set.hpp" | ||
| 12 | #include "pinocchio/spatial/explog.hpp" | ||
| 13 | #include "pinocchio/spatial/skew.hpp" | ||
| 14 | #include "pinocchio/spatial/cartesian-axis.hpp" | ||
| 15 | #include "pinocchio/spatial/spatial-axis.hpp" | ||
| 16 | |||
| 17 | #include <boost/test/unit_test.hpp> | ||
| 18 | #include <boost/utility/binary.hpp> | ||
| 19 | |||
| 20 | BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) | ||
| 21 | |||
| 22 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_SE3) |
| 23 | { | ||
| 24 | using namespace pinocchio; | ||
| 25 | typedef SE3::HomogeneousMatrixType HomogeneousMatrixType; | ||
| 26 | typedef SE3::ActionMatrixType ActionMatrixType; | ||
| 27 | typedef SE3::Vector3 Vector3; | ||
| 28 | typedef Eigen::Matrix<double, 4, 1> Vector4; | ||
| 29 | |||
| 30 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | const SE3 identity = SE3::Identity(); |
| 31 | |||
| 32 | typedef SE3::Quaternion Quaternion; | ||
| 33 | typedef SE3::Vector4 Vector4; | ||
| 34 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | Quaternion quat(Vector4::Random().normalized()); |
| 35 | |||
| 36 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | SE3 m_from_quat(quat, Vector3::Random()); |
| 37 | |||
| 38 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 amb = SE3::Random(); |
| 39 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 bmc = SE3::Random(); |
| 40 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 amc = amb * bmc; |
| 41 | |||
| 42 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | HomogeneousMatrixType aMb = amb; |
| 43 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | HomogeneousMatrixType bMc = bmc; |
| 44 | |||
| 45 | // Test internal product | ||
| 46 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | HomogeneousMatrixType aMc = amc; |
| 47 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(aMc.isApprox(aMb * bMc)); |
| 48 | |||
| 49 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | HomogeneousMatrixType bMa = amb.inverse(); |
| 50 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(bMa.isApprox(aMb.inverse())); |
| 51 | |||
| 52 | // Test point action | ||
| 53 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector3 p = Vector3::Random(); |
| 54 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Vector4 p4; |
| 55 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | p4.head(3) = p; |
| 56 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | p4[3] = 1; |
| 57 | |||
| 58 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | Vector3 Mp = (aMb * p4).head(3); |
| 59 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(amb.act(p).isApprox(Mp)); |
| 60 | |||
| 61 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | Vector3 Mip = (aMb.inverse() * p4).head(3); |
| 62 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(amb.actInv(p).isApprox(Mip)); |
| 63 | |||
| 64 | // Test action matrix | ||
| 65 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ActionMatrixType aXb = amb; |
| 66 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ActionMatrixType bXc = bmc; |
| 67 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ActionMatrixType aXc = amc; |
| 68 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(aXc.isApprox(aXb * bXc)); |
| 69 | |||
| 70 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | ActionMatrixType bXa = amb.inverse(); |
| 71 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(bXa.isApprox(aXb.inverse())); |
| 72 | |||
| 73 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ActionMatrixType X_identity = identity.toActionMatrix(); |
| 74 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(X_identity.isIdentity()); |
| 75 | |||
| 76 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ActionMatrixType X_identity_inverse = identity.toActionMatrixInverse(); |
| 77 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(X_identity_inverse.isIdentity()); |
| 78 | |||
| 79 | // Test dual action matrix | ||
| 80 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(aXb.inverse().transpose().isApprox(amb.toDualActionMatrix())); |
| 81 | |||
| 82 | // Test isIdentity | ||
| 83 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(identity.isIdentity()); |
| 84 | |||
| 85 | // Test isApprox | ||
| 86 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(identity.isApprox(identity)); |
| 87 | |||
| 88 | // Test cast | ||
| 89 | typedef SE3Tpl<float> SE3f; | ||
| 90 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | SE3f::Matrix3 rot_float(amb.rotation().cast<float>()); |
| 91 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3f amb_float = amb.cast<float>(); |
| 92 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(amb_float.isApprox(amb.cast<float>())); |
| 93 | |||
| 94 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3f amb_float2(amb); |
| 95 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(amb_float.isApprox(amb_float2)); |
| 96 | |||
| 97 | // Test actInv | ||
| 98 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | const SE3 M = SE3::Random(); |
| 99 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | const SE3 Minv = M.inverse(); |
| 100 | |||
| 101 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(Minv.actInv(Minv).isIdentity()); |
| 102 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(M.actInv(identity).isApprox(Minv)); |
| 103 | |||
| 104 | // Test normalization | ||
| 105 | { | ||
| 106 | 2 | const double prec = Eigen::NumTraits<double>::dummy_precision(); | |
| 107 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 M(SE3::Random()); |
| 108 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | M.rotation() += prec * SE3::Matrix3::Random(); |
| 109 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(!M.isNormalized()); |
| 110 | |||
| 111 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 M_normalized = M.normalized(); |
| 112 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(M_normalized.isNormalized()); |
| 113 | |||
| 114 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | M.normalize(); |
| 115 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(M.isNormalized()); |
| 116 | } | ||
| 117 | 2 | } | |
| 118 | |||
| 119 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_Motion) |
| 120 | { | ||
| 121 | using namespace pinocchio; | ||
| 122 | typedef SE3::ActionMatrixType ActionMatrixType; | ||
| 123 | typedef Motion::Vector6 Vector6; | ||
| 124 | |||
| 125 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 amb = SE3::Random(); |
| 126 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 bmc = SE3::Random(); |
| 127 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 amc = amb * bmc; |
| 128 | |||
| 129 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion bv = Motion::Random(); |
| 130 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion bv2 = Motion::Random(); |
| 131 | |||
| 132 | typedef MotionBase<Motion> Base; | ||
| 133 | |||
| 134 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Vector6 bv_vec = bv; |
| 135 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Vector6 bv2_vec = bv2; |
| 136 | |||
| 137 | // std::stringstream | ||
| 138 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | std::stringstream ss; |
| 139 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | ss << bv << std::endl; |
| 140 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(!ss.str().empty()); |
| 141 | |||
| 142 | // Test .+. | ||
| 143 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector6 bvPbv2_vec = bv + bv2; |
| 144 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(bvPbv2_vec.isApprox(bv_vec + bv2_vec)); |
| 145 | |||
| 146 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion bplus = static_cast<Base &>(bv) + static_cast<Base &>(bv2); |
| 147 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK((bv + bv2).isApprox(bplus)); |
| 148 | |||
| 149 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Motion v_not_zero(Vector6::Ones()); |
| 150 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(!v_not_zero.isZero()); |
| 151 | |||
| 152 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Motion v_zero(Vector6::Zero()); |
| 153 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(v_zero.isZero()); |
| 154 | |||
| 155 | // Test == and != | ||
| 156 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(bv == bv); |
| 157 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(!(bv != bv)); |
| 158 | |||
| 159 | // Test -. | ||
| 160 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector6 Mbv_vec = -bv; |
| 161 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(Mbv_vec.isApprox(-bv_vec)); |
| 162 | |||
| 163 | // Test .+=. | ||
| 164 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion bv3 = bv; |
| 165 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | bv3 += bv2; |
| 166 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(bv3.toVector().isApprox(bv_vec + bv2_vec)); |
| 167 | |||
| 168 | // Test .=V6 | ||
| 169 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | bv3 = bv2_vec; |
| 170 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(bv3.toVector().isApprox(bv2_vec)); |
| 171 | |||
| 172 | // Test scalar*M6 | ||
| 173 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion twicebv(2. * bv); |
| 174 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(twicebv.isApprox(Motion(2. * bv.toVector()))); |
| 175 | |||
| 176 | // Test M6*scalar | ||
| 177 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion bvtwice(bv * 2.); |
| 178 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(bvtwice.isApprox(twicebv)); |
| 179 | |||
| 180 | // Test M6/scalar | ||
| 181 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion bvdividedbytwo(bvtwice / 2.); |
| 182 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(bvdividedbytwo.isApprox(bv)); |
| 183 | |||
| 184 | // Test constructor from V6 | ||
| 185 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion bv4(bv2_vec); |
| 186 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(bv4.toVector().isApprox(bv2_vec)); |
| 187 | |||
| 188 | // Test action | ||
| 189 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ActionMatrixType aXb = amb; |
| 190 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(amb.act(bv).toVector().isApprox(aXb * bv_vec)); |
| 191 | |||
| 192 | // Test action inverse | ||
| 193 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ActionMatrixType bXc = bmc; |
| 194 |
11/22✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✗ Branch 38 not taken.
✓ Branch 39 taken 1 times.
|
2 | BOOST_CHECK(bmc.actInv(bv).toVector().isApprox(bXc.inverse() * bv_vec)); |
| 195 | |||
| 196 | // Test double action | ||
| 197 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion cv = Motion::Random(); |
| 198 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | bv = bmc.act(cv); |
| 199 |
11/22✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✗ Branch 38 not taken.
✓ Branch 39 taken 1 times.
|
2 | BOOST_CHECK(amb.act(bv).toVector().isApprox(amc.act(cv).toVector())); |
| 200 | |||
| 201 | // Simple test for cross product vxv | ||
| 202 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion vxv = bv.cross(bv); |
| 203 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK_SMALL( |
| 204 | vxv.toVector().tail(3).norm(), | ||
| 205 | 1e-3); // previously ensure that (vxv.toVector().tail(3).isMuchSmallerThan(1e-3)); | ||
| 206 | |||
| 207 | // Test Action Matrix | ||
| 208 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v2xv = bv2.cross(bv); |
| 209 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion::ActionMatrixType actv2 = bv2.toActionMatrix(); |
| 210 | |||
| 211 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(v2xv.toVector().isApprox(actv2 * bv.toVector())); |
| 212 | |||
| 213 | // Test Dual Action Matrix | ||
| 214 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Force f(bv.toVector()); |
| 215 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force v2xf = bv2.cross(f); |
| 216 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion::ActionMatrixType dualactv2 = bv2.toDualActionMatrix(); |
| 217 | |||
| 218 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(v2xf.toVector().isApprox(dualactv2 * f.toVector())); |
| 219 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(dualactv2.isApprox(-actv2.transpose())); |
| 220 | |||
| 221 | // Simple test for cross product vxf | ||
| 222 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force vxf = bv.cross(f); |
| 223 |
11/22✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✗ Branch 38 not taken.
✓ Branch 39 taken 1 times.
|
2 | BOOST_CHECK(vxf.linear().isApprox(bv.angular().cross(f.linear()))); |
| 224 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK_SMALL( |
| 225 | vxf.angular().norm(), | ||
| 226 | 1e-3); // previously ensure that ( vxf.angular().isMuchSmallerThan(1e-3)); | ||
| 227 | |||
| 228 | // Test frame change for vxf | ||
| 229 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion av = Motion::Random(); |
| 230 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force af = Force::Random(); |
| 231 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | bv = amb.actInv(av); |
| 232 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force bf = amb.actInv(af); |
| 233 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force avxf = av.cross(af); |
| 234 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force bvxf = bv.cross(bf); |
| 235 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(avxf.toVector().isApprox(amb.act(bvxf).toVector())); |
| 236 | |||
| 237 | // Test frame change for vxv | ||
| 238 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | av = Motion::Random(); |
| 239 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion aw = Motion::Random(); |
| 240 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | bv = amb.actInv(av); |
| 241 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion bw = amb.actInv(aw); |
| 242 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion avxw = av.cross(aw); |
| 243 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion bvxw = bv.cross(bw); |
| 244 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(avxw.toVector().isApprox(amb.act(bvxw).toVector())); |
| 245 | |||
| 246 | // Test isApprox | ||
| 247 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | bv.toVector().setOnes(); |
| 248 | 2 | const double eps = 1e-6; | |
| 249 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(bv == bv); |
| 250 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(bv.isApprox(bv)); |
| 251 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion bv_approx(bv); |
| 252 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | bv_approx.linear()[0] += eps; |
| 253 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(bv_approx.isApprox(bv, eps)); |
| 254 | |||
| 255 | // Test ref() method | ||
| 256 | { | ||
| 257 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion a(Motion::Random()); |
| 258 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(a.ref().isApprox(a)); |
| 259 | |||
| 260 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | const Motion b(a); |
| 261 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(b.isApprox(a.ref())); |
| 262 | } | ||
| 263 | |||
| 264 | // Test cast | ||
| 265 | { | ||
| 266 | typedef MotionTpl<float> Motionf; | ||
| 267 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion a(Motion::Random()); |
| 268 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motionf a_float = a.cast<float>(); |
| 269 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(a_float.isApprox(a.cast<float>())); |
| 270 | |||
| 271 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motionf a_float2(a); |
| 272 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(a_float.isApprox(a_float2)); |
| 273 | } | ||
| 274 | 2 | } | |
| 275 | |||
| 276 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_motion_ref) |
| 277 | { | ||
| 278 | using namespace pinocchio; | ||
| 279 | typedef Motion::Vector6 Vector6; | ||
| 280 | |||
| 281 | typedef MotionRef<Vector6> MotionV6; | ||
| 282 | |||
| 283 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v_ref(Motion::Random()); |
| 284 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | MotionV6 v(v_ref.toVector()); |
| 285 | |||
| 286 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(v_ref.isApprox(v)); |
| 287 | |||
| 288 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | MotionV6::MotionPlain v2(v * 2.); |
| 289 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v2_ref(v_ref * 2.); |
| 290 | |||
| 291 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(v2_ref.isApprox(v2)); |
| 292 | |||
| 293 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | v2 = v_ref + v; |
| 294 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(v2_ref.isApprox(v2)); |
| 295 | |||
| 296 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | v = v2; |
| 297 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(v2.isApprox(v)); |
| 298 | |||
| 299 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | v2 = v - v; |
| 300 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(v2.isApprox(Motion::Zero())); |
| 301 | |||
| 302 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 M(SE3::Identity()); |
| 303 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | v2 = M.act(v); |
| 304 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(v2.isApprox(v)); |
| 305 | |||
| 306 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | v2 = M.actInv(v); |
| 307 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(v2.isApprox(v)); |
| 308 | |||
| 309 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v3(Motion::Random()); |
| 310 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | v_ref.setRandom(); |
| 311 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | v = v_ref; |
| 312 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | v2 = v.cross(v3); |
| 313 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | v2_ref = v_ref.cross(v3); |
| 314 | |||
| 315 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(v2.isApprox(v2_ref)); |
| 316 | |||
| 317 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | v.setRandom(); |
| 318 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | v.setZero(); |
| 319 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(v.isApprox(Motion::Zero())); |
| 320 | |||
| 321 | // Test ref() method | ||
| 322 | { | ||
| 323 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector6 v6(Vector6::Random()); |
| 324 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | MotionV6 a(v6); |
| 325 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(a.ref().isApprox(a)); |
| 326 | |||
| 327 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | const Motion b(a); |
| 328 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(b.isApprox(a.ref())); |
| 329 | } | ||
| 330 | 2 | } | |
| 331 | |||
| 332 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_motion_zero) |
| 333 | { | ||
| 334 | using namespace pinocchio; | ||
| 335 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v((MotionZero())); |
| 336 | |||
| 337 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(v.toVector().isZero()); |
| 338 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(MotionZero() == Motion::Zero()); |
| 339 | |||
| 340 | // SE3.act | ||
| 341 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 m(SE3::Random()); |
| 342 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✗ Branch 31 not taken.
✓ Branch 32 taken 1 times.
|
2 | BOOST_CHECK(m.act(MotionZero()) == Motion::Zero()); |
| 343 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✗ Branch 31 not taken.
✓ Branch 32 taken 1 times.
|
2 | BOOST_CHECK(m.actInv(MotionZero()) == Motion::Zero()); |
| 344 | |||
| 345 | // Motion.cross | ||
| 346 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v2(Motion::Random()); |
| 347 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✗ Branch 31 not taken.
✓ Branch 32 taken 1 times.
|
2 | BOOST_CHECK(v2.cross(MotionZero()) == Motion::Zero()); |
| 348 | 2 | } | |
| 349 | |||
| 350 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_Force) |
| 351 | { | ||
| 352 | using namespace pinocchio; | ||
| 353 | typedef SE3::ActionMatrixType ActionMatrixType; | ||
| 354 | typedef Force::Vector6 Vector6; | ||
| 355 | |||
| 356 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 amb = SE3::Random(); |
| 357 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 bmc = SE3::Random(); |
| 358 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 amc = amb * bmc; |
| 359 | |||
| 360 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force bf = Force::Random(); |
| 361 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force bf2 = Force::Random(); |
| 362 | |||
| 363 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Vector6 bf_vec = bf; |
| 364 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Vector6 bf2_vec = bf2; |
| 365 | |||
| 366 | // std::stringstream | ||
| 367 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | std::stringstream ss; |
| 368 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | ss << bf << std::endl; |
| 369 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(!ss.str().empty()); |
| 370 | |||
| 371 | // Test .+. | ||
| 372 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector6 bfPbf2_vec = bf + bf2; |
| 373 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(bfPbf2_vec.isApprox(bf_vec + bf2_vec)); |
| 374 | |||
| 375 | // Test -. | ||
| 376 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector6 Mbf_vec = -bf; |
| 377 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(Mbf_vec.isApprox(-bf_vec)); |
| 378 | |||
| 379 | // Test .+=. | ||
| 380 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force bf3 = bf; |
| 381 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | bf3 += bf2; |
| 382 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(bf3.toVector().isApprox(bf_vec + bf2_vec)); |
| 383 | |||
| 384 | // Test .= V6 | ||
| 385 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | bf3 = bf2_vec; |
| 386 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(bf3.toVector().isApprox(bf2_vec)); |
| 387 | |||
| 388 | // Test constructor from V6 | ||
| 389 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force bf4(bf2_vec); |
| 390 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(bf4.toVector().isApprox(bf2_vec)); |
| 391 | |||
| 392 | // Test action | ||
| 393 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ActionMatrixType aXb = amb; |
| 394 |
12/24✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✗ Branch 41 not taken.
✓ Branch 42 taken 1 times.
|
2 | BOOST_CHECK(amb.act(bf).toVector().isApprox(aXb.inverse().transpose() * bf_vec)); |
| 395 | |||
| 396 | // Test action inverse | ||
| 397 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ActionMatrixType bXc = bmc; |
| 398 |
11/22✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✗ Branch 38 not taken.
✓ Branch 39 taken 1 times.
|
2 | BOOST_CHECK(bmc.actInv(bf).toVector().isApprox(bXc.transpose() * bf_vec)); |
| 399 | |||
| 400 | // Test double action | ||
| 401 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force cf = Force::Random(); |
| 402 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | bf = bmc.act(cf); |
| 403 |
11/22✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✗ Branch 38 not taken.
✓ Branch 39 taken 1 times.
|
2 | BOOST_CHECK(amb.act(bf).toVector().isApprox(amc.act(cf).toVector())); |
| 404 | |||
| 405 | // Simple test for cross product | ||
| 406 | // Force vxv = bf.cross(bf); | ||
| 407 | // ensure that (vxv.toVector().isMuchSmallerThan(bf.toVector())); | ||
| 408 | |||
| 409 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Force f_not_zero(Vector6::Ones()); |
| 410 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(!f_not_zero.isZero()); |
| 411 | |||
| 412 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Force f_zero(Vector6::Zero()); |
| 413 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(f_zero.isZero()); |
| 414 | |||
| 415 | // Test isApprox | ||
| 416 | |||
| 417 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(bf == bf); |
| 418 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | bf.setRandom(); |
| 419 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | bf2.setZero(); |
| 420 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(bf == bf); |
| 421 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(bf != bf2); |
| 422 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(bf.isApprox(bf)); |
| 423 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(!bf.isApprox(bf2)); |
| 424 | |||
| 425 | 2 | const double eps = 1e-6; | |
| 426 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force bf_approx(bf); |
| 427 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | bf_approx.linear()[0] += 2. * eps; |
| 428 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(!bf_approx.isApprox(bf, eps)); |
| 429 | |||
| 430 | // Test ref() method | ||
| 431 | { | ||
| 432 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force a(Force::Random()); |
| 433 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(a.ref().isApprox(a)); |
| 434 | |||
| 435 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | const Force b(a); |
| 436 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(b.isApprox(a.ref())); |
| 437 | } | ||
| 438 | |||
| 439 | // Test cast | ||
| 440 | { | ||
| 441 | typedef ForceTpl<float> Forcef; | ||
| 442 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force a(Force::Random()); |
| 443 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Forcef a_float = a.cast<float>(); |
| 444 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(a_float.isApprox(a.cast<float>())); |
| 445 | |||
| 446 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Forcef a_float2(a); |
| 447 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(a_float.isApprox(a_float2)); |
| 448 | } | ||
| 449 | |||
| 450 | // Test scalar multiplication | ||
| 451 | 2 | const double alpha = 1.5; | |
| 452 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force b(Force::Random()); |
| 453 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force alpha_f = alpha * b; |
| 454 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force f_alpha = b * alpha; |
| 455 | |||
| 456 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(alpha_f == f_alpha); |
| 457 | 2 | } | |
| 458 | |||
| 459 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_force_ref) |
| 460 | { | ||
| 461 | using namespace pinocchio; | ||
| 462 | typedef Force::Vector6 Vector6; | ||
| 463 | |||
| 464 | typedef ForceRef<Vector6> ForceV6; | ||
| 465 | |||
| 466 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force f_ref(Force::Random()); |
| 467 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | ForceV6 f(f_ref.toVector()); |
| 468 | |||
| 469 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(f_ref.isApprox(f)); |
| 470 | |||
| 471 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ForceV6::ForcePlain f2(f * 2.); |
| 472 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force f2_ref(f_ref * 2.); |
| 473 | |||
| 474 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(f2_ref.isApprox(f2)); |
| 475 | |||
| 476 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | f2 = f_ref + f; |
| 477 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(f2_ref.isApprox(f2)); |
| 478 | |||
| 479 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | f = f2; |
| 480 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(f2.isApprox(f)); |
| 481 | |||
| 482 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | f2 = f - f; |
| 483 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(f2.isApprox(Force::Zero())); |
| 484 | |||
| 485 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 M(SE3::Identity()); |
| 486 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | f2 = M.act(f); |
| 487 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(f2.isApprox(f)); |
| 488 | |||
| 489 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | f2 = M.actInv(f); |
| 490 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(f2.isApprox(f)); |
| 491 | |||
| 492 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v(Motion::Random()); |
| 493 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | f_ref.setRandom(); |
| 494 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | f = f_ref; |
| 495 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | f2 = v.cross(f); |
| 496 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | f2_ref = v.cross(f_ref); |
| 497 | |||
| 498 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(f2.isApprox(f2_ref)); |
| 499 | |||
| 500 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | f.setRandom(); |
| 501 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | f.setZero(); |
| 502 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(f.isApprox(Force::Zero())); |
| 503 | |||
| 504 | // Test ref() method | ||
| 505 | { | ||
| 506 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector6 v6(Vector6::Random()); |
| 507 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ForceV6 a(v6); |
| 508 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(a.ref().isApprox(a)); |
| 509 | |||
| 510 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | const Force b(a); |
| 511 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(b.isApprox(a.ref())); |
| 512 | } | ||
| 513 | 2 | } | |
| 514 | |||
| 515 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_Inertia) |
| 516 | { | ||
| 517 | using namespace pinocchio; | ||
| 518 | typedef Inertia::Matrix6 Matrix6; | ||
| 519 | |||
| 520 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia aI = Inertia::Random(); |
| 521 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Matrix6 matI = aI; |
| 522 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 1 times.
|
2 | BOOST_CHECK_EQUAL(matI(0, 0), aI.mass()); |
| 523 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 1 times.
|
2 | BOOST_CHECK_EQUAL(matI(1, 1), aI.mass()); |
| 524 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 1 times.
|
2 | BOOST_CHECK_EQUAL(matI(2, 2), aI.mass()); // 1,1 before unifying |
| 525 | |||
| 526 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 1 times.
✗ Branch 26 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK_SMALL( |
| 527 | (matI - matI.transpose()).norm(), | ||
| 528 | matI.norm()); // previously ensure that( (matI-matI.transpose()).isMuchSmallerThan(matI) ); | ||
| 529 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 31 not taken.
✓ Branch 32 taken 1 times.
|
2 | BOOST_CHECK_SMALL( |
| 530 | (matI.topRightCorner<3, 3>() * aI.lever()).norm(), | ||
| 531 | aI.lever().norm()); // previously ensure that( | ||
| 532 | // (matI.topRightCorner<3,3>()*aI.lever()).isMuchSmallerThan(aI.lever()) ); | ||
| 533 | |||
| 534 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I1 = Inertia::Identity(); |
| 535 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(I1.matrix().isApprox(Matrix6::Identity())); |
| 536 | |||
| 537 | // Test motion-to-force map | ||
| 538 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v = Motion::Random(); |
| 539 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force f = I1 * v; |
| 540 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(f.toVector().isApprox(v.toVector())); |
| 541 | |||
| 542 | // Test Inertia group application | ||
| 543 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 bma = SE3::Random(); |
| 544 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia bI = bma.act(aI); |
| 545 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Matrix6 bXa = bma; |
| 546 |
14/28✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 35 taken 1 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 1 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 44 taken 1 times.
✗ Branch 45 not taken.
✗ Branch 49 not taken.
✓ Branch 50 taken 1 times.
|
2 | BOOST_CHECK((bma.rotation() * aI.inertia().matrix() * bma.rotation().transpose()) |
| 547 | .isApprox(bI.inertia().matrix())); | ||
| 548 |
14/28✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 1 times.
✗ Branch 30 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 39 taken 1 times.
✗ Branch 40 not taken.
✓ Branch 42 taken 1 times.
✗ Branch 43 not taken.
✗ Branch 47 not taken.
✓ Branch 48 taken 1 times.
|
2 | BOOST_CHECK((bXa.transpose().inverse() * aI.matrix() * bXa.inverse()).isApprox(bI.matrix())); |
| 549 | |||
| 550 | // Test inverse action | ||
| 551 |
13/26✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 39 taken 1 times.
✗ Branch 40 not taken.
✗ Branch 44 not taken.
✓ Branch 45 taken 1 times.
|
2 | BOOST_CHECK((bXa.transpose() * bI.matrix() * bXa).isApprox(bma.actInv(bI).matrix())); |
| 552 | |||
| 553 | // Test vxIv cross product | ||
| 554 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | v = Motion::Random(); |
| 555 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | f = aI * v; |
| 556 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force vxf = v.cross(f); |
| 557 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force vxIv = aI.vxiv(v); |
| 558 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(vxf.toVector().isApprox(vxIv.toVector())); |
| 559 | |||
| 560 | // Test operator+ | ||
| 561 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | I1 = Inertia::Random(); |
| 562 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I2 = Inertia::Random(); |
| 563 |
12/24✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✗ Branch 41 not taken.
✓ Branch 42 taken 1 times.
|
2 | BOOST_CHECK((I1.matrix() + I2.matrix()).isApprox((I1 + I2).matrix())); |
| 564 | |||
| 565 | // Test operator- | ||
| 566 | { | ||
| 567 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | I1 = Inertia::Random(); |
| 568 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I2 = Inertia::Random(); |
| 569 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia Isum = I1 + I2; |
| 570 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I1_other = Isum - I2; |
| 571 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(I1_other.matrix().isApprox(I1.matrix())); |
| 572 | } | ||
| 573 | |||
| 574 | // Test operator += | ||
| 575 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I12 = I1; |
| 576 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | I12 += I2; |
| 577 |
11/22✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✗ Branch 38 not taken.
✓ Branch 39 taken 1 times.
|
2 | BOOST_CHECK((I1.matrix() + I2.matrix()).isApprox(I12.matrix())); |
| 578 | |||
| 579 | // Test operator -= | ||
| 580 | { | ||
| 581 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I2 = Inertia::Random(); |
| 582 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia Isum = I1 + I2; |
| 583 | |||
| 584 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I1_other = Isum; |
| 585 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | I1_other -= I2; |
| 586 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK((I1_other.matrix()).isApprox(I1.matrix())); |
| 587 | } | ||
| 588 | |||
| 589 | // Test operator vtiv | ||
| 590 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
|
2 | double kinetic_ref = v.toVector().transpose() * aI.matrix() * v.toVector(); |
| 591 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | double kinetic = aI.vtiv(v); |
| 592 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✗ Branch 17 not taken.
✓ Branch 18 taken 1 times.
|
2 | BOOST_CHECK_SMALL(kinetic_ref - kinetic, 1e-12); |
| 593 | |||
| 594 | // Test constructor (Matrix6) | ||
| 595 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Inertia I1_bis(I1.matrix()); |
| 596 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(I1.matrix().isApprox(I1_bis.matrix())); |
| 597 | |||
| 598 | // Test Inertia from ellipsoid | ||
| 599 | 2 | const double sphere_mass = 5.; | |
| 600 | 2 | const double sphere_radius = 2.; | |
| 601 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | I1 = Inertia::FromSphere(sphere_mass, sphere_radius); |
| 602 | 2 | const double L_sphere = 2. / 5. * sphere_mass * sphere_radius * sphere_radius; | |
| 603 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✗ Branch 18 not taken.
✓ Branch 19 taken 1 times.
|
2 | BOOST_CHECK_SMALL(I1.mass() - sphere_mass, 1e-12); |
| 604 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(I1.lever().isZero()); |
| 605 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 1 times.
✗ Branch 32 not taken.
✗ Branch 36 not taken.
✓ Branch 37 taken 1 times.
|
2 | BOOST_CHECK( |
| 606 | I1.inertia().matrix().isApprox(Symmetric3(L_sphere, 0., L_sphere, 0., 0., L_sphere).matrix())); | ||
| 607 | |||
| 608 | // Test Inertia from ellipsoid | ||
| 609 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | I1 = Inertia::FromEllipsoid(2., 3., 4., 5.); |
| 610 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✗ Branch 18 not taken.
✓ Branch 19 taken 1 times.
|
2 | BOOST_CHECK_SMALL(I1.mass() - 2, 1e-12); |
| 611 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 1 times.
|
2 | BOOST_CHECK_SMALL(I1.lever().norm(), 1e-12); |
| 612 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 1 times.
✗ Branch 32 not taken.
✗ Branch 36 not taken.
✓ Branch 37 taken 1 times.
|
2 | BOOST_CHECK(I1.inertia().matrix().isApprox(Symmetric3(16.4, 0., 13.6, 0., 0., 10.).matrix())); |
| 613 | |||
| 614 | // Test Inertia from Cylinder | ||
| 615 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | I1 = Inertia::FromCylinder(2., 4., 6.); |
| 616 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✗ Branch 18 not taken.
✓ Branch 19 taken 1 times.
|
2 | BOOST_CHECK_SMALL(I1.mass() - 2, 1e-12); |
| 617 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 1 times.
|
2 | BOOST_CHECK_SMALL(I1.lever().norm(), 1e-12); |
| 618 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 1 times.
✗ Branch 32 not taken.
✗ Branch 36 not taken.
✓ Branch 37 taken 1 times.
|
2 | BOOST_CHECK(I1.inertia().matrix().isApprox(Symmetric3(14., 0., 14., 0., 0., 16.).matrix())); |
| 619 | |||
| 620 | // Test Inertia from Box | ||
| 621 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | I1 = Inertia::FromBox(2., 6., 12., 18.); |
| 622 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✗ Branch 18 not taken.
✓ Branch 19 taken 1 times.
|
2 | BOOST_CHECK_SMALL(I1.mass() - 2, 1e-12); |
| 623 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 1 times.
|
2 | BOOST_CHECK_SMALL(I1.lever().norm(), 1e-12); |
| 624 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 1 times.
✗ Branch 32 not taken.
✗ Branch 36 not taken.
✓ Branch 37 taken 1 times.
|
2 | BOOST_CHECK(I1.inertia().matrix().isApprox(Symmetric3(78., 0., 60., 0., 0., 30.).matrix())); |
| 625 | |||
| 626 | // Test Inertia From Capsule | ||
| 627 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | I1 = Inertia::FromCapsule(1., 2., 3); |
| 628 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✗ Branch 18 not taken.
✓ Branch 19 taken 1 times.
|
2 | BOOST_CHECK_SMALL(I1.mass() - 1, 1e-12); |
| 629 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 1 times.
|
2 | BOOST_CHECK_SMALL(I1.lever().norm(), 1e-12); |
| 630 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(I1.inertia().matrix().isApprox( |
| 631 | Symmetric3(3.79705882, 0., 3.79705882, 0., 0., 1.81176471).matrix(), | ||
| 632 | 1e-5)); // Computed with hppfcl::Capsule | ||
| 633 | |||
| 634 | // Copy operator | ||
| 635 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia aI_copy(aI); |
| 636 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(aI_copy == aI); |
| 637 | |||
| 638 | // Test isZero | ||
| 639 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I_not_zero = Inertia::Identity(); |
| 640 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(!I_not_zero.isZero()); |
| 641 | |||
| 642 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I_zero = Inertia::Zero(); |
| 643 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(I_zero.isZero()); |
| 644 | |||
| 645 | // Test isApprox | ||
| 646 | 2 | const double eps = 1e-6; | |
| 647 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(aI == aI); |
| 648 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(aI.isApprox(aI)); |
| 649 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia aI_approx(aI); |
| 650 | 2 | aI_approx.mass() += eps / 2.; | |
| 651 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(aI_approx.isApprox(aI, eps)); |
| 652 | |||
| 653 | // Test Variation | ||
| 654 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia::Matrix6 aIvariation = aI.variation(v); |
| 655 | |||
| 656 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion::ActionMatrixType vAction = v.toActionMatrix(); |
| 657 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion::ActionMatrixType vDualAction = v.toDualActionMatrix(); |
| 658 | |||
| 659 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia::Matrix6 aImatrix = aI.matrix(); |
| 660 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | Inertia::Matrix6 aIvariation_ref = vDualAction * aImatrix - aImatrix * vAction; |
| 661 | |||
| 662 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(aIvariation.isApprox(aIvariation_ref)); |
| 663 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(vxIv.isApprox(Force(aIvariation * v.toVector()))); |
| 664 | |||
| 665 | // Test vxI operator | ||
| 666 | { | ||
| 667 | typedef Inertia::Matrix6 Matrix6; | ||
| 668 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I(Inertia::Random()); |
| 669 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v(Motion::Random()); |
| 670 | |||
| 671 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | const Matrix6 M_ref(v.toDualActionMatrix() * I.matrix()); |
| 672 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Matrix6 M; |
| 673 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia::vxi(v, I, M); |
| 674 | |||
| 675 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(M.isApprox(M_ref)); |
| 676 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(I.vxi(v).isApprox(M_ref)); |
| 677 | } | ||
| 678 | |||
| 679 | // Test Ivx operator | ||
| 680 | { | ||
| 681 | typedef Inertia::Matrix6 Matrix6; | ||
| 682 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I(Inertia::Random()); |
| 683 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v(Motion::Random()); |
| 684 | |||
| 685 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | const Matrix6 M_ref(I.matrix() * v.toActionMatrix()); |
| 686 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Matrix6 M; |
| 687 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia::ivx(v, I, M); |
| 688 | |||
| 689 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(M.isApprox(M_ref)); |
| 690 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(I.ivx(v).isApprox(M_ref)); |
| 691 | } | ||
| 692 | |||
| 693 | // Test variation against vxI - Ivx operator | ||
| 694 | { | ||
| 695 | typedef Inertia::Matrix6 Matrix6; | ||
| 696 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I(Inertia::Random()); |
| 697 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v(Motion::Random()); |
| 698 | |||
| 699 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Matrix6 Ivariation = I.variation(v); |
| 700 | |||
| 701 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Matrix6 M1; |
| 702 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia::vxi(v, I, M1); |
| 703 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Matrix6 M2; |
| 704 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia::ivx(v, I, M2); |
| 705 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Matrix6 M3(M1 - M2); |
| 706 | |||
| 707 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(M3.isApprox(Ivariation)); |
| 708 | } | ||
| 709 | |||
| 710 | // Test inverse | ||
| 711 | { | ||
| 712 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I(Inertia::Random()); |
| 713 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia::Matrix6 I_inv = I.inverse(); |
| 714 | |||
| 715 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(I_inv.isApprox(I.matrix().inverse())); |
| 716 | } | ||
| 717 | |||
| 718 | // Test dynamic parameters | ||
| 719 | { | ||
| 720 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I(Inertia::Random()); |
| 721 | |||
| 722 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia::Vector10 v = I.toDynamicParameters(); |
| 723 | |||
| 724 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 1 times.
|
2 | BOOST_CHECK_CLOSE(v[0], I.mass(), 1e-12); |
| 725 | |||
| 726 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 1 times.
✗ Branch 30 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 1 times.
|
2 | BOOST_CHECK(v.segment<3>(1).isApprox(I.mass() * I.lever())); |
| 727 | |||
| 728 |
7/14✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
|
2 | Eigen::Matrix3d I_o = I.inertia() + I.mass() * skew(I.lever()).transpose() * skew(I.lever()); |
| 729 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Eigen::Matrix3d I_ov; |
| 730 |
18/36✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 1 times.
✗ Branch 32 not taken.
✓ Branch 34 taken 1 times.
✗ Branch 35 not taken.
✓ Branch 37 taken 1 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 1 times.
✗ Branch 41 not taken.
✓ Branch 43 taken 1 times.
✗ Branch 44 not taken.
✓ Branch 46 taken 1 times.
✗ Branch 47 not taken.
✓ Branch 49 taken 1 times.
✗ Branch 50 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
|
2 | I_ov << v[4], v[5], v[7], v[5], v[6], v[8], v[7], v[8], v[9]; |
| 731 | |||
| 732 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(I_o.isApprox(I_ov)); |
| 733 | |||
| 734 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I2 = Inertia::FromDynamicParameters(v); |
| 735 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(I2.isApprox(I)); |
| 736 | } | ||
| 737 | |||
| 738 | // Test disp | ||
| 739 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | std::cout << aI << std::endl; |
| 740 | |||
| 741 | // Test Inertia parametrizations | ||
| 742 | { | ||
| 743 | typedef LogCholeskyParametersTpl<double, 0> LogCholeskyParameters; | ||
| 744 | typedef PseudoInertiaTpl<double, 0> PseudoInertia; | ||
| 745 | |||
| 746 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia::Vector10 eta; |
| 747 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | eta.setRandom(); |
| 748 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | LogCholeskyParameters log_cholesky = LogCholeskyParameters(eta); |
| 749 | |||
| 750 | // Convert logcholesky parametrization to pseudo-inertia | ||
| 751 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | PseudoInertia pseudo = log_cholesky.toPseudoInertia(); |
| 752 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Eigen::Matrix4d pseudo_matrix = pseudo.toMatrix(); |
| 753 | // Convert logcholesky to inertia tpl | ||
| 754 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I_from_log_cholesky = Inertia::FromLogCholeskyParameters(log_cholesky); |
| 755 | |||
| 756 | // Check if conversion from inertia tpl to pseudo inertia gives same result as from logcholesky | ||
| 757 | // parametrization to pseudo-inertia | ||
| 758 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Eigen::Matrix4d pseudo_from_inertia = I_from_log_cholesky.toPseudoInertia().toMatrix(); |
| 759 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(pseudo_matrix.isApprox(pseudo_from_inertia, 1e-10)); |
| 760 | |||
| 761 | // // Check if log-cholesky parametrization to pseudo-inertia gives same result as their | ||
| 762 | // calculations | ||
| 763 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | double alpha = log_cholesky.parameters[0]; |
| 764 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | double d1 = log_cholesky.parameters[1]; |
| 765 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | double d2 = log_cholesky.parameters[2]; |
| 766 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | double d3 = log_cholesky.parameters[3]; |
| 767 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | double s12 = log_cholesky.parameters[4]; |
| 768 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | double s23 = log_cholesky.parameters[5]; |
| 769 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | double s13 = log_cholesky.parameters[6]; |
| 770 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | double t1 = log_cholesky.parameters[7]; |
| 771 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | double t2 = log_cholesky.parameters[8]; |
| 772 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | double t3 = log_cholesky.parameters[9]; |
| 773 | |||
| 774 | 2 | double exp_alpha = std::exp(alpha); | |
| 775 | 2 | double exp_d1 = std::exp(d1); | |
| 776 | 2 | double exp_d2 = std::exp(d2); | |
| 777 | 2 | double exp_d3 = std::exp(d3); | |
| 778 | |||
| 779 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Eigen::Matrix4d U; |
| 780 | // clang-format off | ||
| 781 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | U << exp_d1, s12, s13, t1, |
| 782 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | 0, exp_d2, s23, t2, |
| 783 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | 0, 0, exp_d3, t3, |
| 784 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | 0, 0, 0, 1; |
| 785 | // clang-format on | ||
| 786 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | U *= exp_alpha; |
| 787 | |||
| 788 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | Eigen::Matrix4d pseudo_chol = U * U.transpose(); |
| 789 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(pseudo_matrix.isApprox(pseudo_chol, 1e-10)); |
| 790 | |||
| 791 | // Additional checks: Convert back from pseudo-inertia to inertia and validate | ||
| 792 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia I_back = pseudo.toInertia(); |
| 793 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
|
2 | BOOST_CHECK_CLOSE(I_back.mass(), I_from_log_cholesky.mass(), 1e-12); |
| 794 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(I_back.lever().isApprox(I_from_log_cholesky.lever(), 1e-12)); |
| 795 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(I_back.inertia().isApprox(I_from_log_cholesky.inertia(), 1e-12)); |
| 796 | |||
| 797 | // Convert Inertia to dynamic parameters | ||
| 798 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia::Vector10 dynamic_params_inertia = I_from_log_cholesky.toDynamicParameters(); |
| 799 | |||
| 800 | // Convert log Cholesky to dynamic parameters | ||
| 801 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia::Vector10 dynamic_params_log_cholesky = log_cholesky.toDynamicParameters(); |
| 802 | |||
| 803 | // Compare dynamic parameters from Inertia and log Cholesky | ||
| 804 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(dynamic_params_inertia.isApprox(dynamic_params_log_cholesky, 1e-10)); |
| 805 | |||
| 806 | // Convert Pseudo Inertia to dynamic parameters | ||
| 807 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | PseudoInertia pseudo_inertia = PseudoInertia::FromMatrix(pseudo_matrix); |
| 808 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia::Vector10 dynamic_params_pseudo_inertia = pseudo_inertia.toDynamicParameters(); |
| 809 | |||
| 810 | // Compare dynamic parameters from Inertia and Pseudo Inertia | ||
| 811 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(dynamic_params_inertia.isApprox(dynamic_params_pseudo_inertia, 1e-10)); |
| 812 | |||
| 813 | // Compare dynamic parameters from log Cholesky and Pseudo Inertia | ||
| 814 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(dynamic_params_log_cholesky.isApprox(dynamic_params_pseudo_inertia, 1e-10)); |
| 815 | |||
| 816 | // Calculate Jacobian of logcholesky parametrization | ||
| 817 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Eigen::Matrix<double, 10, 10> jacobian = log_cholesky.calculateJacobian(); |
| 818 | |||
| 819 | // Check if determinant is non-zero | ||
| 820 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(std::abs(jacobian.determinant()) > 1e-10); |
| 821 | |||
| 822 | // Check physical consistency by positive definiteness of pseudo inertia | ||
| 823 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Eigen::SelfAdjointEigenSolver<Eigen::Matrix4d> eigensolver(pseudo_matrix); |
| 824 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK((eigensolver.eigenvalues().array() > 0).all()); |
| 825 | |||
| 826 | // Test disp | ||
| 827 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | std::cout << I_from_log_cholesky << std::endl; |
| 828 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | std::cout << log_cholesky << std::endl; |
| 829 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | std::cout << pseudo_inertia << std::endl; |
| 830 | } | ||
| 831 | 2 | } | |
| 832 | |||
| 833 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(cast_inertia) |
| 834 | { | ||
| 835 | using namespace pinocchio; | ||
| 836 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertia Y(Inertia::Random()); |
| 837 | |||
| 838 | typedef InertiaTpl<long double> Inertiald; | ||
| 839 | |||
| 840 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(Y.cast<double>() == Y); |
| 841 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✗ Branch 31 not taken.
✓ Branch 32 taken 1 times.
|
2 | BOOST_CHECK(Y.cast<long double>().cast<double>() == Y); |
| 842 | |||
| 843 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Inertiald Y2(Y); |
| 844 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(Y2.isApprox(Y.cast<long double>())); |
| 845 | 2 | } | |
| 846 | |||
| 847 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_ActOnSet) |
| 848 | { | ||
| 849 | using namespace pinocchio; | ||
| 850 | 2 | const int N = 20; | |
| 851 | typedef Eigen::Matrix<double, 6, N> Matrix6N; | ||
| 852 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 jMi = SE3::Random(); |
| 853 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v = Motion::Random(); |
| 854 | |||
| 855 | // Forcet SET | ||
| 856 | PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH | ||
| 857 | PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED | ||
| 858 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
|
2 | Matrix6N iF = Matrix6N::Random(), jF, jFinv, jF_ref, jFinv_ref; |
| 859 | |||
| 860 | // forceSet::se3Action | ||
| 861 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | forceSet::se3Action(jMi, iF, jF); |
| 862 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int k = 0; k < N; ++k) |
| 863 |
12/24✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 20 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 20 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 20 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 20 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 20 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 20 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 20 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 20 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 20 times.
✗ Branch 37 not taken.
✗ Branch 41 not taken.
✓ Branch 42 taken 20 times.
|
40 | BOOST_CHECK(jMi.act(Force(iF.col(k))).toVector().isApprox(jF.col(k))); |
| 864 | |||
| 865 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jF_ref = jMi.toDualActionMatrix() * iF; |
| 866 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jF_ref.isApprox(jF)); |
| 867 | |||
| 868 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | forceSet::se3ActionInverse(jMi.inverse(), iF, jFinv); |
| 869 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jFinv.isApprox(jF)); |
| 870 | PINOCCHIO_COMPILER_DIAGNOSTIC_POP | ||
| 871 | |||
| 872 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Matrix6N iF2 = Matrix6N::Random(); |
| 873 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jF_ref += jMi.toDualActionMatrix() * iF2; |
| 874 | |||
| 875 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | forceSet::se3Action<ADDTO>(jMi, iF2, jF); |
| 876 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jF.isApprox(jF_ref)); |
| 877 | |||
| 878 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Matrix6N iF3 = Matrix6N::Random(); |
| 879 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jF_ref -= jMi.toDualActionMatrix() * iF3; |
| 880 | |||
| 881 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | forceSet::se3Action<RMTO>(jMi, iF3, jF); |
| 882 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jF.isApprox(jF_ref)); |
| 883 | |||
| 884 | // forceSet::se3ActionInverse | ||
| 885 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | forceSet::se3ActionInverse(jMi, iF, jFinv); |
| 886 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | jFinv_ref = jMi.inverse().toDualActionMatrix() * iF; |
| 887 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jFinv_ref.isApprox(jFinv)); |
| 888 | |||
| 889 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | jFinv_ref += jMi.inverse().toDualActionMatrix() * iF2; |
| 890 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | forceSet::se3ActionInverse<ADDTO>(jMi, iF2, jFinv); |
| 891 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jFinv.isApprox(jFinv_ref)); |
| 892 | |||
| 893 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | jFinv_ref -= jMi.inverse().toDualActionMatrix() * iF3; |
| 894 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | forceSet::se3ActionInverse<RMTO>(jMi, iF3, jFinv); |
| 895 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jFinv.isApprox(jFinv_ref)); |
| 896 | |||
| 897 | // forceSet::motionAction | ||
| 898 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | forceSet::motionAction(v, iF, jF); |
| 899 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int k = 0; k < N; ++k) |
| 900 |
12/24✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 20 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 20 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 20 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 20 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 20 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 20 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 20 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 20 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 20 times.
✗ Branch 37 not taken.
✗ Branch 41 not taken.
✓ Branch 42 taken 20 times.
|
40 | BOOST_CHECK(v.cross(Force(iF.col(k))).toVector().isApprox(jF.col(k))); |
| 901 | |||
| 902 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jF_ref = v.toDualActionMatrix() * iF; |
| 903 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jF.isApprox(jF_ref)); |
| 904 | |||
| 905 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jF_ref += v.toDualActionMatrix() * iF2; |
| 906 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | forceSet::motionAction<ADDTO>(v, iF2, jF); |
| 907 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jF.isApprox(jF_ref)); |
| 908 | |||
| 909 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jF_ref -= v.toDualActionMatrix() * iF3; |
| 910 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | forceSet::motionAction<RMTO>(v, iF3, jF); |
| 911 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jF.isApprox(jF_ref)); |
| 912 | |||
| 913 | // Motion SET | ||
| 914 | PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH | ||
| 915 | PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED | ||
| 916 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
|
2 | Matrix6N iV = Matrix6N::Random(), jV, jV_ref, jVinv, jVinv_ref; |
| 917 | |||
| 918 | // motionSet::se3Action | ||
| 919 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::se3Action(jMi, iV, jV); |
| 920 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int k = 0; k < N; ++k) |
| 921 |
12/24✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 20 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 20 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 20 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 20 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 20 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 20 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 20 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 20 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 20 times.
✗ Branch 37 not taken.
✗ Branch 41 not taken.
✓ Branch 42 taken 20 times.
|
40 | BOOST_CHECK(jMi.act(Motion(iV.col(k))).toVector().isApprox(jV.col(k))); |
| 922 | |||
| 923 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jV_ref = jMi.toActionMatrix() * iV; |
| 924 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jV.isApprox(jV_ref)); |
| 925 | |||
| 926 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | motionSet::se3ActionInverse(jMi.inverse(), iV, jVinv); |
| 927 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jVinv.isApprox(jV)); |
| 928 | PINOCCHIO_COMPILER_DIAGNOSTIC_POP | ||
| 929 | |||
| 930 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Matrix6N iV2 = Matrix6N::Random(); |
| 931 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jV_ref += jMi.toActionMatrix() * iV2; |
| 932 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::se3Action<ADDTO>(jMi, iV2, jV); |
| 933 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jV.isApprox(jV_ref)); |
| 934 | |||
| 935 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Matrix6N iV3 = Matrix6N::Random(); |
| 936 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jV_ref -= jMi.toActionMatrix() * iV3; |
| 937 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::se3Action<RMTO>(jMi, iV3, jV); |
| 938 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jV.isApprox(jV_ref)); |
| 939 | |||
| 940 | // motionSet::se3ActionInverse | ||
| 941 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::se3ActionInverse(jMi, iV, jVinv); |
| 942 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | jVinv_ref = jMi.inverse().toActionMatrix() * iV; |
| 943 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jVinv.isApprox(jVinv_ref)); |
| 944 | |||
| 945 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | jVinv_ref += jMi.inverse().toActionMatrix() * iV2; |
| 946 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::se3ActionInverse<ADDTO>(jMi, iV2, jVinv); |
| 947 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jVinv.isApprox(jVinv_ref)); |
| 948 | |||
| 949 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | jVinv_ref -= jMi.inverse().toActionMatrix() * iV3; |
| 950 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::se3ActionInverse<RMTO>(jMi, iV3, jVinv); |
| 951 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jVinv.isApprox(jVinv_ref)); |
| 952 | |||
| 953 | // motionSet::motionAction | ||
| 954 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::motionAction(v, iV, jV); |
| 955 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int k = 0; k < N; ++k) |
| 956 |
12/24✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 20 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 20 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 20 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 20 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 20 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 20 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 20 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 20 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 20 times.
✗ Branch 37 not taken.
✗ Branch 41 not taken.
✓ Branch 42 taken 20 times.
|
40 | BOOST_CHECK(v.cross(Motion(iV.col(k))).toVector().isApprox(jV.col(k))); |
| 957 | |||
| 958 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jV_ref = v.toActionMatrix() * iV; |
| 959 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jV.isApprox(jV_ref)); |
| 960 | |||
| 961 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jV_ref += v.toActionMatrix() * iV2; |
| 962 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::motionAction<ADDTO>(v, iV2, jV); |
| 963 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jV.isApprox(jV_ref)); |
| 964 | |||
| 965 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jV_ref -= v.toActionMatrix() * iV3; |
| 966 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::motionAction<RMTO>(v, iV3, jV); |
| 967 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jV.isApprox(jV_ref)); |
| 968 | |||
| 969 | // motionSet::inertiaAction | ||
| 970 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | const Inertia I(Inertia::Random()); |
| 971 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::inertiaAction(I, iV, jV); |
| 972 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int k = 0; k < N; ++k) |
| 973 |
12/24✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 20 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 20 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 20 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 20 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 20 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 20 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 20 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 20 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 20 times.
✗ Branch 37 not taken.
✗ Branch 41 not taken.
✓ Branch 42 taken 20 times.
|
40 | BOOST_CHECK((I * (Motion(iV.col(k)))).toVector().isApprox(jV.col(k))); |
| 974 | |||
| 975 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jV_ref = I.matrix() * iV; |
| 976 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jV.isApprox(jV_ref)); |
| 977 | |||
| 978 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jV_ref += I.matrix() * iV2; |
| 979 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::inertiaAction<ADDTO>(I, iV2, jV); |
| 980 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jV.isApprox(jV_ref)); |
| 981 | |||
| 982 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | jV_ref -= I.matrix() * iV3; |
| 983 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::inertiaAction<RMTO>(I, iV3, jV); |
| 984 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jV.isApprox(jV_ref)); |
| 985 | |||
| 986 | // motionSet::act | ||
| 987 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force f = Force::Random(); |
| 988 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::act(iV, f, jF); |
| 989 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int k = 0; k < N; ++k) |
| 990 |
12/24✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 20 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 20 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 20 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 20 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 20 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 20 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 20 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 20 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 20 times.
✗ Branch 37 not taken.
✗ Branch 41 not taken.
✓ Branch 42 taken 20 times.
|
40 | BOOST_CHECK(Motion(iV.col(k)).cross(f).toVector().isApprox(jF.col(k))); |
| 991 | |||
| 992 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int k = 0; k < N; ++k) |
| 993 |
6/12✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 20 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 20 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 20 times.
✗ Branch 17 not taken.
|
40 | jF_ref.col(k) = Force(Motion(iV.col(k)).cross(f)).toVector(); |
| 994 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jF.isApprox(jF_ref)); |
| 995 | |||
| 996 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int k = 0; k < N; ++k) |
| 997 |
6/12✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 20 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 20 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 20 times.
✗ Branch 17 not taken.
|
40 | jF_ref.col(k) += Force(Motion(iV2.col(k)).cross(f)).toVector(); |
| 998 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::act<ADDTO>(iV2, f, jF); |
| 999 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jF.isApprox(jF_ref)); |
| 1000 | |||
| 1001 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int k = 0; k < N; ++k) |
| 1002 |
6/12✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 20 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 20 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 20 times.
✗ Branch 17 not taken.
|
40 | jF_ref.col(k) -= Force(Motion(iV3.col(k)).cross(f)).toVector(); |
| 1003 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | motionSet::act<RMTO>(iV3, f, jF); |
| 1004 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(jF.isApprox(jF_ref)); |
| 1005 | 2 | } | |
| 1006 | |||
| 1007 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_skew) |
| 1008 | { | ||
| 1009 | using namespace pinocchio; | ||
| 1010 | typedef SE3::Vector3 Vector3; | ||
| 1011 | typedef Motion::Vector6 Vector6; | ||
| 1012 | |||
| 1013 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector3 v3(Vector3::Random()); |
| 1014 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector6 v6(Vector6::Random()); |
| 1015 | |||
| 1016 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector3 res1 = unSkew(skew(v3)); |
| 1017 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(res1.isApprox(v3)); |
| 1018 | |||
| 1019 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | Vector3 res2 = unSkew(skew(v6.head<3>())); |
| 1020 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(res2.isApprox(v6.head<3>())); |
| 1021 | |||
| 1022 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | Vector3 res3 = skew(v3) * v3; |
| 1023 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(res3.isZero()); |
| 1024 | |||
| 1025 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector3 rhs(Vector3::Random()); |
| 1026 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | Vector3 res41 = skew(v3) * rhs; |
| 1027 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Vector3 res42 = v3.cross(rhs); |
| 1028 | |||
| 1029 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(res41.isApprox(res42)); |
| 1030 | 2 | } | |
| 1031 | |||
| 1032 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_addSkew) |
| 1033 | { | ||
| 1034 | using namespace pinocchio; | ||
| 1035 | typedef SE3::Vector3 Vector3; | ||
| 1036 | typedef SE3::Matrix3 Matrix3; | ||
| 1037 | |||
| 1038 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector3 v(Vector3::Random()); |
| 1039 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Matrix3 M(Matrix3::Random()); |
| 1040 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Matrix3 Mcopy(M); |
| 1041 | |||
| 1042 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | addSkew(v, M); |
| 1043 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | Matrix3 Mref = Mcopy + skew(v); |
| 1044 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(M.isApprox(Mref)); |
| 1045 | |||
| 1046 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | Mref += skew(-v); |
| 1047 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | addSkew(-v, M); |
| 1048 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(M.isApprox(Mcopy)); |
| 1049 | |||
| 1050 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | M.setZero(); |
| 1051 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | addSkew(v, M); |
| 1052 |
8/16✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(M.isApprox(skew(v))); |
| 1053 | 2 | } | |
| 1054 | |||
| 1055 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_skew_square) |
| 1056 | { | ||
| 1057 | using namespace pinocchio; | ||
| 1058 | typedef SE3::Vector3 Vector3; | ||
| 1059 | typedef SE3::Matrix3 Matrix3; | ||
| 1060 | |||
| 1061 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector3 u(Vector3::Random()); |
| 1062 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector3 v(Vector3::Random()); |
| 1063 | |||
| 1064 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | Matrix3 ref = skew(u) * skew(v); |
| 1065 | |||
| 1066 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Matrix3 res = skewSquare(u, v); |
| 1067 | |||
| 1068 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(res.isApprox(ref)); |
| 1069 | 2 | } | |
| 1070 | |||
| 1071 | template<int axis> | ||
| 1072 | struct test_scalar_multiplication_cartesian_axis | ||
| 1073 | { | ||
| 1074 | typedef pinocchio::CartesianAxis<axis> Axis; | ||
| 1075 | typedef double Scalar; | ||
| 1076 | typedef Eigen::Matrix<Scalar, 3, 1> Vector3; | ||
| 1077 | |||
| 1078 | 6 | static void run() | |
| 1079 | { | ||
| 1080 | 6 | const Scalar alpha = static_cast<Scalar>(rand()) / static_cast<Scalar>(RAND_MAX); | |
| 1081 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
6 | const Vector3 r1 = Axis() * alpha; |
| 1082 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
6 | const Vector3 r2 = alpha * Axis(); |
| 1083 | |||
| 1084 |
7/14✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 3 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 3 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 3 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 3 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 3 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 3 times.
|
6 | BOOST_CHECK(r1.isApprox(r2)); |
| 1085 | |||
| 1086 |
2/2✓ Branch 0 taken 9 times.
✓ Branch 1 taken 3 times.
|
24 | for (int k = 0; k < Axis::dim; ++k) |
| 1087 | { | ||
| 1088 |
2/2✓ Branch 0 taken 3 times.
✓ Branch 1 taken 6 times.
|
18 | if (k == axis) |
| 1089 | { | ||
| 1090 |
7/14✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 3 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 3 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 3 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 3 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 3 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 3 times.
|
6 | BOOST_CHECK(r1[k] == alpha); |
| 1091 |
7/14✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 3 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 3 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 3 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 3 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 3 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 3 times.
|
6 | BOOST_CHECK(r2[k] == alpha); |
| 1092 | } | ||
| 1093 | else | ||
| 1094 | { | ||
| 1095 |
7/14✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 6 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 6 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 6 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 6 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 6 times.
|
12 | BOOST_CHECK(r1[k] == Scalar(0)); |
| 1096 |
7/14✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 6 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 6 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 6 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 6 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 6 times.
|
12 | BOOST_CHECK(r2[k] == Scalar(0)); |
| 1097 | } | ||
| 1098 | } | ||
| 1099 | 6 | } | |
| 1100 | }; | ||
| 1101 | |||
| 1102 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_cartesian_axis) |
| 1103 | { | ||
| 1104 | using namespace Eigen; | ||
| 1105 | using namespace pinocchio; | ||
| 1106 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector3d v(Vector3d::Random()); |
| 1107 | 2 | const double alpha = 3; | |
| 1108 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector3d v2(alpha * v); |
| 1109 | |||
| 1110 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(XAxis::cross(v).isApprox(Vector3d::Unit(0).cross(v))); |
| 1111 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(YAxis::cross(v).isApprox(Vector3d::Unit(1).cross(v))); |
| 1112 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(ZAxis::cross(v).isApprox(Vector3d::Unit(2).cross(v))); |
| 1113 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(XAxis::alphaCross(alpha, v).isApprox(Vector3d::Unit(0).cross(v2))); |
| 1114 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(YAxis::alphaCross(alpha, v).isApprox(Vector3d::Unit(1).cross(v2))); |
| 1115 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(ZAxis::alphaCross(alpha, v).isApprox(Vector3d::Unit(2).cross(v2))); |
| 1116 | |||
| 1117 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | test_scalar_multiplication_cartesian_axis<0>::run(); |
| 1118 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | test_scalar_multiplication_cartesian_axis<1>::run(); |
| 1119 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | test_scalar_multiplication_cartesian_axis<2>::run(); |
| 1120 | |||
| 1121 | // test Vector value | ||
| 1122 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✗ Branch 31 not taken.
✓ Branch 32 taken 1 times.
|
2 | BOOST_CHECK(XAxis::vector() == Vector3d::UnitX()); |
| 1123 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✗ Branch 31 not taken.
✓ Branch 32 taken 1 times.
|
2 | BOOST_CHECK(YAxis::vector() == Vector3d::UnitY()); |
| 1124 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✗ Branch 31 not taken.
✓ Branch 32 taken 1 times.
|
2 | BOOST_CHECK(ZAxis::vector() == Vector3d::UnitZ()); |
| 1125 | 2 | } | |
| 1126 | |||
| 1127 | template<int axis> | ||
| 1128 | struct test_scalar_multiplication | ||
| 1129 | { | ||
| 1130 | typedef pinocchio::SpatialAxis<axis> Axis; | ||
| 1131 | typedef double Scalar; | ||
| 1132 | typedef pinocchio::MotionTpl<Scalar> Motion; | ||
| 1133 | |||
| 1134 | 12 | static void run() | |
| 1135 | { | ||
| 1136 | 12 | const Scalar alpha = static_cast<Scalar>(rand()) / static_cast<Scalar>(RAND_MAX); | |
| 1137 |
1/2✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
|
12 | const Motion r1 = Axis() * alpha; |
| 1138 |
1/2✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
|
12 | const Motion r2 = alpha * Axis(); |
| 1139 | |||
| 1140 |
7/14✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 6 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 6 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 6 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 6 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 6 times.
|
12 | BOOST_CHECK(r1.isApprox(r2)); |
| 1141 | |||
| 1142 |
2/2✓ Branch 0 taken 36 times.
✓ Branch 1 taken 6 times.
|
84 | for (int k = 0; k < Axis::dim; ++k) |
| 1143 | { | ||
| 1144 |
2/2✓ Branch 0 taken 6 times.
✓ Branch 1 taken 30 times.
|
72 | if (k == axis) |
| 1145 | { | ||
| 1146 |
8/16✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 6 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 6 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 6 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 6 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 6 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 6 times.
|
12 | BOOST_CHECK(r1.toVector()[k] == alpha); |
| 1147 |
8/16✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 6 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 6 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 6 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 6 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 6 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 6 times.
|
12 | BOOST_CHECK(r2.toVector()[k] == alpha); |
| 1148 | } | ||
| 1149 | else | ||
| 1150 | { | ||
| 1151 |
8/16✓ Branch 1 taken 30 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 30 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 30 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 30 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 30 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 30 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 30 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 30 times.
|
60 | BOOST_CHECK(r1.toVector()[k] == Scalar(0)); |
| 1152 |
8/16✓ Branch 1 taken 30 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 30 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 30 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 30 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 30 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 30 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 30 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 30 times.
|
60 | BOOST_CHECK(r2.toVector()[k] == Scalar(0)); |
| 1153 | } | ||
| 1154 | } | ||
| 1155 | 12 | } | |
| 1156 | }; | ||
| 1157 | |||
| 1158 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_spatial_axis) |
| 1159 | { | ||
| 1160 | using namespace pinocchio; | ||
| 1161 | |||
| 1162 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v(Motion::Random()); |
| 1163 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force f(Force::Random()); |
| 1164 | |||
| 1165 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion vaxis; |
| 1166 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | vaxis << AxisVX(); |
| 1167 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(AxisVX::cross(v).isApprox(vaxis.cross(v))); |
| 1168 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(v.cross(AxisVX()).isApprox(v.cross(vaxis))); |
| 1169 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(AxisVX::cross(f).isApprox(vaxis.cross(f))); |
| 1170 | |||
| 1171 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | vaxis << AxisVY(); |
| 1172 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(AxisVY::cross(v).isApprox(vaxis.cross(v))); |
| 1173 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(v.cross(AxisVY()).isApprox(v.cross(vaxis))); |
| 1174 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(AxisVY::cross(f).isApprox(vaxis.cross(f))); |
| 1175 | |||
| 1176 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | vaxis << AxisVZ(); |
| 1177 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(AxisVZ::cross(v).isApprox(vaxis.cross(v))); |
| 1178 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(v.cross(AxisVZ()).isApprox(v.cross(vaxis))); |
| 1179 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(AxisVZ::cross(f).isApprox(vaxis.cross(f))); |
| 1180 | |||
| 1181 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | vaxis << AxisWX(); |
| 1182 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(AxisWX::cross(v).isApprox(vaxis.cross(v))); |
| 1183 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(v.cross(AxisWX()).isApprox(v.cross(vaxis))); |
| 1184 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(AxisWX::cross(f).isApprox(vaxis.cross(f))); |
| 1185 | |||
| 1186 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | vaxis << AxisWY(); |
| 1187 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(AxisWY::cross(v).isApprox(vaxis.cross(v))); |
| 1188 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(v.cross(AxisWY()).isApprox(v.cross(vaxis))); |
| 1189 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(AxisWY::cross(f).isApprox(vaxis.cross(f))); |
| 1190 | |||
| 1191 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | vaxis << AxisWZ(); |
| 1192 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(AxisWZ::cross(v).isApprox(vaxis.cross(v))); |
| 1193 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(v.cross(AxisWZ()).isApprox(v.cross(vaxis))); |
| 1194 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(AxisWZ::cross(f).isApprox(vaxis.cross(f))); |
| 1195 | |||
| 1196 | // Test operation Axis * Scalar | ||
| 1197 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | test_scalar_multiplication<0>::run(); |
| 1198 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | test_scalar_multiplication<1>::run(); |
| 1199 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | test_scalar_multiplication<2>::run(); |
| 1200 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | test_scalar_multiplication<3>::run(); |
| 1201 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | test_scalar_multiplication<4>::run(); |
| 1202 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | test_scalar_multiplication<5>::run(); |
| 1203 | |||
| 1204 | // Operations of Constraint on forces Sxf | ||
| 1205 | typedef Motion::ActionMatrixType ActionMatrixType; | ||
| 1206 | typedef ActionMatrixType::ColXpr ColType; | ||
| 1207 | typedef ForceRef<ColType> ForceRefOnColType; | ||
| 1208 | typedef MotionRef<ColType> MotionRefOnColType; | ||
| 1209 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | ActionMatrixType Sxf, Sxf_ref; |
| 1210 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | ActionMatrixType S(ActionMatrixType::Identity()); |
| 1211 | |||
| 1212 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | SpatialAxis<0>::cross(f, ForceRefOnColType(Sxf.col(0))); |
| 1213 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | SpatialAxis<1>::cross(f, ForceRefOnColType(Sxf.col(1))); |
| 1214 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | SpatialAxis<2>::cross(f, ForceRefOnColType(Sxf.col(2))); |
| 1215 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | SpatialAxis<3>::cross(f, ForceRefOnColType(Sxf.col(3))); |
| 1216 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | SpatialAxis<4>::cross(f, ForceRefOnColType(Sxf.col(4))); |
| 1217 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | SpatialAxis<5>::cross(f, ForceRefOnColType(Sxf.col(5))); |
| 1218 | |||
| 1219 |
2/2✓ Branch 0 taken 6 times.
✓ Branch 1 taken 1 times.
|
14 | for (int k = 0; k < 6; ++k) |
| 1220 | { | ||
| 1221 |
2/4✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
|
12 | MotionRefOnColType Scol(S.col(k)); |
| 1222 |
4/8✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 6 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 6 times.
✗ Branch 11 not taken.
|
12 | ForceRefOnColType(Sxf_ref.col(k)) = Scol.cross(f); |
| 1223 | } | ||
| 1224 | |||
| 1225 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(Sxf.isApprox(Sxf_ref)); |
| 1226 | 2 | } | |
| 1227 | |||
| 1228 | BOOST_AUTO_TEST_SUITE_END() | ||
| 1229 |