| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | /* | ||
| 2 | * Software License Agreement (BSD License) | ||
| 3 | * | ||
| 4 | * Copyright (c) 2011-2014, Willow Garage, Inc. | ||
| 5 | * Copyright (c) 2014-2016, Open Source Robotics Foundation | ||
| 6 | * All rights reserved. | ||
| 7 | * | ||
| 8 | * Redistribution and use in source and binary forms, with or without | ||
| 9 | * modification, are permitted provided that the following conditions | ||
| 10 | * are met: | ||
| 11 | * | ||
| 12 | * * Redistributions of source code must retain the above copyright | ||
| 13 | * notice, this list of conditions and the following disclaimer. | ||
| 14 | * * Redistributions in binary form must reproduce the above | ||
| 15 | * copyright notice, this list of conditions and the following | ||
| 16 | * disclaimer in the documentation and/or other materials provided | ||
| 17 | * with the distribution. | ||
| 18 | * * Neither the name of Open Source Robotics Foundation nor the names of its | ||
| 19 | * contributors may be used to endorse or promote products derived | ||
| 20 | * from this software without specific prior written permission. | ||
| 21 | * | ||
| 22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS | ||
| 23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT | ||
| 24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS | ||
| 25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE | ||
| 26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, | ||
| 27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, | ||
| 28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; | ||
| 29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER | ||
| 30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT | ||
| 31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN | ||
| 32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE | ||
| 33 | * POSSIBILITY OF SUCH DAMAGE. | ||
| 34 | */ | ||
| 35 | |||
| 36 | /** @author Jia Pan */ | ||
| 37 | |||
| 38 | #define BOOST_TEST_MODULE COAL_BROADPHASE_COLLISION_2 | ||
| 39 | #include <boost/test/included/unit_test.hpp> | ||
| 40 | |||
| 41 | #include "coal/broadphase/broadphase_bruteforce.h" | ||
| 42 | #include "coal/broadphase/broadphase_spatialhash.h" | ||
| 43 | #include "coal/broadphase/broadphase_SaP.h" | ||
| 44 | #include "coal/broadphase/broadphase_SSaP.h" | ||
| 45 | #include "coal/broadphase/broadphase_interval_tree.h" | ||
| 46 | #include "coal/broadphase/broadphase_dynamic_AABB_tree.h" | ||
| 47 | #include "coal/broadphase/broadphase_dynamic_AABB_tree_array.h" | ||
| 48 | #include "coal/broadphase/default_broadphase_callbacks.h" | ||
| 49 | #include "coal/broadphase/detail/sparse_hash_table.h" | ||
| 50 | #include "coal/broadphase/detail/spatial_hash.h" | ||
| 51 | #include "utility.h" | ||
| 52 | |||
| 53 | #if USE_GOOGLEHASH | ||
| 54 | #include <sparsehash/sparse_hash_map> | ||
| 55 | #include <sparsehash/dense_hash_map> | ||
| 56 | #include <hash_map> | ||
| 57 | #endif | ||
| 58 | |||
| 59 | #include <iostream> | ||
| 60 | #include <iomanip> | ||
| 61 | |||
| 62 | using namespace coal; | ||
| 63 | |||
| 64 | /// @brief test for broad phase collision and self collision | ||
| 65 | void broad_phase_collision_test(Scalar env_scale, std::size_t env_size, | ||
| 66 | std::size_t query_size, | ||
| 67 | std::size_t num_max_contacts = 1, | ||
| 68 | bool exhaustive = false, bool use_mesh = false); | ||
| 69 | |||
| 70 | #if USE_GOOGLEHASH | ||
| 71 | template <typename U, typename V> | ||
| 72 | struct GoogleSparseHashTable | ||
| 73 | : public google::sparse_hash_map<U, V, std::tr1::hash<size_t>, | ||
| 74 | std::equal_to<size_t> > {}; | ||
| 75 | |||
| 76 | template <typename U, typename V> | ||
| 77 | struct GoogleDenseHashTable | ||
| 78 | : public google::dense_hash_map<U, V, std::tr1::hash<size_t>, | ||
| 79 | std::equal_to<size_t> > { | ||
| 80 | GoogleDenseHashTable() | ||
| 81 | : google::dense_hash_map<U, V, std::tr1::hash<size_t>, | ||
| 82 | std::equal_to<size_t> >() { | ||
| 83 | this->set_empty_key(nullptr); | ||
| 84 | } | ||
| 85 | }; | ||
| 86 | #endif | ||
| 87 | |||
| 88 | /// check broad phase collision for empty collision object set and queries | ||
| 89 |
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_core_bf_broad_phase_collision_empty) { |
| 90 | #ifdef NDEBUG | ||
| 91 | broad_phase_collision_test(2000, 0, 0, 10, false, false); | ||
| 92 | broad_phase_collision_test(2000, 0, 1000, 10, false, false); | ||
| 93 | broad_phase_collision_test(2000, 100, 0, 10, false, false); | ||
| 94 | |||
| 95 | broad_phase_collision_test(2000, 0, 0, 10, false, true); | ||
| 96 | broad_phase_collision_test(2000, 0, 1000, 10, false, true); | ||
| 97 | broad_phase_collision_test(2000, 100, 0, 10, false, true); | ||
| 98 | |||
| 99 | broad_phase_collision_test(2000, 0, 0, 10, true, false); | ||
| 100 | broad_phase_collision_test(2000, 0, 1000, 10, true, false); | ||
| 101 | broad_phase_collision_test(2000, 100, 0, 10, true, false); | ||
| 102 | |||
| 103 | broad_phase_collision_test(2000, 0, 0, 10, true, true); | ||
| 104 | broad_phase_collision_test(2000, 0, 1000, 10, true, true); | ||
| 105 | broad_phase_collision_test(2000, 100, 0, 10, true, true); | ||
| 106 | #else | ||
| 107 | 2 | broad_phase_collision_test(2000, 0, 0, 10, false, false); | |
| 108 | 2 | broad_phase_collision_test(2000, 0, 5, 10, false, false); | |
| 109 | 2 | broad_phase_collision_test(2000, 2, 0, 10, false, false); | |
| 110 | |||
| 111 | 2 | broad_phase_collision_test(2000, 0, 0, 10, false, true); | |
| 112 | 2 | broad_phase_collision_test(2000, 0, 5, 10, false, true); | |
| 113 | 2 | broad_phase_collision_test(2000, 2, 0, 10, false, true); | |
| 114 | |||
| 115 | 2 | broad_phase_collision_test(2000, 0, 0, 10, true, false); | |
| 116 | 2 | broad_phase_collision_test(2000, 0, 5, 10, true, false); | |
| 117 | 2 | broad_phase_collision_test(2000, 2, 0, 10, true, false); | |
| 118 | |||
| 119 | 2 | broad_phase_collision_test(2000, 0, 0, 10, true, true); | |
| 120 | 2 | broad_phase_collision_test(2000, 0, 5, 10, true, true); | |
| 121 | 2 | broad_phase_collision_test(2000, 2, 0, 10, true, true); | |
| 122 | #endif | ||
| 123 | 2 | } | |
| 124 | |||
| 125 | /// check broad phase collision and self collision, only return collision or not | ||
| 126 |
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_core_bf_broad_phase_collision_binary) { |
| 127 | #ifdef NDEBUG | ||
| 128 | broad_phase_collision_test(2000, 100, 1000, 1, false); | ||
| 129 | broad_phase_collision_test(2000, 1000, 1000, 1, false); | ||
| 130 | broad_phase_collision_test(2000, 100, 1000, 1, true); | ||
| 131 | broad_phase_collision_test(2000, 1000, 1000, 1, true); | ||
| 132 | #else | ||
| 133 | 2 | broad_phase_collision_test(2000, 10, 100, 1, false); | |
| 134 | 2 | broad_phase_collision_test(2000, 100, 100, 1, false); | |
| 135 | 2 | broad_phase_collision_test(2000, 10, 100, 1, true); | |
| 136 | 2 | broad_phase_collision_test(2000, 100, 100, 1, true); | |
| 137 | #endif | ||
| 138 | 2 | } | |
| 139 | |||
| 140 | /// check broad phase collision and self collision, return 10 contacts | ||
| 141 |
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_core_bf_broad_phase_collision) { |
| 142 | #ifdef NDEBUG | ||
| 143 | broad_phase_collision_test(2000, 100, 1000, 10, false); | ||
| 144 | broad_phase_collision_test(2000, 1000, 1000, 10, false); | ||
| 145 | #else | ||
| 146 | 2 | broad_phase_collision_test(2000, 10, 100, 10, false); | |
| 147 | 2 | broad_phase_collision_test(2000, 100, 100, 10, false); | |
| 148 | #endif | ||
| 149 | 2 | } | |
| 150 | |||
| 151 | /// check broad phase collision and self collision, return only collision or | ||
| 152 | /// not, in mesh | ||
| 153 |
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_core_mesh_bf_broad_phase_collision_mesh_binary) { |
| 154 | #ifdef NDEBUG | ||
| 155 | broad_phase_collision_test(2000, 100, 1000, 1, false, true); | ||
| 156 | broad_phase_collision_test(2000, 1000, 1000, 1, false, true); | ||
| 157 | #else | ||
| 158 | 2 | broad_phase_collision_test(2000, 2, 5, 1, false, true); | |
| 159 | 2 | broad_phase_collision_test(2000, 5, 5, 1, false, true); | |
| 160 | #endif | ||
| 161 | 2 | } | |
| 162 | |||
| 163 | /// check broad phase collision and self collision, return 10 contacts, in mesh | ||
| 164 |
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_core_mesh_bf_broad_phase_collision_mesh) { |
| 165 | #ifdef NDEBUG | ||
| 166 | broad_phase_collision_test(2000, 100, 1000, 10, false, true); | ||
| 167 | broad_phase_collision_test(2000, 1000, 1000, 10, false, true); | ||
| 168 | #else | ||
| 169 | 2 | broad_phase_collision_test(2000, 2, 5, 10, false, true); | |
| 170 | 2 | broad_phase_collision_test(2000, 5, 5, 10, false, true); | |
| 171 | #endif | ||
| 172 | 2 | } | |
| 173 | |||
| 174 | /// check broad phase collision and self collision, exhaustive, in mesh | ||
| 175 |
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_core_mesh_bf_broad_phase_collision_mesh_exhaustive) { |
| 176 | #ifdef NDEBUG | ||
| 177 | broad_phase_collision_test(2000, 100, 1000, 1, true, true); | ||
| 178 | broad_phase_collision_test(2000, 1000, 1000, 1, true, true); | ||
| 179 | #else | ||
| 180 | 2 | broad_phase_collision_test(2000, 2, 5, 1, true, true); | |
| 181 | 2 | broad_phase_collision_test(2000, 5, 5, 1, true, true); | |
| 182 | #endif | ||
| 183 | 2 | } | |
| 184 | |||
| 185 | 24 | void broad_phase_collision_test(Scalar env_scale, std::size_t env_size, | |
| 186 | std::size_t query_size, | ||
| 187 | std::size_t num_max_contacts, bool exhaustive, | ||
| 188 | bool use_mesh) { | ||
| 189 | 24 | std::vector<TStruct> ts; | |
| 190 | 24 | std::vector<BenchTimer> timers; | |
| 191 | |||
| 192 | 24 | std::vector<CollisionObject*> env; | |
| 193 |
2/2✓ Branch 0 taken 12 times.
✓ Branch 1 taken 12 times.
|
24 | if (use_mesh) |
| 194 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
12 | generateEnvironmentsMesh(env, env_scale, env_size); |
| 195 | else | ||
| 196 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
12 | generateEnvironments(env, env_scale, env_size); |
| 197 | |||
| 198 | 24 | std::vector<CollisionObject*> query; | |
| 199 |
2/2✓ Branch 0 taken 12 times.
✓ Branch 1 taken 12 times.
|
24 | if (use_mesh) |
| 200 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
12 | generateEnvironmentsMesh(query, env_scale, query_size); |
| 201 | else | ||
| 202 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
12 | generateEnvironments(query, env_scale, query_size); |
| 203 | |||
| 204 | 24 | std::vector<BroadPhaseCollisionManager*> managers; | |
| 205 | |||
| 206 |
3/8✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
|
24 | managers.push_back(new NaiveCollisionManager()); |
| 207 |
3/8✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
|
24 | managers.push_back(new SSaPCollisionManager()); |
| 208 |
3/8✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
|
24 | managers.push_back(new SaPCollisionManager()); |
| 209 |
3/8✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
|
24 | managers.push_back(new IntervalTreeCollisionManager()); |
| 210 | |||
| 211 |
2/4✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
|
24 | Vec3s lower_limit, upper_limit; |
| 212 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
24 | SpatialHashingCollisionManager<>::computeBound(env, lower_limit, upper_limit); |
| 213 | // Scalar ncell_per_axis = std::pow((S)env_size / 10, 1 / 3.0); | ||
| 214 | 24 | Scalar ncell_per_axis = 20; | |
| 215 | Scalar cell_size = | ||
| 216 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
24 | std::min(std::min((upper_limit[0] - lower_limit[0]) / ncell_per_axis, |
| 217 |
2/4✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
|
24 | (upper_limit[1] - lower_limit[1]) / ncell_per_axis), |
| 218 |
3/6✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
|
24 | (upper_limit[2] - lower_limit[2]) / ncell_per_axis); |
| 219 | // managers.push_back(new SpatialHashingCollisionManager(cell_size, | ||
| 220 | // lower_limit, upper_limit)); | ||
| 221 |
1/4✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✗ Branch 4 not taken.
|
24 | managers.push_back(new SpatialHashingCollisionManager<detail::SparseHashTable< |
| 222 | AABB, CollisionObject*, detail::SpatialHash> >( | ||
| 223 |
2/4✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
|
24 | cell_size, lower_limit, upper_limit)); |
| 224 | #if USE_GOOGLEHASH | ||
| 225 | managers.push_back( | ||
| 226 | new SpatialHashingCollisionManager<detail::SparseHashTable< | ||
| 227 | AABB, CollisionObject*, detail::SpatialHash, GoogleSparseHashTable> >( | ||
| 228 | cell_size, lower_limit, upper_limit)); | ||
| 229 | managers.push_back( | ||
| 230 | new SpatialHashingCollisionManager<detail::SparseHashTable< | ||
| 231 | AABB, CollisionObject*, detail::SpatialHash, GoogleDenseHashTable> >( | ||
| 232 | cell_size, lower_limit, upper_limit)); | ||
| 233 | #endif | ||
| 234 |
3/8✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
|
24 | managers.push_back(new DynamicAABBTreeCollisionManager()); |
| 235 | |||
| 236 |
3/8✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
|
24 | managers.push_back(new DynamicAABBTreeArrayCollisionManager()); |
| 237 | |||
| 238 | { | ||
| 239 |
2/6✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
|
24 | DynamicAABBTreeCollisionManager* m = new DynamicAABBTreeCollisionManager(); |
| 240 | 24 | m->tree_init_level = 2; | |
| 241 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
24 | managers.push_back(m); |
| 242 | } | ||
| 243 | |||
| 244 | { | ||
| 245 | DynamicAABBTreeArrayCollisionManager* m = | ||
| 246 |
2/6✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
|
24 | new DynamicAABBTreeArrayCollisionManager(); |
| 247 | 24 | m->tree_init_level = 2; | |
| 248 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
24 | managers.push_back(m); |
| 249 | } | ||
| 250 | |||
| 251 |
1/2✓ Branch 2 taken 24 times.
✗ Branch 3 not taken.
|
24 | ts.resize(managers.size()); |
| 252 |
1/2✓ Branch 2 taken 24 times.
✗ Branch 3 not taken.
|
24 | timers.resize(managers.size()); |
| 253 | |||
| 254 |
2/2✓ Branch 1 taken 216 times.
✓ Branch 2 taken 24 times.
|
240 | for (size_t i = 0; i < managers.size(); ++i) { |
| 255 |
1/2✓ Branch 2 taken 216 times.
✗ Branch 3 not taken.
|
216 | timers[i].start(); |
| 256 |
1/2✓ Branch 2 taken 216 times.
✗ Branch 3 not taken.
|
216 | managers[i]->registerObjects(env); |
| 257 |
1/2✓ Branch 2 taken 216 times.
✗ Branch 3 not taken.
|
216 | timers[i].stop(); |
| 258 |
2/4✓ Branch 3 taken 216 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 216 times.
✗ Branch 7 not taken.
|
216 | ts[i].push_back(timers[i].getElapsedTime()); |
| 259 | } | ||
| 260 | |||
| 261 |
2/2✓ Branch 1 taken 216 times.
✓ Branch 2 taken 24 times.
|
240 | for (size_t i = 0; i < managers.size(); ++i) { |
| 262 |
1/2✓ Branch 2 taken 216 times.
✗ Branch 3 not taken.
|
216 | timers[i].start(); |
| 263 |
1/2✓ Branch 2 taken 216 times.
✗ Branch 3 not taken.
|
216 | managers[i]->setup(); |
| 264 |
1/2✓ Branch 2 taken 216 times.
✗ Branch 3 not taken.
|
216 | timers[i].stop(); |
| 265 |
2/4✓ Branch 3 taken 216 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 216 times.
✗ Branch 7 not taken.
|
216 | ts[i].push_back(timers[i].getElapsedTime()); |
| 266 | } | ||
| 267 | |||
| 268 |
1/2✓ Branch 2 taken 24 times.
✗ Branch 3 not taken.
|
24 | std::vector<CollisionCallBackDefault> callbacks(managers.size()); |
| 269 |
2/2✓ Branch 1 taken 216 times.
✓ Branch 2 taken 24 times.
|
240 | for (size_t i = 0; i < managers.size(); ++i) { |
| 270 |
2/2✓ Branch 0 taken 90 times.
✓ Branch 1 taken 126 times.
|
216 | if (exhaustive) |
| 271 | 90 | callbacks[i].data.request.num_max_contacts = 100000; | |
| 272 | else | ||
| 273 | 126 | callbacks[i].data.request.num_max_contacts = num_max_contacts; | |
| 274 | } | ||
| 275 | |||
| 276 |
2/2✓ Branch 1 taken 216 times.
✓ Branch 2 taken 24 times.
|
240 | for (size_t i = 0; i < managers.size(); ++i) { |
| 277 |
1/2✓ Branch 2 taken 216 times.
✗ Branch 3 not taken.
|
216 | timers[i].start(); |
| 278 |
1/2✓ Branch 3 taken 216 times.
✗ Branch 4 not taken.
|
216 | managers[i]->collide(&callbacks[i]); |
| 279 |
1/2✓ Branch 2 taken 216 times.
✗ Branch 3 not taken.
|
216 | timers[i].stop(); |
| 280 |
2/4✓ Branch 3 taken 216 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 216 times.
✗ Branch 7 not taken.
|
216 | ts[i].push_back(timers[i].getElapsedTime()); |
| 281 | } | ||
| 282 | |||
| 283 |
2/2✓ Branch 1 taken 216 times.
✓ Branch 2 taken 24 times.
|
240 | for (size_t i = 0; i < managers.size(); ++i) |
| 284 |
2/4✓ Branch 3 taken 216 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 216 times.
✗ Branch 7 not taken.
|
216 | std::cout << callbacks[i].data.result.numContacts() << " "; |
| 285 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
24 | std::cout << std::endl; |
| 286 | |||
| 287 |
2/2✓ Branch 0 taken 10 times.
✓ Branch 1 taken 14 times.
|
24 | if (exhaustive) { |
| 288 |
2/2✓ Branch 1 taken 80 times.
✓ Branch 2 taken 10 times.
|
90 | for (size_t i = 1; i < managers.size(); ++i) |
| 289 |
6/12✓ Branch 1 taken 80 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 80 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 80 times.
✗ Branch 12 not taken.
✓ Branch 18 taken 80 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 80 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 80 times.
|
80 | BOOST_CHECK(callbacks[i].data.result.numContacts() == |
| 290 | callbacks[0].data.result.numContacts()); | ||
| 291 | } else { | ||
| 292 |
1/2✓ Branch 2 taken 14 times.
✗ Branch 3 not taken.
|
14 | std::vector<bool> self_res(managers.size()); |
| 293 |
2/2✓ Branch 1 taken 126 times.
✓ Branch 2 taken 14 times.
|
140 | for (size_t i = 0; i < self_res.size(); ++i) |
| 294 |
1/2✓ Branch 3 taken 126 times.
✗ Branch 4 not taken.
|
126 | self_res[i] = (callbacks[i].data.result.numContacts() > 0); |
| 295 | |||
| 296 |
2/2✓ Branch 1 taken 112 times.
✓ Branch 2 taken 14 times.
|
126 | for (size_t i = 1; i < self_res.size(); ++i) |
| 297 |
8/16✓ Branch 1 taken 112 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 112 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 112 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 112 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 112 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 112 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 112 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 112 times.
|
112 | BOOST_CHECK(self_res[0] == self_res[i]); |
| 298 | |||
| 299 |
2/2✓ Branch 1 taken 112 times.
✓ Branch 2 taken 14 times.
|
126 | for (size_t i = 1; i < managers.size(); ++i) |
| 300 |
6/12✓ Branch 1 taken 112 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 112 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 112 times.
✗ Branch 12 not taken.
✓ Branch 18 taken 112 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 112 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 112 times.
|
112 | BOOST_CHECK(callbacks[i].data.result.numContacts() == |
| 301 | callbacks[0].data.result.numContacts()); | ||
| 302 | 14 | } | |
| 303 | |||
| 304 |
2/2✓ Branch 1 taken 1950 times.
✓ Branch 2 taken 24 times.
|
1974 | for (size_t i = 0; i < query.size(); ++i) { |
| 305 |
1/2✓ Branch 2 taken 1950 times.
✗ Branch 3 not taken.
|
1950 | std::vector<CollisionCallBackDefault> callbacks(managers.size()); |
| 306 |
2/2✓ Branch 1 taken 17550 times.
✓ Branch 2 taken 1950 times.
|
19500 | for (size_t j = 0; j < managers.size(); ++j) { |
| 307 |
2/2✓ Branch 0 taken 5940 times.
✓ Branch 1 taken 11610 times.
|
17550 | if (exhaustive) |
| 308 | 5940 | callbacks[j].data.request.num_max_contacts = 100000; | |
| 309 | else | ||
| 310 | 11610 | callbacks[j].data.request.num_max_contacts = num_max_contacts; | |
| 311 | } | ||
| 312 | |||
| 313 |
2/2✓ Branch 1 taken 17550 times.
✓ Branch 2 taken 1950 times.
|
19500 | for (size_t j = 0; j < managers.size(); ++j) { |
| 314 |
1/2✓ Branch 2 taken 17550 times.
✗ Branch 3 not taken.
|
17550 | timers[j].start(); |
| 315 |
1/2✓ Branch 4 taken 17550 times.
✗ Branch 5 not taken.
|
17550 | managers[j]->collide(query[i], &callbacks[j]); |
| 316 |
1/2✓ Branch 2 taken 17550 times.
✗ Branch 3 not taken.
|
17550 | timers[j].stop(); |
| 317 |
2/4✓ Branch 3 taken 17550 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 17550 times.
✗ Branch 7 not taken.
|
17550 | ts[j].push_back(timers[j].getElapsedTime()); |
| 318 | } | ||
| 319 | |||
| 320 | // for(size_t j = 0; j < managers.size(); ++j) | ||
| 321 | // std::cout << callbacks[i].data.result.numContacts() << " "; | ||
| 322 | // std::cout << std::endl; | ||
| 323 | |||
| 324 |
2/2✓ Branch 0 taken 660 times.
✓ Branch 1 taken 1290 times.
|
1950 | if (exhaustive) { |
| 325 |
2/2✓ Branch 1 taken 5280 times.
✓ Branch 2 taken 660 times.
|
5940 | for (size_t j = 1; j < managers.size(); ++j) |
| 326 |
6/12✓ Branch 1 taken 5280 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 5280 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 5280 times.
✗ Branch 12 not taken.
✓ Branch 18 taken 5280 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 5280 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 5280 times.
|
5280 | BOOST_CHECK(callbacks[j].data.result.numContacts() == |
| 327 | callbacks[0].data.result.numContacts()); | ||
| 328 | } else { | ||
| 329 |
1/2✓ Branch 2 taken 1290 times.
✗ Branch 3 not taken.
|
1290 | std::vector<bool> query_res(managers.size()); |
| 330 |
2/2✓ Branch 1 taken 11610 times.
✓ Branch 2 taken 1290 times.
|
12900 | for (size_t j = 0; j < query_res.size(); ++j) |
| 331 |
1/2✓ Branch 3 taken 11610 times.
✗ Branch 4 not taken.
|
11610 | query_res[j] = (callbacks[j].data.result.numContacts() > 0); |
| 332 |
2/2✓ Branch 1 taken 10320 times.
✓ Branch 2 taken 1290 times.
|
11610 | for (size_t j = 1; j < query_res.size(); ++j) |
| 333 |
8/16✓ Branch 1 taken 10320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 10320 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 10320 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 10320 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 10320 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 10320 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 10320 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 10320 times.
|
10320 | BOOST_CHECK(query_res[0] == query_res[j]); |
| 334 | |||
| 335 |
2/2✓ Branch 1 taken 10320 times.
✓ Branch 2 taken 1290 times.
|
11610 | for (size_t j = 1; j < managers.size(); ++j) |
| 336 |
6/12✓ Branch 1 taken 10320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 10320 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 10320 times.
✗ Branch 12 not taken.
✓ Branch 18 taken 10320 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 10320 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 10320 times.
|
10320 | BOOST_CHECK(callbacks[j].data.result.numContacts() == |
| 337 | callbacks[0].data.result.numContacts()); | ||
| 338 | 1290 | } | |
| 339 | 1950 | } | |
| 340 | |||
| 341 |
3/4✓ Branch 1 taken 1077 times.
✗ Branch 2 not taken.
✓ Branch 6 taken 1077 times.
✓ Branch 7 taken 24 times.
|
1101 | for (size_t i = 0; i < env.size(); ++i) delete env[i]; |
| 342 |
3/4✓ Branch 1 taken 1950 times.
✗ Branch 2 not taken.
✓ Branch 6 taken 1950 times.
✓ Branch 7 taken 24 times.
|
1974 | for (size_t i = 0; i < query.size(); ++i) delete query[i]; |
| 343 | |||
| 344 |
3/4✓ Branch 1 taken 216 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 216 times.
✓ Branch 6 taken 24 times.
|
240 | for (size_t i = 0; i < managers.size(); ++i) delete managers[i]; |
| 345 | |||
| 346 | 24 | std::cout.setf(std::ios_base::left, std::ios_base::adjustfield); | |
| 347 | 24 | int w = 7; | |
| 348 | |||
| 349 |
2/4✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
|
24 | std::cout << "collision timing summary" << std::endl; |
| 350 |
5/10✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 24 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 24 times.
✗ Branch 14 not taken.
|
24 | std::cout << env_size << " objs, " << query_size << " queries" << std::endl; |
| 351 |
2/4✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
|
24 | std::cout << "register time" << std::endl; |
| 352 |
2/2✓ Branch 1 taken 216 times.
✓ Branch 2 taken 24 times.
|
240 | for (size_t i = 0; i < ts.size(); ++i) |
| 353 |
2/4✓ Branch 5 taken 216 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 216 times.
✗ Branch 9 not taken.
|
216 | std::cout << std::setw(w) << ts[i].records[0] << " "; |
| 354 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
24 | std::cout << std::endl; |
| 355 | |||
| 356 |
2/4✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
|
24 | std::cout << "setup time" << std::endl; |
| 357 |
2/2✓ Branch 1 taken 216 times.
✓ Branch 2 taken 24 times.
|
240 | for (size_t i = 0; i < ts.size(); ++i) |
| 358 |
2/4✓ Branch 5 taken 216 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 216 times.
✗ Branch 9 not taken.
|
216 | std::cout << std::setw(w) << ts[i].records[1] << " "; |
| 359 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
24 | std::cout << std::endl; |
| 360 | |||
| 361 |
2/4✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
|
24 | std::cout << "self collision time" << std::endl; |
| 362 |
2/2✓ Branch 1 taken 216 times.
✓ Branch 2 taken 24 times.
|
240 | for (size_t i = 0; i < ts.size(); ++i) |
| 363 |
2/4✓ Branch 5 taken 216 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 216 times.
✗ Branch 9 not taken.
|
216 | std::cout << std::setw(w) << ts[i].records[2] << " "; |
| 364 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
24 | std::cout << std::endl; |
| 365 | |||
| 366 |
2/4✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
|
24 | std::cout << "collision time" << std::endl; |
| 367 |
2/2✓ Branch 1 taken 216 times.
✓ Branch 2 taken 24 times.
|
240 | for (size_t i = 0; i < ts.size(); ++i) { |
| 368 | 216 | double tmp = 0; | |
| 369 |
2/2✓ Branch 4 taken 17550 times.
✓ Branch 5 taken 216 times.
|
17766 | for (size_t j = 3; j < ts[i].records.size(); ++j) tmp += ts[i].records[j]; |
| 370 |
2/4✓ Branch 3 taken 216 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 216 times.
✗ Branch 7 not taken.
|
216 | std::cout << std::setw(w) << tmp << " "; |
| 371 | } | ||
| 372 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
24 | std::cout << std::endl; |
| 373 | |||
| 374 |
2/4✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
|
24 | std::cout << "overall time" << std::endl; |
| 375 |
2/2✓ Branch 1 taken 216 times.
✓ Branch 2 taken 24 times.
|
240 | for (size_t i = 0; i < ts.size(); ++i) |
| 376 |
2/4✓ Branch 4 taken 216 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 216 times.
✗ Branch 8 not taken.
|
216 | std::cout << std::setw(w) << ts[i].overall_time << " "; |
| 377 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
24 | std::cout << std::endl; |
| 378 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
24 | std::cout << std::endl; |
| 379 | 24 | } | |
| 380 |