| Directory: | ./ |
|---|---|
| File: | unittest/cartesian-product-liegroups.cpp |
| Date: | 2025-02-12 21:03:38 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 69 | 69 | 100.0% |
| Branches: | 263 | 508 | 51.8% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // | ||
| 2 | // Copyright (c) 2020 INRIA | ||
| 3 | // | ||
| 4 | |||
| 5 | #include "pinocchio/multibody/liegroup/liegroup.hpp" | ||
| 6 | #include "pinocchio/multibody/liegroup/liegroup-collection.hpp" | ||
| 7 | #include "pinocchio/multibody/liegroup/liegroup-generic.hpp" | ||
| 8 | #include "pinocchio/multibody/liegroup/cartesian-product-variant.hpp" | ||
| 9 | #include "pinocchio/multibody/liegroup/cartesian-product.hpp" | ||
| 10 | |||
| 11 | #include "pinocchio/multibody/joint/joint-generic.hpp" | ||
| 12 | |||
| 13 | #include <iostream> | ||
| 14 | #include <boost/test/unit_test.hpp> | ||
| 15 | #include <boost/utility/binary.hpp> | ||
| 16 | #include <boost/algorithm/string.hpp> | ||
| 17 | |||
| 18 | using namespace pinocchio; | ||
| 19 | |||
| 20 | namespace pinocchio | ||
| 21 | { | ||
| 22 | template<typename Derived> | ||
| 23 | 1 | std::ostream & operator<<(std::ostream & os, const LieGroupBase<Derived> & lg) | |
| 24 | { | ||
| 25 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
1 | return os << lg.name(); |
| 26 | } | ||
| 27 | template<typename LieGroupCollection> | ||
| 28 | std::ostream & operator<<(std::ostream & os, const LieGroupGenericTpl<LieGroupCollection> & lg) | ||
| 29 | { | ||
| 30 | return os << lg.name(); | ||
| 31 | } | ||
| 32 | } // namespace pinocchio | ||
| 33 | |||
| 34 | template<typename Scalar, int Options, template<typename S, int O> class LieGroupCollectionTpl> | ||
| 35 | struct TestCartesianProduct | ||
| 36 | { | ||
| 37 | |||
| 38 | typedef LieGroupCollectionTpl<Scalar, Options> LieGroupCollection; | ||
| 39 | |||
| 40 | typedef LieGroupGenericTpl<LieGroupCollection> LieGroupGeneric; | ||
| 41 | typedef typename LieGroupGeneric::ConfigVector_t ConfigVector_t; | ||
| 42 | typedef typename LieGroupGeneric::TangentVector_t TangentVector_t; | ||
| 43 | |||
| 44 | typedef CartesianProductOperationVariantTpl<Scalar, Options, LieGroupCollectionTpl> | ||
| 45 | CartesianProduct; | ||
| 46 | |||
| 47 | template<typename Derived> | ||
| 48 | 16 | void operator()(const LieGroupBase<Derived> & lg) const | |
| 49 | { | ||
| 50 |
1/2✓ Branch 2 taken 8 times.
✗ Branch 3 not taken.
|
16 | LieGroupGenericTpl<LieGroupCollection> lg_generic(lg.derived()); |
| 51 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | CartesianProduct cp(lg_generic); |
| 52 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | test(lg, cp); |
| 53 | |||
| 54 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | CartesianProduct cp2; |
| 55 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | cp2.append(lg); |
| 56 |
7/14✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 8 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 8 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 8 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 8 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 8 times.
|
16 | BOOST_CHECK(cp == cp2); |
| 57 | 16 | } | |
| 58 | |||
| 59 | template<typename LieGroup> | ||
| 60 | 18 | static void test(const LieGroupBase<LieGroup> & lg, const CartesianProduct & cp) | |
| 61 | { | ||
| 62 |
10/19✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 9 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 7 times.
✗ Branch 15 not taken.
✓ Branch 16 taken 2 times.
✗ Branch 17 not taken.
✓ Branch 18 taken 7 times.
✓ Branch 19 taken 2 times.
✗ Branch 20 not taken.
✓ Branch 21 taken 7 times.
✗ Branch 22 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 2 times.
✗ Branch 26 not taken.
✓ Branch 27 taken 7 times.
|
18 | BOOST_CHECK(lg.nq() == cp.nq()); |
| 63 |
10/19✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 9 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 7 times.
✗ Branch 15 not taken.
✓ Branch 16 taken 2 times.
✗ Branch 17 not taken.
✓ Branch 18 taken 7 times.
✓ Branch 19 taken 2 times.
✗ Branch 20 not taken.
✓ Branch 21 taken 7 times.
✗ Branch 22 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 2 times.
✗ Branch 26 not taken.
✓ Branch 27 taken 7 times.
|
18 | BOOST_CHECK(lg.nv() == cp.nv()); |
| 64 | |||
| 65 |
4/8✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 9 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 9 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 9 times.
✗ Branch 11 not taken.
|
18 | std::cout << "name: " << cp.name() << std::endl; |
| 66 | |||
| 67 |
10/19✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 9 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 9 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 9 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 9 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 9 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 9 times.
✗ Branch 27 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 8 times.
✓ Branch 34 taken 1 times.
|
18 | BOOST_CHECK(lg.neutral() == cp.neutral()); |
| 68 | |||
| 69 | typedef typename LieGroup::ConfigVector_t ConfigVector; | ||
| 70 | typedef typename LieGroup::TangentVector_t TangentVector; | ||
| 71 | typedef typename LieGroup::JacobianMatrix_t JacobianMatrix; | ||
| 72 | |||
| 73 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | ConfigVector q0 = lg.random(); |
| 74 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | ConfigVector q1 = lg.random(); |
| 75 |
5/8✓ Branch 1 taken 7 times.
✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 7 times.
✓ Branch 5 taken 2 times.
✗ Branch 6 not taken.
✓ Branch 7 taken 7 times.
✗ Branch 8 not taken.
|
18 | TangentVector v = TangentVector_t::Random(lg.nv()); |
| 76 | PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH | ||
| 77 | PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED | ||
| 78 |
6/10✓ Branch 1 taken 7 times.
✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 7 times.
✗ Branch 5 not taken.
✓ Branch 6 taken 2 times.
✓ Branch 7 taken 7 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 7 times.
✗ Branch 11 not taken.
|
18 | ConfigVector qout_ref(lg.nq()), qout(lg.nq()); |
| 79 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | lg.integrate(q0, v, qout_ref); |
| 80 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | cp.integrate(q0, v, qout); |
| 81 | PINOCCHIO_COMPILER_DIAGNOSTIC_POP | ||
| 82 | |||
| 83 |
7/14✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 9 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 9 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 9 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 9 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 9 times.
|
18 | BOOST_CHECK(qout.isApprox(qout_ref)); |
| 84 | |||
| 85 | PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH | ||
| 86 | PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED | ||
| 87 |
6/10✓ Branch 1 taken 7 times.
✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 7 times.
✗ Branch 5 not taken.
✓ Branch 6 taken 2 times.
✓ Branch 7 taken 7 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 7 times.
✗ Branch 11 not taken.
|
18 | TangentVector v_diff_ref(lg.nv()), v_diff(lg.nv()); |
| 88 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | lg.difference(q0, q1, v_diff_ref); |
| 89 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | cp.difference(q0, q1, v_diff); |
| 90 | PINOCCHIO_COMPILER_DIAGNOSTIC_POP | ||
| 91 | |||
| 92 |
7/14✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 9 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 9 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 9 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 9 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 9 times.
|
18 | BOOST_CHECK(v_diff_ref.isApprox(v_diff)); |
| 93 |
7/14✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 9 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 9 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 9 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 9 times.
✗ Branch 20 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 9 times.
|
18 | BOOST_CHECK_EQUAL(lg.squaredDistance(q0, q1), cp.squaredDistance(q0, q1)); |
| 94 |
7/14✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 9 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 9 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 9 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 9 times.
✗ Branch 20 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 9 times.
|
18 | BOOST_CHECK_EQUAL(lg.distance(q0, q1), cp.distance(q0, q1)); |
| 95 | |||
| 96 |
6/10✓ Branch 1 taken 7 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 2 times.
✓ Branch 4 taken 7 times.
✗ Branch 5 not taken.
✓ Branch 6 taken 2 times.
✓ Branch 7 taken 7 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 7 times.
✗ Branch 11 not taken.
|
18 | JacobianMatrix J_ref(JacobianMatrix::Zero(lg.nv(), lg.nv())), |
| 97 |
6/10✓ Branch 1 taken 7 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 2 times.
✓ Branch 4 taken 7 times.
✗ Branch 5 not taken.
✓ Branch 6 taken 2 times.
✓ Branch 7 taken 7 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 7 times.
✗ Branch 11 not taken.
|
18 | J(JacobianMatrix::Zero(lg.nv(), lg.nv())); |
| 98 | |||
| 99 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | lg.dDifference(q0, q1, J_ref, ARG0); |
| 100 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | cp.dDifference(q0, q1, J, ARG0); |
| 101 | |||
| 102 |
7/14✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 9 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 9 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 9 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 9 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 9 times.
|
18 | BOOST_CHECK(J.isApprox(J_ref)); |
| 103 | |||
| 104 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | lg.dDifference(q0, q1, J_ref, ARG1); |
| 105 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | cp.dDifference(q0, q1, J, ARG1); |
| 106 | |||
| 107 |
7/14✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 9 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 9 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 9 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 9 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 9 times.
|
18 | BOOST_CHECK(J.isApprox(J_ref)); |
| 108 | |||
| 109 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | lg.dIntegrate(q0, v, J_ref, ARG0); |
| 110 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | cp.dIntegrate(q0, v, J, ARG0); |
| 111 | |||
| 112 |
7/14✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 9 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 9 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 9 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 9 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 9 times.
|
18 | BOOST_CHECK(J.isApprox(J_ref)); |
| 113 | |||
| 114 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | lg.dIntegrate(q0, v, J_ref, ARG1); |
| 115 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | cp.dIntegrate(q0, v, J, ARG1); |
| 116 | |||
| 117 |
7/14✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 9 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 9 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 9 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 9 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 9 times.
|
18 | BOOST_CHECK(J.isApprox(J_ref)); |
| 118 | |||
| 119 |
7/14✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 9 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 9 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 9 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 9 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 9 times.
|
18 | BOOST_CHECK(cp.isSameConfiguration(q0, q0)); |
| 120 | PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH | ||
| 121 | PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED | ||
| 122 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | ConfigVector q_rand; |
| 123 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | cp.random(q_rand); |
| 124 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | ConfigVector q_rand_copy = q_rand; |
| 125 | |||
| 126 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | lg.normalize(q_rand_copy); |
| 127 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | cp.normalize(q_rand); |
| 128 |
7/14✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 9 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 9 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 9 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 9 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 9 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 9 times.
|
18 | BOOST_CHECK(q_rand.isApprox(q_rand_copy)); |
| 129 | |||
| 130 |
7/11✓ Branch 1 taken 7 times.
✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 7 times.
✓ Branch 5 taken 2 times.
✗ Branch 6 not taken.
✓ Branch 7 taken 7 times.
✓ Branch 8 taken 2 times.
✗ Branch 9 not taken.
✓ Branch 10 taken 7 times.
✗ Branch 11 not taken.
|
18 | const ConfigVector lb(-ConfigVector::Ones(lg.nq())); |
| 131 |
5/8✓ Branch 1 taken 7 times.
✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 7 times.
✓ Branch 5 taken 2 times.
✗ Branch 6 not taken.
✓ Branch 7 taken 7 times.
✗ Branch 8 not taken.
|
18 | const ConfigVector ub(ConfigVector::Ones(lg.nq())); |
| 132 | |||
| 133 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | cp.randomConfiguration(lb, ub, q_rand); |
| 134 | PINOCCHIO_COMPILER_DIAGNOSTIC_POP | ||
| 135 | 18 | } | |
| 136 | }; | ||
| 137 | |||
| 138 | BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) | ||
| 139 | |||
| 140 |
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_product_with_liegroup_variant) |
| 141 | { | ||
| 142 | 2 | boost::mpl::for_each<LieGroupCollectionDefault::LieGroupVariant::types>( | |
| 143 | TestCartesianProduct<double, 0, LieGroupCollectionDefaultTpl>()); | ||
| 144 | 2 | } | |
| 145 | |||
| 146 |
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_product_vs_cartesian_product_variant) |
| 147 | { | ||
| 148 | typedef SpecialEuclideanOperationTpl<3, double, 0> SE3; | ||
| 149 | typedef VectorSpaceOperationTpl<3, double, 0> Rn; | ||
| 150 | |||
| 151 | typedef CartesianProductOperation<SE3, Rn> CPRef; | ||
| 152 | typedef CartesianProductOperationVariantTpl<double, 0, LieGroupCollectionDefaultTpl> CP; | ||
| 153 | |||
| 154 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 lg1; |
| 155 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Rn lg2; |
| 156 | typedef LieGroupGenericTpl<CP::LieGroupCollection> LieGroupGeneric; | ||
| 157 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | LieGroupGeneric lg1_variant(lg1); |
| 158 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | LieGroupGeneric lg2_variant(lg2); |
| 159 | |||
| 160 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | CP cartesian_product(lg1_variant, lg2_variant); |
| 161 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | CP cartesian_product2(lg1_variant); |
| 162 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | cartesian_product2.append(lg2_variant); |
| 163 |
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 | std::cout << "cartesian_product: " << cartesian_product << std::endl; |
| 164 | |||
| 165 |
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(cartesian_product == cartesian_product2); |
| 166 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | CPRef cartesian_product_ref; |
| 167 | |||
| 168 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | TestCartesianProduct<double, 0, LieGroupCollectionDefaultTpl>::test( |
| 169 | cartesian_product_ref, cartesian_product); | ||
| 170 | 2 | } | |
| 171 | |||
| 172 | BOOST_AUTO_TEST_SUITE_END() | ||
| 173 |