| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | /* | ||
| 2 | * Software License Agreement (BSD License) | ||
| 3 | * | ||
| 4 | * Copyright (c) 2011-2014, Willow Garage, Inc. | ||
| 5 | * Copyright (c) 2014-2015, 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 | #include "coal/shape/geometric_shapes_utility.h" | ||
| 39 | #include "coal/internal/BV_fitter.h" | ||
| 40 | #include "coal/internal/tools.h" | ||
| 41 | |||
| 42 | namespace coal { | ||
| 43 | |||
| 44 | namespace details { | ||
| 45 | |||
| 46 | 202 | std::vector<Vec3s> getBoundVertices(const Box& box, const Transform3s& tf) { | |
| 47 |
1/2✓ Branch 1 taken 202 times.
✗ Branch 2 not taken.
|
202 | std::vector<Vec3s> result(8); |
| 48 |
1/2✓ Branch 1 taken 202 times.
✗ Branch 2 not taken.
|
202 | Scalar a = box.halfSide[0]; |
| 49 |
1/2✓ Branch 1 taken 202 times.
✗ Branch 2 not taken.
|
202 | Scalar b = box.halfSide[1]; |
| 50 |
1/2✓ Branch 1 taken 202 times.
✗ Branch 2 not taken.
|
202 | Scalar c = box.halfSide[2]; |
| 51 |
2/4✓ Branch 1 taken 202 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 202 times.
✗ Branch 5 not taken.
|
202 | result[0] = tf.transform(Vec3s(a, b, c)); |
| 52 |
2/4✓ Branch 1 taken 202 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 202 times.
✗ Branch 5 not taken.
|
202 | result[1] = tf.transform(Vec3s(a, b, -c)); |
| 53 |
2/4✓ Branch 1 taken 202 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 202 times.
✗ Branch 5 not taken.
|
202 | result[2] = tf.transform(Vec3s(a, -b, c)); |
| 54 |
2/4✓ Branch 1 taken 202 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 202 times.
✗ Branch 5 not taken.
|
202 | result[3] = tf.transform(Vec3s(a, -b, -c)); |
| 55 |
2/4✓ Branch 1 taken 202 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 202 times.
✗ Branch 5 not taken.
|
202 | result[4] = tf.transform(Vec3s(-a, b, c)); |
| 56 |
2/4✓ Branch 1 taken 202 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 202 times.
✗ Branch 5 not taken.
|
202 | result[5] = tf.transform(Vec3s(-a, b, -c)); |
| 57 |
2/4✓ Branch 1 taken 202 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 202 times.
✗ Branch 5 not taken.
|
202 | result[6] = tf.transform(Vec3s(-a, -b, c)); |
| 58 |
2/4✓ Branch 1 taken 202 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 202 times.
✗ Branch 5 not taken.
|
202 | result[7] = tf.transform(Vec3s(-a, -b, -c)); |
| 59 | |||
| 60 | 404 | return result; | |
| 61 | ✗ | } | |
| 62 | |||
| 63 | // we use icosahedron to bound the sphere | ||
| 64 | 17 | std::vector<Vec3s> getBoundVertices(const Sphere& sphere, | |
| 65 | const Transform3s& tf) { | ||
| 66 |
1/2✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
|
17 | std::vector<Vec3s> result(12); |
| 67 | 17 | const Scalar m = (1 + sqrt(Scalar(5))) / Scalar(2); | |
| 68 | 17 | Scalar edge_size = sphere.radius * 6 / (sqrt(Scalar(27)) + sqrt(Scalar(15))); | |
| 69 | |||
| 70 | 17 | Scalar a = edge_size; | |
| 71 | 17 | Scalar b = m * edge_size; | |
| 72 |
2/4✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 17 times.
✗ Branch 5 not taken.
|
17 | result[0] = tf.transform(Vec3s(0, a, b)); |
| 73 |
2/4✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 17 times.
✗ Branch 5 not taken.
|
17 | result[1] = tf.transform(Vec3s(0, -a, b)); |
| 74 |
2/4✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 17 times.
✗ Branch 5 not taken.
|
17 | result[2] = tf.transform(Vec3s(0, a, -b)); |
| 75 |
2/4✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 17 times.
✗ Branch 5 not taken.
|
17 | result[3] = tf.transform(Vec3s(0, -a, -b)); |
| 76 |
2/4✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 17 times.
✗ Branch 5 not taken.
|
17 | result[4] = tf.transform(Vec3s(a, b, 0)); |
| 77 |
2/4✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 17 times.
✗ Branch 5 not taken.
|
17 | result[5] = tf.transform(Vec3s(-a, b, 0)); |
| 78 |
2/4✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 17 times.
✗ Branch 5 not taken.
|
17 | result[6] = tf.transform(Vec3s(a, -b, 0)); |
| 79 |
2/4✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 17 times.
✗ Branch 5 not taken.
|
17 | result[7] = tf.transform(Vec3s(-a, -b, 0)); |
| 80 |
2/4✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 17 times.
✗ Branch 5 not taken.
|
17 | result[8] = tf.transform(Vec3s(b, 0, a)); |
| 81 |
2/4✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 17 times.
✗ Branch 5 not taken.
|
17 | result[9] = tf.transform(Vec3s(b, 0, -a)); |
| 82 |
2/4✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 17 times.
✗ Branch 5 not taken.
|
17 | result[10] = tf.transform(Vec3s(-b, 0, a)); |
| 83 |
2/4✓ Branch 1 taken 17 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 17 times.
✗ Branch 5 not taken.
|
17 | result[11] = tf.transform(Vec3s(-b, 0, -a)); |
| 84 | |||
| 85 | 34 | return result; | |
| 86 | ✗ | } | |
| 87 | |||
| 88 | // we use scaled icosahedron to bound the ellipsoid | ||
| 89 | ✗ | std::vector<Vec3s> getBoundVertices(const Ellipsoid& ellipsoid, | |
| 90 | const Transform3s& tf) { | ||
| 91 | ✗ | std::vector<Vec3s> result(12); | |
| 92 | ✗ | const Scalar phi = (1 + sqrt(Scalar(5))) / Scalar(2); | |
| 93 | |||
| 94 | ✗ | const Scalar a = sqrt(Scalar(3)) / (phi * phi); | |
| 95 | ✗ | const Scalar b = phi * a; | |
| 96 | |||
| 97 | ✗ | const Scalar& A = ellipsoid.radii[0]; | |
| 98 | ✗ | const Scalar& B = ellipsoid.radii[1]; | |
| 99 | ✗ | const Scalar& C = ellipsoid.radii[2]; | |
| 100 | |||
| 101 | ✗ | Scalar Aa = A * a; | |
| 102 | ✗ | Scalar Ab = A * b; | |
| 103 | ✗ | Scalar Ba = B * a; | |
| 104 | ✗ | Scalar Bb = B * b; | |
| 105 | ✗ | Scalar Ca = C * a; | |
| 106 | ✗ | Scalar Cb = C * b; | |
| 107 | ✗ | result[0] = tf.transform(Vec3s(0, Ba, Cb)); | |
| 108 | ✗ | result[1] = tf.transform(Vec3s(0, -Ba, Cb)); | |
| 109 | ✗ | result[2] = tf.transform(Vec3s(0, Ba, -Cb)); | |
| 110 | ✗ | result[3] = tf.transform(Vec3s(0, -Ba, -Cb)); | |
| 111 | ✗ | result[4] = tf.transform(Vec3s(Aa, Bb, 0)); | |
| 112 | ✗ | result[5] = tf.transform(Vec3s(-Aa, Bb, 0)); | |
| 113 | ✗ | result[6] = tf.transform(Vec3s(Aa, -Bb, 0)); | |
| 114 | ✗ | result[7] = tf.transform(Vec3s(-Aa, -Bb, 0)); | |
| 115 | ✗ | result[8] = tf.transform(Vec3s(Ab, 0, Ca)); | |
| 116 | ✗ | result[9] = tf.transform(Vec3s(Ab, 0, -Ca)); | |
| 117 | ✗ | result[10] = tf.transform(Vec3s(-Ab, 0, Ca)); | |
| 118 | ✗ | result[11] = tf.transform(Vec3s(-Ab, 0, -Ca)); | |
| 119 | |||
| 120 | ✗ | return result; | |
| 121 | ✗ | } | |
| 122 | |||
| 123 | 2 | std::vector<Vec3s> getBoundVertices(const Capsule& capsule, | |
| 124 | const Transform3s& tf) { | ||
| 125 |
1/2✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
|
2 | std::vector<Vec3s> result(36); |
| 126 | 2 | const Scalar m = (1 + sqrt(Scalar(5))) / Scalar(2); | |
| 127 | |||
| 128 | 2 | Scalar hl = capsule.halfLength; | |
| 129 | 2 | Scalar edge_size = capsule.radius * 6 / (sqrt(Scalar(27)) + sqrt(Scalar(15))); | |
| 130 | 2 | Scalar a = edge_size; | |
| 131 | 2 | Scalar b = m * edge_size; | |
| 132 | 2 | Scalar r2 = capsule.radius * 2 / sqrt(Scalar(3)); | |
| 133 | |||
| 134 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[0] = tf.transform(Vec3s(0, a, b + hl)); |
| 135 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[1] = tf.transform(Vec3s(0, -a, b + hl)); |
| 136 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[2] = tf.transform(Vec3s(0, a, -b + hl)); |
| 137 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[3] = tf.transform(Vec3s(0, -a, -b + hl)); |
| 138 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[4] = tf.transform(Vec3s(a, b, hl)); |
| 139 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[5] = tf.transform(Vec3s(-a, b, hl)); |
| 140 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[6] = tf.transform(Vec3s(a, -b, hl)); |
| 141 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[7] = tf.transform(Vec3s(-a, -b, hl)); |
| 142 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[8] = tf.transform(Vec3s(b, 0, a + hl)); |
| 143 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[9] = tf.transform(Vec3s(b, 0, -a + hl)); |
| 144 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[10] = tf.transform(Vec3s(-b, 0, a + hl)); |
| 145 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[11] = tf.transform(Vec3s(-b, 0, -a + hl)); |
| 146 | |||
| 147 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[12] = tf.transform(Vec3s(0, a, b - hl)); |
| 148 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[13] = tf.transform(Vec3s(0, -a, b - hl)); |
| 149 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[14] = tf.transform(Vec3s(0, a, -b - hl)); |
| 150 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[15] = tf.transform(Vec3s(0, -a, -b - hl)); |
| 151 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[16] = tf.transform(Vec3s(a, b, -hl)); |
| 152 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[17] = tf.transform(Vec3s(-a, b, -hl)); |
| 153 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[18] = tf.transform(Vec3s(a, -b, -hl)); |
| 154 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[19] = tf.transform(Vec3s(-a, -b, -hl)); |
| 155 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[20] = tf.transform(Vec3s(b, 0, a - hl)); |
| 156 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[21] = tf.transform(Vec3s(b, 0, -a - hl)); |
| 157 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[22] = tf.transform(Vec3s(-b, 0, a - hl)); |
| 158 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[23] = tf.transform(Vec3s(-b, 0, -a - hl)); |
| 159 | |||
| 160 | 2 | Scalar c = Scalar(0.5) * r2; | |
| 161 | 2 | Scalar d = capsule.radius; | |
| 162 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[24] = tf.transform(Vec3s(r2, 0, hl)); |
| 163 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[25] = tf.transform(Vec3s(c, d, hl)); |
| 164 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[26] = tf.transform(Vec3s(-c, d, hl)); |
| 165 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[27] = tf.transform(Vec3s(-r2, 0, hl)); |
| 166 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[28] = tf.transform(Vec3s(-c, -d, hl)); |
| 167 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[29] = tf.transform(Vec3s(c, -d, hl)); |
| 168 | |||
| 169 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[30] = tf.transform(Vec3s(r2, 0, -hl)); |
| 170 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[31] = tf.transform(Vec3s(c, d, -hl)); |
| 171 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[32] = tf.transform(Vec3s(-c, d, -hl)); |
| 172 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[33] = tf.transform(Vec3s(-r2, 0, -hl)); |
| 173 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[34] = tf.transform(Vec3s(-c, -d, -hl)); |
| 174 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[35] = tf.transform(Vec3s(c, -d, -hl)); |
| 175 | |||
| 176 | 4 | return result; | |
| 177 | ✗ | } | |
| 178 | |||
| 179 | 2 | std::vector<Vec3s> getBoundVertices(const Cone& cone, const Transform3s& tf) { | |
| 180 |
1/2✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
|
2 | std::vector<Vec3s> result(7); |
| 181 | |||
| 182 | 2 | Scalar hl = cone.halfLength; | |
| 183 | 2 | Scalar r2 = cone.radius * 2 / sqrt(Scalar(3)); | |
| 184 | 2 | Scalar a = Scalar(0.5) * r2; | |
| 185 | 2 | Scalar b = cone.radius; | |
| 186 | |||
| 187 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[0] = tf.transform(Vec3s(r2, 0, -hl)); |
| 188 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[1] = tf.transform(Vec3s(a, b, -hl)); |
| 189 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[2] = tf.transform(Vec3s(-a, b, -hl)); |
| 190 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[3] = tf.transform(Vec3s(-r2, 0, -hl)); |
| 191 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[4] = tf.transform(Vec3s(-a, -b, -hl)); |
| 192 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[5] = tf.transform(Vec3s(a, -b, -hl)); |
| 193 | |||
| 194 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | result[6] = tf.transform(Vec3s(0, 0, hl)); |
| 195 | |||
| 196 | 4 | return result; | |
| 197 | ✗ | } | |
| 198 | |||
| 199 | 5 | std::vector<Vec3s> getBoundVertices(const Cylinder& cylinder, | |
| 200 | const Transform3s& tf) { | ||
| 201 |
1/2✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
|
5 | std::vector<Vec3s> result(12); |
| 202 | |||
| 203 | 5 | Scalar hl = cylinder.halfLength; | |
| 204 | 5 | Scalar r2 = cylinder.radius * 2 / sqrt(Scalar(3)); | |
| 205 | 5 | Scalar a = Scalar(0.5) * r2; | |
| 206 | 5 | Scalar b = cylinder.radius; | |
| 207 | |||
| 208 |
2/4✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
|
5 | result[0] = tf.transform(Vec3s(r2, 0, -hl)); |
| 209 |
2/4✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
|
5 | result[1] = tf.transform(Vec3s(a, b, -hl)); |
| 210 |
2/4✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
|
5 | result[2] = tf.transform(Vec3s(-a, b, -hl)); |
| 211 |
2/4✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
|
5 | result[3] = tf.transform(Vec3s(-r2, 0, -hl)); |
| 212 |
2/4✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
|
5 | result[4] = tf.transform(Vec3s(-a, -b, -hl)); |
| 213 |
2/4✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
|
5 | result[5] = tf.transform(Vec3s(a, -b, -hl)); |
| 214 | |||
| 215 |
2/4✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
|
5 | result[6] = tf.transform(Vec3s(r2, 0, hl)); |
| 216 |
2/4✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
|
5 | result[7] = tf.transform(Vec3s(a, b, hl)); |
| 217 |
2/4✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
|
5 | result[8] = tf.transform(Vec3s(-a, b, hl)); |
| 218 |
2/4✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
|
5 | result[9] = tf.transform(Vec3s(-r2, 0, hl)); |
| 219 |
2/4✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
|
5 | result[10] = tf.transform(Vec3s(-a, -b, hl)); |
| 220 |
2/4✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
|
5 | result[11] = tf.transform(Vec3s(a, -b, hl)); |
| 221 | |||
| 222 | 10 | return result; | |
| 223 | ✗ | } | |
| 224 | |||
| 225 | ✗ | std::vector<Vec3s> getBoundVertices(const TriangleP& triangle, | |
| 226 | const Transform3s& tf) { | ||
| 227 | ✗ | std::vector<Vec3s> result(3); | |
| 228 | ✗ | result[0] = tf.transform(triangle.a); | |
| 229 | ✗ | result[1] = tf.transform(triangle.b); | |
| 230 | ✗ | result[2] = tf.transform(triangle.c); | |
| 231 | |||
| 232 | ✗ | return result; | |
| 233 | ✗ | } | |
| 234 | |||
| 235 | } // namespace details | ||
| 236 | |||
| 237 | 6420 | Halfspace transform(const Halfspace& a, const Transform3s& tf) { | |
| 238 | /// suppose the initial halfspace is n * x <= d | ||
| 239 | /// after transform (R, T), x --> x' = R x + T | ||
| 240 | /// and the new half space becomes n' * x' <= d' | ||
| 241 | /// where n' = R * n | ||
| 242 | /// and d' = d + n' * T | ||
| 243 | |||
| 244 |
2/4✓ Branch 2 taken 6420 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 6420 times.
✗ Branch 6 not taken.
|
6420 | Vec3s n = tf.getRotation() * a.n; |
| 245 |
1/2✓ Branch 2 taken 6420 times.
✗ Branch 3 not taken.
|
6420 | Scalar d = a.d + n.dot(tf.getTranslation()); |
| 246 |
1/2✓ Branch 1 taken 6420 times.
✗ Branch 2 not taken.
|
6420 | Halfspace result(n, d); |
| 247 |
1/2✓ Branch 2 taken 6420 times.
✗ Branch 3 not taken.
|
6420 | result.setSweptSphereRadius(a.getSweptSphereRadius()); |
| 248 | |||
| 249 | 12840 | return result; | |
| 250 | ✗ | } | |
| 251 | |||
| 252 | 61 | Plane transform(const Plane& a, const Transform3s& tf) { | |
| 253 | /// suppose the initial halfspace is n * x <= d | ||
| 254 | /// after transform (R, T), x --> x' = R x + T | ||
| 255 | /// and the new half space becomes n' * x' <= d' | ||
| 256 | /// where n' = R * n | ||
| 257 | /// and d' = d + n' * T | ||
| 258 | |||
| 259 |
2/4✓ Branch 2 taken 61 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 61 times.
✗ Branch 6 not taken.
|
61 | Vec3s n = tf.getRotation() * a.n; |
| 260 |
1/2✓ Branch 2 taken 61 times.
✗ Branch 3 not taken.
|
61 | Scalar d = a.d + n.dot(tf.getTranslation()); |
| 261 |
1/2✓ Branch 1 taken 61 times.
✗ Branch 2 not taken.
|
61 | Plane result(n, d); |
| 262 |
1/2✓ Branch 2 taken 61 times.
✗ Branch 3 not taken.
|
61 | result.setSweptSphereRadius(a.getSweptSphereRadius()); |
| 263 | |||
| 264 | 122 | return result; | |
| 265 | ✗ | } | |
| 266 | |||
| 267 | 5546 | std::array<Halfspace, 2> transformToHalfspaces(const Plane& a, | |
| 268 | const Transform3s& tf) { | ||
| 269 | // A plane can be represented by two halfspaces | ||
| 270 | |||
| 271 |
2/4✓ Branch 2 taken 5546 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 5546 times.
✗ Branch 6 not taken.
|
5546 | Vec3s n = tf.getRotation() * a.n; |
| 272 |
1/2✓ Branch 2 taken 5546 times.
✗ Branch 3 not taken.
|
5546 | Scalar d = a.d + n.dot(tf.getTranslation()); |
| 273 |
4/12✓ Branch 1 taken 5546 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5546 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 5546 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 5546 times.
✗ Branch 11 not taken.
✗ Branch 12 not taken.
✗ Branch 13 not taken.
✗ Branch 14 not taken.
✗ Branch 15 not taken.
|
5546 | std::array<Halfspace, 2> result = {Halfspace(n, d), Halfspace(-n, -d)}; |
| 274 |
1/2✓ Branch 3 taken 5546 times.
✗ Branch 4 not taken.
|
5546 | result[0].setSweptSphereRadius(a.getSweptSphereRadius()); |
| 275 |
1/2✓ Branch 3 taken 5546 times.
✗ Branch 4 not taken.
|
5546 | result[1].setSweptSphereRadius(a.getSweptSphereRadius()); |
| 276 | |||
| 277 | 11092 | return result; | |
| 278 | ✗ | } | |
| 279 | |||
| 280 | template <> | ||
| 281 | 15122 | void computeBV<AABB, Box>(const Box& s, const Transform3s& tf, AABB& bv) { | |
| 282 | 15122 | const Matrix3s& R = tf.getRotation(); | |
| 283 | 15122 | const Vec3s& T = tf.getTranslation(); | |
| 284 | |||
| 285 |
3/6✓ Branch 1 taken 15122 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 15122 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 15122 times.
✗ Branch 8 not taken.
|
15122 | Vec3s v_delta(R.cwiseAbs() * s.halfSide); |
| 286 |
2/4✓ Branch 1 taken 15122 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 15122 times.
✗ Branch 5 not taken.
|
15122 | bv.max_ = T + v_delta; |
| 287 |
2/4✓ Branch 1 taken 15122 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 15122 times.
✗ Branch 5 not taken.
|
15122 | bv.min_ = T - v_delta; |
| 288 | 15122 | } | |
| 289 | |||
| 290 | template <> | ||
| 291 | 16958 | void computeBV<AABB, Sphere>(const Sphere& s, const Transform3s& tf, AABB& bv) { | |
| 292 | 16958 | const Vec3s& T = tf.getTranslation(); | |
| 293 | |||
| 294 |
2/4✓ Branch 1 taken 16958 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16958 times.
✗ Branch 5 not taken.
|
16958 | Vec3s v_delta(Vec3s::Constant(s.radius)); |
| 295 |
2/4✓ Branch 1 taken 16958 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16958 times.
✗ Branch 5 not taken.
|
16958 | bv.max_ = T + v_delta; |
| 296 |
2/4✓ Branch 1 taken 16958 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16958 times.
✗ Branch 5 not taken.
|
16958 | bv.min_ = T - v_delta; |
| 297 | 16958 | } | |
| 298 | |||
| 299 | template <> | ||
| 300 | 1 | void computeBV<AABB, Ellipsoid>(const Ellipsoid& e, const Transform3s& tf, | |
| 301 | AABB& bv) { | ||
| 302 | 1 | const Matrix3s& R = tf.getRotation(); | |
| 303 | 1 | const Vec3s& T = tf.getTranslation(); | |
| 304 | |||
| 305 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | Vec3s v_delta = R * e.radii; |
| 306 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | bv.max_ = T + v_delta; |
| 307 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | bv.min_ = T - v_delta; |
| 308 | 1 | } | |
| 309 | |||
| 310 | template <> | ||
| 311 | 10011 | void computeBV<AABB, Capsule>(const Capsule& s, const Transform3s& tf, | |
| 312 | AABB& bv) { | ||
| 313 | 10011 | const Matrix3s& R = tf.getRotation(); | |
| 314 | 10011 | const Vec3s& T = tf.getTranslation(); | |
| 315 | |||
| 316 |
6/12✓ Branch 1 taken 10011 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10011 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 10011 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 10011 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 10011 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 10011 times.
✗ Branch 17 not taken.
|
10011 | Vec3s v_delta(R.col(2).cwiseAbs() * s.halfLength + Vec3s::Constant(s.radius)); |
| 317 |
2/4✓ Branch 1 taken 10011 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10011 times.
✗ Branch 5 not taken.
|
10011 | bv.max_ = T + v_delta; |
| 318 |
2/4✓ Branch 1 taken 10011 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10011 times.
✗ Branch 5 not taken.
|
10011 | bv.min_ = T - v_delta; |
| 319 | 10011 | } | |
| 320 | |||
| 321 | template <> | ||
| 322 | 1 | void computeBV<AABB, Cone>(const Cone& s, const Transform3s& tf, AABB& bv) { | |
| 323 | 1 | const Matrix3s& R = tf.getRotation(); | |
| 324 | 1 | const Vec3s& T = tf.getTranslation(); | |
| 325 | |||
| 326 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | Scalar x_range = fabs(R(0, 0) * s.radius) + fabs(R(0, 1) * s.radius) + |
| 327 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | fabs(R(0, 2) * s.halfLength); |
| 328 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | Scalar y_range = fabs(R(1, 0) * s.radius) + fabs(R(1, 1) * s.radius) + |
| 329 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | fabs(R(1, 2) * s.halfLength); |
| 330 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | Scalar z_range = fabs(R(2, 0) * s.radius) + fabs(R(2, 1) * s.radius) + |
| 331 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | fabs(R(2, 2) * s.halfLength); |
| 332 | |||
| 333 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | Vec3s v_delta(x_range, y_range, z_range); |
| 334 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | bv.max_ = T + v_delta; |
| 335 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | bv.min_ = T - v_delta; |
| 336 | 1 | } | |
| 337 | |||
| 338 | template <> | ||
| 339 | 8913 | void computeBV<AABB, Cylinder>(const Cylinder& s, const Transform3s& tf, | |
| 340 | AABB& bv) { | ||
| 341 | 8913 | const Matrix3s& R = tf.getRotation(); | |
| 342 | 8913 | const Vec3s& T = tf.getTranslation(); | |
| 343 | |||
| 344 |
2/4✓ Branch 1 taken 8913 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8913 times.
✗ Branch 5 not taken.
|
8913 | Scalar x_range = fabs(R(0, 0) * s.radius) + fabs(R(0, 1) * s.radius) + |
| 345 |
1/2✓ Branch 1 taken 8913 times.
✗ Branch 2 not taken.
|
8913 | fabs(R(0, 2) * s.halfLength); |
| 346 |
2/4✓ Branch 1 taken 8913 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8913 times.
✗ Branch 5 not taken.
|
8913 | Scalar y_range = fabs(R(1, 0) * s.radius) + fabs(R(1, 1) * s.radius) + |
| 347 |
1/2✓ Branch 1 taken 8913 times.
✗ Branch 2 not taken.
|
8913 | fabs(R(1, 2) * s.halfLength); |
| 348 |
2/4✓ Branch 1 taken 8913 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8913 times.
✗ Branch 5 not taken.
|
8913 | Scalar z_range = fabs(R(2, 0) * s.radius) + fabs(R(2, 1) * s.radius) + |
| 349 |
1/2✓ Branch 1 taken 8913 times.
✗ Branch 2 not taken.
|
8913 | fabs(R(2, 2) * s.halfLength); |
| 350 | |||
| 351 |
1/2✓ Branch 1 taken 8913 times.
✗ Branch 2 not taken.
|
8913 | Vec3s v_delta(x_range, y_range, z_range); |
| 352 |
2/4✓ Branch 1 taken 8913 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8913 times.
✗ Branch 5 not taken.
|
8913 | bv.max_ = T + v_delta; |
| 353 |
2/4✓ Branch 1 taken 8913 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8913 times.
✗ Branch 5 not taken.
|
8913 | bv.min_ = T - v_delta; |
| 354 | 8913 | } | |
| 355 | |||
| 356 | template <typename IndexType> | ||
| 357 | 2 | void computeAABBConvex(const ConvexBaseTpl<IndexType>& s, const Transform3s& tf, | |
| 358 | AABB& bv) { | ||
| 359 | 2 | const Matrix3s& R = tf.getRotation(); | |
| 360 | 2 | const Vec3s& T = tf.getTranslation(); | |
| 361 | |||
| 362 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | AABB bv_; |
| 363 | 2 | const std::vector<Vec3s>& points_ = *(s.points); | |
| 364 |
2/2✓ Branch 0 taken 8 times.
✓ Branch 1 taken 1 times.
|
18 | for (std::size_t i = 0; i < s.num_points; ++i) { |
| 365 |
3/6✓ Branch 2 taken 8 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 8 times.
✗ Branch 9 not taken.
|
16 | Vec3s new_p = R * points_[i] + T; |
| 366 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | bv_ += new_p; |
| 367 | } | ||
| 368 | |||
| 369 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | bv = bv_; |
| 370 | 2 | } | |
| 371 | |||
| 372 | template <> | ||
| 373 | 1 | void computeBV<AABB, ConvexBase32>(const ConvexBase32& s, const Transform3s& tf, | |
| 374 | AABB& bv) { | ||
| 375 | 1 | computeAABBConvex(s, tf, bv); | |
| 376 | 1 | } | |
| 377 | |||
| 378 | template <> | ||
| 379 | ✗ | void computeBV<AABB, ConvexBase16>(const ConvexBase16& s, const Transform3s& tf, | |
| 380 | AABB& bv) { | ||
| 381 | ✗ | computeAABBConvex(s, tf, bv); | |
| 382 | ✗ | } | |
| 383 | |||
| 384 | template <> | ||
| 385 | 1 | void computeBV<AABB, TriangleP>(const TriangleP& s, const Transform3s& tf, | |
| 386 | AABB& bv) { | ||
| 387 |
5/10✓ 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.
|
1 | bv = AABB(tf.transform(s.a), tf.transform(s.b), tf.transform(s.c)); |
| 388 | 1 | } | |
| 389 | |||
| 390 | template <> | ||
| 391 | 1 | void computeBV<AABB, Halfspace>(const Halfspace& s, const Transform3s& tf, | |
| 392 | AABB& bv) { | ||
| 393 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | Halfspace new_s = transform(s, tf); |
| 394 | 1 | const Vec3s& n = new_s.n; | |
| 395 | 1 | const Scalar& d = new_s.d; | |
| 396 | |||
| 397 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | AABB bv_; |
| 398 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
1 | bv_.min_ = Vec3s::Constant(-(std::numeric_limits<Scalar>::max)()); |
| 399 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
1 | bv_.max_ = Vec3s::Constant((std::numeric_limits<Scalar>::max)()); |
| 400 |
3/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
✓ Branch 11 taken 1 times.
|
1 | if (n[1] == (Scalar)0.0 && n[2] == (Scalar)0.0) { |
| 401 | // normal aligned with x axis | ||
| 402 | ✗ | if (n[0] < 0) | |
| 403 | ✗ | bv_.min_[0] = -d; | |
| 404 | ✗ | else if (n[0] > 0) | |
| 405 | ✗ | bv_.max_[0] = d; | |
| 406 |
3/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
✓ Branch 11 taken 1 times.
|
1 | } else if (n[0] == (Scalar)0.0 && n[2] == (Scalar)0.0) { |
| 407 | // normal aligned with y axis | ||
| 408 | ✗ | if (n[1] < 0) | |
| 409 | ✗ | bv_.min_[1] = -d; | |
| 410 | ✗ | else if (n[1] > 0) | |
| 411 | ✗ | bv_.max_[1] = d; | |
| 412 |
3/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
✓ Branch 11 taken 1 times.
|
1 | } else if (n[0] == (Scalar)0.0 && n[1] == (Scalar)0.0) { |
| 413 | // normal aligned with z axis | ||
| 414 | ✗ | if (n[2] < 0) | |
| 415 | ✗ | bv_.min_[2] = -d; | |
| 416 | ✗ | else if (n[2] > 0) | |
| 417 | ✗ | bv_.max_[2] = d; | |
| 418 | } | ||
| 419 | |||
| 420 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | bv = bv_; |
| 421 | 1 | } | |
| 422 | |||
| 423 | template <> | ||
| 424 | 1 | void computeBV<AABB, Plane>(const Plane& s, const Transform3s& tf, AABB& bv) { | |
| 425 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | Plane new_s = transform(s, tf); |
| 426 | 1 | const Vec3s& n = new_s.n; | |
| 427 | 1 | const Scalar& d = new_s.d; | |
| 428 | |||
| 429 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | AABB bv_; |
| 430 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
1 | bv_.min_ = Vec3s::Constant(-(std::numeric_limits<Scalar>::max)()); |
| 431 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
1 | bv_.max_ = Vec3s::Constant((std::numeric_limits<Scalar>::max)()); |
| 432 |
3/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
✓ Branch 11 taken 1 times.
|
1 | if (n[1] == (Scalar)0.0 && n[2] == (Scalar)0.0) { |
| 433 | // normal aligned with x axis | ||
| 434 | ✗ | if (n[0] < 0) { | |
| 435 | ✗ | bv_.min_[0] = bv_.max_[0] = -d; | |
| 436 | ✗ | } else if (n[0] > 0) { | |
| 437 | ✗ | bv_.min_[0] = bv_.max_[0] = d; | |
| 438 | } | ||
| 439 |
3/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
✓ Branch 11 taken 1 times.
|
1 | } else if (n[0] == (Scalar)0.0 && n[2] == (Scalar)0.0) { |
| 440 | // normal aligned with y axis | ||
| 441 | ✗ | if (n[1] < 0) { | |
| 442 | ✗ | bv_.min_[1] = bv_.max_[1] = -d; | |
| 443 | ✗ | } else if (n[1] > 0) { | |
| 444 | ✗ | bv_.min_[1] = bv_.max_[1] = d; | |
| 445 | } | ||
| 446 |
3/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
✓ Branch 11 taken 1 times.
|
1 | } else if (n[0] == (Scalar)0.0 && n[1] == (Scalar)0.0) { |
| 447 | // normal aligned with z axis | ||
| 448 | ✗ | if (n[2] < 0) { | |
| 449 | ✗ | bv_.min_[2] = bv_.max_[2] = -d; | |
| 450 | ✗ | } else if (n[2] > 0) { | |
| 451 | ✗ | bv_.min_[2] = bv_.max_[2] = d; | |
| 452 | } | ||
| 453 | } | ||
| 454 | |||
| 455 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | bv = bv_; |
| 456 | 1 | } | |
| 457 | |||
| 458 | template <> | ||
| 459 | 2 | void computeBV<OBB, Box>(const Box& s, const Transform3s& tf, OBB& bv) { | |
| 460 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 2 times.
|
2 | if (s.getSweptSphereRadius() > 0) { |
| 461 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 462 | std::runtime_error); | ||
| 463 | } | ||
| 464 | 2 | const Matrix3s& R = tf.getRotation(); | |
| 465 | 2 | const Vec3s& T = tf.getTranslation(); | |
| 466 | |||
| 467 | 2 | bv.To = T; | |
| 468 | 2 | bv.axes = R; | |
| 469 | 2 | bv.extent = s.halfSide; | |
| 470 | 2 | } | |
| 471 | |||
| 472 | template <> | ||
| 473 | 1002 | void computeBV<OBB, Sphere>(const Sphere& s, const Transform3s& tf, OBB& bv) { | |
| 474 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 1002 times.
|
1002 | if (s.getSweptSphereRadius() > 0) { |
| 475 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 476 | std::runtime_error); | ||
| 477 | } | ||
| 478 | 1002 | const Vec3s& T = tf.getTranslation(); | |
| 479 | |||
| 480 |
2/4✓ Branch 1 taken 1002 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1002 times.
✗ Branch 5 not taken.
|
1002 | bv.To.noalias() = T; |
| 481 | 1002 | bv.axes.setIdentity(); | |
| 482 | 1002 | bv.extent.setConstant(s.radius); | |
| 483 | 1002 | } | |
| 484 | |||
| 485 | template <> | ||
| 486 | 1002 | void computeBV<OBB, Capsule>(const Capsule& s, const Transform3s& tf, OBB& bv) { | |
| 487 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 1002 times.
|
1002 | if (s.getSweptSphereRadius() > 0) { |
| 488 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 489 | std::runtime_error); | ||
| 490 | } | ||
| 491 | 1002 | const Matrix3s& R = tf.getRotation(); | |
| 492 | 1002 | const Vec3s& T = tf.getTranslation(); | |
| 493 | |||
| 494 |
2/4✓ Branch 1 taken 1002 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1002 times.
✗ Branch 5 not taken.
|
1002 | bv.To.noalias() = T; |
| 495 |
2/4✓ Branch 1 taken 1002 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1002 times.
✗ Branch 5 not taken.
|
1002 | bv.axes.noalias() = R; |
| 496 |
3/6✓ Branch 1 taken 1002 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1002 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1002 times.
✗ Branch 8 not taken.
|
1002 | bv.extent << s.radius, s.radius, s.halfLength + s.radius; |
| 497 | 1002 | } | |
| 498 | |||
| 499 | template <> | ||
| 500 | 1002 | void computeBV<OBB, Cone>(const Cone& s, const Transform3s& tf, OBB& bv) { | |
| 501 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 1002 times.
|
1002 | if (s.getSweptSphereRadius() > 0) { |
| 502 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 503 | std::runtime_error); | ||
| 504 | } | ||
| 505 | 1002 | const Matrix3s& R = tf.getRotation(); | |
| 506 | 1002 | const Vec3s& T = tf.getTranslation(); | |
| 507 | |||
| 508 |
2/4✓ Branch 1 taken 1002 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1002 times.
✗ Branch 5 not taken.
|
1002 | bv.To.noalias() = T; |
| 509 |
2/4✓ Branch 1 taken 1002 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1002 times.
✗ Branch 5 not taken.
|
1002 | bv.axes.noalias() = R; |
| 510 |
3/6✓ Branch 1 taken 1002 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1002 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1002 times.
✗ Branch 8 not taken.
|
1002 | bv.extent << s.radius, s.radius, s.halfLength; |
| 511 | 1002 | } | |
| 512 | |||
| 513 | template <> | ||
| 514 | 1003 | void computeBV<OBB, Cylinder>(const Cylinder& s, const Transform3s& tf, | |
| 515 | OBB& bv) { | ||
| 516 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 1003 times.
|
1003 | if (s.getSweptSphereRadius() > 0) { |
| 517 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 518 | std::runtime_error); | ||
| 519 | } | ||
| 520 | 1003 | const Matrix3s& R = tf.getRotation(); | |
| 521 | 1003 | const Vec3s& T = tf.getTranslation(); | |
| 522 | |||
| 523 |
2/4✓ Branch 1 taken 1003 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1003 times.
✗ Branch 5 not taken.
|
1003 | bv.To.noalias() = T; |
| 524 |
2/4✓ Branch 1 taken 1003 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1003 times.
✗ Branch 5 not taken.
|
1003 | bv.axes.noalias() = R; |
| 525 |
3/6✓ Branch 1 taken 1003 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1003 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1003 times.
✗ Branch 8 not taken.
|
1003 | bv.extent << s.radius, s.radius, s.halfLength; |
| 526 | 1003 | } | |
| 527 | |||
| 528 | template <typename IndexType> | ||
| 529 | ✗ | void computeOBBConvex(const ConvexBaseTpl<IndexType>& s, const Transform3s& tf, | |
| 530 | OBB& bv) { | ||
| 531 | ✗ | if (s.getSweptSphereRadius() > 0) { | |
| 532 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 533 | std::runtime_error); | ||
| 534 | } | ||
| 535 | ✗ | const Matrix3s& R = tf.getRotation(); | |
| 536 | ✗ | const Vec3s& T = tf.getTranslation(); | |
| 537 | |||
| 538 | ✗ | fit(s.points->data(), s.num_points, bv); | |
| 539 | |||
| 540 | ✗ | bv.axes.applyOnTheLeft(R); | |
| 541 | |||
| 542 | ✗ | bv.To = R * bv.To + T; | |
| 543 | ✗ | } | |
| 544 | |||
| 545 | template <> | ||
| 546 | ✗ | void computeBV<OBB, ConvexBase32>(const ConvexBase32& s, const Transform3s& tf, | |
| 547 | OBB& bv) { | ||
| 548 | ✗ | computeOBBConvex(s, tf, bv); | |
| 549 | ✗ | } | |
| 550 | |||
| 551 | template <> | ||
| 552 | ✗ | void computeBV<OBB, ConvexBase16>(const ConvexBase16& s, const Transform3s& tf, | |
| 553 | OBB& bv) { | ||
| 554 | ✗ | computeOBBConvex(s, tf, bv); | |
| 555 | ✗ | } | |
| 556 | |||
| 557 | template <> | ||
| 558 | 4 | void computeBV<OBB, Halfspace>(const Halfspace& s, const Transform3s&, | |
| 559 | OBB& bv) { | ||
| 560 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 4 times.
|
4 | if (s.getSweptSphereRadius() > 0) { |
| 561 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 562 | std::runtime_error); | ||
| 563 | } | ||
| 564 | /// Half space can only have very rough OBB | ||
| 565 | 4 | bv.axes.setIdentity(); | |
| 566 | 4 | bv.To.setZero(); | |
| 567 |
1/2✓ Branch 2 taken 4 times.
✗ Branch 3 not taken.
|
4 | bv.extent.setConstant(((std::numeric_limits<Scalar>::max)())); |
| 568 | 4 | } | |
| 569 | |||
| 570 | template <> | ||
| 571 | 4 | void computeBV<RSS, Halfspace>(const Halfspace& s, const Transform3s&, | |
| 572 | RSS& bv) { | ||
| 573 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 4 times.
|
4 | if (s.getSweptSphereRadius() > 0) { |
| 574 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 575 | std::runtime_error); | ||
| 576 | } | ||
| 577 | /// Half space can only have very rough RSS | ||
| 578 | 4 | bv.axes.setIdentity(); | |
| 579 | 4 | bv.Tr.setZero(); | |
| 580 | 4 | bv.length[0] = bv.length[1] = bv.radius = | |
| 581 | 4 | (std::numeric_limits<Scalar>::max)(); | |
| 582 | 4 | } | |
| 583 | |||
| 584 | template <> | ||
| 585 | 4 | void computeBV<OBBRSS, Halfspace>(const Halfspace& s, const Transform3s& tf, | |
| 586 | OBBRSS& bv) { | ||
| 587 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 4 times.
|
4 | if (s.getSweptSphereRadius() > 0) { |
| 588 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 589 | std::runtime_error); | ||
| 590 | } | ||
| 591 | 4 | computeBV<OBB, Halfspace>(s, tf, bv.obb); | |
| 592 | 4 | computeBV<RSS, Halfspace>(s, tf, bv.rss); | |
| 593 | 4 | } | |
| 594 | |||
| 595 | template <> | ||
| 596 | ✗ | void computeBV<kIOS, Halfspace>(const Halfspace& s, const Transform3s& tf, | |
| 597 | kIOS& bv) { | ||
| 598 | ✗ | if (s.getSweptSphereRadius() > 0) { | |
| 599 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 600 | std::runtime_error); | ||
| 601 | } | ||
| 602 | ✗ | bv.num_spheres = 1; | |
| 603 | ✗ | computeBV<OBB, Halfspace>(s, tf, bv.obb); | |
| 604 | ✗ | bv.spheres[0].o = Vec3s(); | |
| 605 | ✗ | bv.spheres[0].r = (std::numeric_limits<Scalar>::max)(); | |
| 606 | ✗ | } | |
| 607 | |||
| 608 | template <> | ||
| 609 | ✗ | void computeBV<KDOP<16>, Halfspace>(const Halfspace& s, const Transform3s& tf, | |
| 610 | KDOP<16>& bv) { | ||
| 611 | ✗ | if (s.getSweptSphereRadius() > 0) { | |
| 612 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 613 | std::runtime_error); | ||
| 614 | } | ||
| 615 | ✗ | Halfspace new_s = transform(s, tf); | |
| 616 | ✗ | const Vec3s& n = new_s.n; | |
| 617 | ✗ | const Scalar& d = new_s.d; | |
| 618 | |||
| 619 | ✗ | const short D = 8; | |
| 620 | ✗ | for (short i = 0; i < D; ++i) | |
| 621 | ✗ | bv.dist(i) = -(std::numeric_limits<Scalar>::max)(); | |
| 622 | ✗ | for (short i = D; i < 2 * D; ++i) | |
| 623 | ✗ | bv.dist(i) = (std::numeric_limits<Scalar>::max)(); | |
| 624 | |||
| 625 | ✗ | if (n[1] == (Scalar)0.0 && n[2] == (Scalar)0.0) { | |
| 626 | ✗ | if (n[0] > 0) | |
| 627 | ✗ | bv.dist(D) = d; | |
| 628 | else | ||
| 629 | ✗ | bv.dist(0) = -d; | |
| 630 | ✗ | } else if (n[0] == (Scalar)0.0 && n[2] == (Scalar)0.0) { | |
| 631 | ✗ | if (n[1] > 0) | |
| 632 | ✗ | bv.dist(D + 1) = d; | |
| 633 | else | ||
| 634 | ✗ | bv.dist(1) = -d; | |
| 635 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] == (Scalar)0.0) { | |
| 636 | ✗ | if (n[2] > 0) | |
| 637 | ✗ | bv.dist(D + 2) = d; | |
| 638 | else | ||
| 639 | ✗ | bv.dist(2) = -d; | |
| 640 | ✗ | } else if (n[2] == (Scalar)0.0 && n[0] == n[1]) { | |
| 641 | ✗ | if (n[0] > 0) | |
| 642 | ✗ | bv.dist(D + 3) = n[0] * d * 2; | |
| 643 | else | ||
| 644 | ✗ | bv.dist(3) = n[0] * d * 2; | |
| 645 | ✗ | } else if (n[1] == (Scalar)0.0 && n[0] == n[2]) { | |
| 646 | ✗ | if (n[1] > 0) | |
| 647 | ✗ | bv.dist(D + 4) = n[0] * d * 2; | |
| 648 | else | ||
| 649 | ✗ | bv.dist(4) = n[0] * d * 2; | |
| 650 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] == n[2]) { | |
| 651 | ✗ | if (n[1] > 0) | |
| 652 | ✗ | bv.dist(D + 5) = n[1] * d * 2; | |
| 653 | else | ||
| 654 | ✗ | bv.dist(5) = n[1] * d * 2; | |
| 655 | ✗ | } else if (n[2] == (Scalar)0.0 && n[0] + n[1] == (Scalar)0.0) { | |
| 656 | ✗ | if (n[0] > 0) | |
| 657 | ✗ | bv.dist(D + 6) = n[0] * d * 2; | |
| 658 | else | ||
| 659 | ✗ | bv.dist(6) = n[0] * d * 2; | |
| 660 | ✗ | } else if (n[1] == (Scalar)0.0 && n[0] + n[2] == (Scalar)0.0) { | |
| 661 | ✗ | if (n[0] > 0) | |
| 662 | ✗ | bv.dist(D + 7) = n[0] * d * 2; | |
| 663 | else | ||
| 664 | ✗ | bv.dist(7) = n[0] * d * 2; | |
| 665 | } | ||
| 666 | ✗ | } | |
| 667 | |||
| 668 | template <> | ||
| 669 | ✗ | void computeBV<KDOP<18>, Halfspace>(const Halfspace& s, const Transform3s& tf, | |
| 670 | KDOP<18>& bv) { | ||
| 671 | ✗ | if (s.getSweptSphereRadius() > 0) { | |
| 672 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 673 | std::runtime_error); | ||
| 674 | } | ||
| 675 | ✗ | Halfspace new_s = transform(s, tf); | |
| 676 | ✗ | const Vec3s& n = new_s.n; | |
| 677 | ✗ | const Scalar& d = new_s.d; | |
| 678 | |||
| 679 | ✗ | const short D = 9; | |
| 680 | |||
| 681 | ✗ | for (short i = 0; i < D; ++i) | |
| 682 | ✗ | bv.dist(i) = -(std::numeric_limits<Scalar>::max)(); | |
| 683 | ✗ | for (short i = D; i < 2 * D; ++i) | |
| 684 | ✗ | bv.dist(i) = (std::numeric_limits<Scalar>::max)(); | |
| 685 | |||
| 686 | ✗ | if (n[1] == (Scalar)0.0 && n[2] == (Scalar)0.0) { | |
| 687 | ✗ | if (n[0] > 0) | |
| 688 | ✗ | bv.dist(D) = d; | |
| 689 | else | ||
| 690 | ✗ | bv.dist(0) = -d; | |
| 691 | ✗ | } else if (n[0] == (Scalar)0.0 && n[2] == (Scalar)0.0) { | |
| 692 | ✗ | if (n[1] > 0) | |
| 693 | ✗ | bv.dist(D + 1) = d; | |
| 694 | else | ||
| 695 | ✗ | bv.dist(1) = -d; | |
| 696 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] == (Scalar)0.0) { | |
| 697 | ✗ | if (n[2] > 0) | |
| 698 | ✗ | bv.dist(D + 2) = d; | |
| 699 | else | ||
| 700 | ✗ | bv.dist(2) = -d; | |
| 701 | ✗ | } else if (n[2] == (Scalar)0.0 && n[0] == n[1]) { | |
| 702 | ✗ | if (n[0] > 0) | |
| 703 | ✗ | bv.dist(D + 3) = n[0] * d * 2; | |
| 704 | else | ||
| 705 | ✗ | bv.dist(3) = n[0] * d * 2; | |
| 706 | ✗ | } else if (n[1] == (Scalar)0.0 && n[0] == n[2]) { | |
| 707 | ✗ | if (n[1] > 0) | |
| 708 | ✗ | bv.dist(D + 4) = n[0] * d * 2; | |
| 709 | else | ||
| 710 | ✗ | bv.dist(4) = n[0] * d * 2; | |
| 711 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] == n[2]) { | |
| 712 | ✗ | if (n[1] > 0) | |
| 713 | ✗ | bv.dist(D + 5) = n[1] * d * 2; | |
| 714 | else | ||
| 715 | ✗ | bv.dist(5) = n[1] * d * 2; | |
| 716 | ✗ | } else if (n[2] == (Scalar)0.0 && n[0] + n[1] == (Scalar)0.0) { | |
| 717 | ✗ | if (n[0] > 0) | |
| 718 | ✗ | bv.dist(D + 6) = n[0] * d * 2; | |
| 719 | else | ||
| 720 | ✗ | bv.dist(6) = n[0] * d * 2; | |
| 721 | ✗ | } else if (n[1] == (Scalar)0.0 && n[0] + n[2] == (Scalar)0.0) { | |
| 722 | ✗ | if (n[0] > 0) | |
| 723 | ✗ | bv.dist(D + 7) = n[0] * d * 2; | |
| 724 | else | ||
| 725 | ✗ | bv.dist(7) = n[0] * d * 2; | |
| 726 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] + n[2] == (Scalar)0.0) { | |
| 727 | ✗ | if (n[1] > 0) | |
| 728 | ✗ | bv.dist(D + 8) = n[1] * d * 2; | |
| 729 | else | ||
| 730 | ✗ | bv.dist(8) = n[1] * d * 2; | |
| 731 | } | ||
| 732 | ✗ | } | |
| 733 | |||
| 734 | template <> | ||
| 735 | ✗ | void computeBV<KDOP<24>, Halfspace>(const Halfspace& s, const Transform3s& tf, | |
| 736 | KDOP<24>& bv) { | ||
| 737 | ✗ | if (s.getSweptSphereRadius() > 0) { | |
| 738 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 739 | std::runtime_error); | ||
| 740 | } | ||
| 741 | ✗ | Halfspace new_s = transform(s, tf); | |
| 742 | ✗ | const Vec3s& n = new_s.n; | |
| 743 | ✗ | const Scalar& d = new_s.d; | |
| 744 | |||
| 745 | ✗ | const short D = 12; | |
| 746 | |||
| 747 | ✗ | for (short i = 0; i < D; ++i) | |
| 748 | ✗ | bv.dist(i) = -(std::numeric_limits<Scalar>::max)(); | |
| 749 | ✗ | for (short i = D; i < 2 * D; ++i) | |
| 750 | ✗ | bv.dist(i) = (std::numeric_limits<Scalar>::max)(); | |
| 751 | |||
| 752 | ✗ | if (n[1] == (Scalar)0.0 && n[2] == (Scalar)0.0) { | |
| 753 | ✗ | if (n[0] > 0) | |
| 754 | ✗ | bv.dist(D) = d; | |
| 755 | else | ||
| 756 | ✗ | bv.dist(0) = -d; | |
| 757 | ✗ | } else if (n[0] == (Scalar)0.0 && n[2] == (Scalar)0.0) { | |
| 758 | ✗ | if (n[1] > 0) | |
| 759 | ✗ | bv.dist(D + 1) = d; | |
| 760 | else | ||
| 761 | ✗ | bv.dist(1) = -d; | |
| 762 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] == (Scalar)0.0) { | |
| 763 | ✗ | if (n[2] > 0) | |
| 764 | ✗ | bv.dist(D + 2) = d; | |
| 765 | else | ||
| 766 | ✗ | bv.dist(2) = -d; | |
| 767 | ✗ | } else if (n[2] == (Scalar)0.0 && n[0] == n[1]) { | |
| 768 | ✗ | if (n[0] > 0) | |
| 769 | ✗ | bv.dist(D + 3) = n[0] * d * 2; | |
| 770 | else | ||
| 771 | ✗ | bv.dist(3) = n[0] * d * 2; | |
| 772 | ✗ | } else if (n[1] == (Scalar)0.0 && n[0] == n[2]) { | |
| 773 | ✗ | if (n[1] > 0) | |
| 774 | ✗ | bv.dist(D + 4) = n[0] * d * 2; | |
| 775 | else | ||
| 776 | ✗ | bv.dist(4) = n[0] * d * 2; | |
| 777 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] == n[2]) { | |
| 778 | ✗ | if (n[1] > 0) | |
| 779 | ✗ | bv.dist(D + 5) = n[1] * d * 2; | |
| 780 | else | ||
| 781 | ✗ | bv.dist(5) = n[1] * d * 2; | |
| 782 | ✗ | } else if (n[2] == (Scalar)0.0 && n[0] + n[1] == (Scalar)0.0) { | |
| 783 | ✗ | if (n[0] > 0) | |
| 784 | ✗ | bv.dist(D + 6) = n[0] * d * 2; | |
| 785 | else | ||
| 786 | ✗ | bv.dist(6) = n[0] * d * 2; | |
| 787 | ✗ | } else if (n[1] == (Scalar)0.0 && n[0] + n[2] == (Scalar)0.0) { | |
| 788 | ✗ | if (n[0] > 0) | |
| 789 | ✗ | bv.dist(D + 7) = n[0] * d * 2; | |
| 790 | else | ||
| 791 | ✗ | bv.dist(7) = n[0] * d * 2; | |
| 792 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] + n[2] == (Scalar)0.0) { | |
| 793 | ✗ | if (n[1] > 0) | |
| 794 | ✗ | bv.dist(D + 8) = n[1] * d * 2; | |
| 795 | else | ||
| 796 | ✗ | bv.dist(8) = n[1] * d * 2; | |
| 797 | ✗ | } else if (n[0] + n[2] == (Scalar)0.0 && n[0] + n[1] == (Scalar)0.0) { | |
| 798 | ✗ | if (n[0] > 0) | |
| 799 | ✗ | bv.dist(D + 9) = n[0] * d * 3; | |
| 800 | else | ||
| 801 | ✗ | bv.dist(9) = n[0] * d * 3; | |
| 802 | ✗ | } else if (n[0] + n[1] == (Scalar)0.0 && n[1] + n[2] == (Scalar)0.0) { | |
| 803 | ✗ | if (n[0] > 0) | |
| 804 | ✗ | bv.dist(D + 10) = n[0] * d * 3; | |
| 805 | else | ||
| 806 | ✗ | bv.dist(10) = n[0] * d * 3; | |
| 807 | ✗ | } else if (n[0] + n[1] == (Scalar)0.0 && n[0] + n[2] == (Scalar)0.0) { | |
| 808 | ✗ | if (n[1] > 0) | |
| 809 | ✗ | bv.dist(D + 11) = n[1] * d * 3; | |
| 810 | else | ||
| 811 | ✗ | bv.dist(11) = n[1] * d * 3; | |
| 812 | } | ||
| 813 | ✗ | } | |
| 814 | |||
| 815 | template <> | ||
| 816 | ✗ | void computeBV<OBB, Plane>(const Plane& s, const Transform3s& tf, OBB& bv) { | |
| 817 | ✗ | if (s.getSweptSphereRadius() > 0) { | |
| 818 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 819 | std::runtime_error); | ||
| 820 | } | ||
| 821 | ✗ | Vec3s n = tf.getRotation() * s.n; | |
| 822 | ✗ | generateCoordinateSystem(n, bv.axes.col(1), bv.axes.col(2)); | |
| 823 | ✗ | bv.axes.col(0).noalias() = n; | |
| 824 | |||
| 825 | ✗ | bv.extent << 0, (std::numeric_limits<Scalar>::max)(), | |
| 826 | ✗ | (std::numeric_limits<Scalar>::max)(); | |
| 827 | |||
| 828 | ✗ | Vec3s p = s.n * s.d; | |
| 829 | bv.To = | ||
| 830 | ✗ | tf.transform(p); /// n'd' = R * n * (d + (R * n) * T) = R * (n * d) + T | |
| 831 | ✗ | } | |
| 832 | |||
| 833 | template <> | ||
| 834 | ✗ | void computeBV<RSS, Plane>(const Plane& s, const Transform3s& tf, RSS& bv) { | |
| 835 | ✗ | if (s.getSweptSphereRadius() > 0) { | |
| 836 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 837 | std::runtime_error); | ||
| 838 | } | ||
| 839 | ✗ | Vec3s n = tf.getRotation() * s.n; | |
| 840 | |||
| 841 | ✗ | generateCoordinateSystem(n, bv.axes.col(1), bv.axes.col(2)); | |
| 842 | ✗ | bv.axes.col(0).noalias() = n; | |
| 843 | |||
| 844 | ✗ | bv.length[0] = (std::numeric_limits<Scalar>::max)(); | |
| 845 | ✗ | bv.length[1] = (std::numeric_limits<Scalar>::max)(); | |
| 846 | |||
| 847 | ✗ | bv.radius = 0; | |
| 848 | |||
| 849 | ✗ | Vec3s p = s.n * s.d; | |
| 850 | ✗ | bv.Tr = tf.transform(p); | |
| 851 | ✗ | } | |
| 852 | |||
| 853 | template <> | ||
| 854 | ✗ | void computeBV<OBBRSS, Plane>(const Plane& s, const Transform3s& tf, | |
| 855 | OBBRSS& bv) { | ||
| 856 | ✗ | if (s.getSweptSphereRadius() > 0) { | |
| 857 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 858 | std::runtime_error); | ||
| 859 | } | ||
| 860 | ✗ | computeBV<OBB, Plane>(s, tf, bv.obb); | |
| 861 | ✗ | computeBV<RSS, Plane>(s, tf, bv.rss); | |
| 862 | ✗ | } | |
| 863 | |||
| 864 | template <> | ||
| 865 | ✗ | void computeBV<kIOS, Plane>(const Plane& s, const Transform3s& tf, kIOS& bv) { | |
| 866 | ✗ | if (s.getSweptSphereRadius() > 0) { | |
| 867 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 868 | std::runtime_error); | ||
| 869 | } | ||
| 870 | ✗ | bv.num_spheres = 1; | |
| 871 | ✗ | computeBV<OBB, Plane>(s, tf, bv.obb); | |
| 872 | ✗ | bv.spheres[0].o = Vec3s(); | |
| 873 | ✗ | bv.spheres[0].r = (std::numeric_limits<Scalar>::max)(); | |
| 874 | ✗ | } | |
| 875 | |||
| 876 | template <> | ||
| 877 | ✗ | void computeBV<KDOP<16>, Plane>(const Plane& s, const Transform3s& tf, | |
| 878 | KDOP<16>& bv) { | ||
| 879 | ✗ | if (s.getSweptSphereRadius() > 0) { | |
| 880 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 881 | std::runtime_error); | ||
| 882 | } | ||
| 883 | ✗ | Plane new_s = transform(s, tf); | |
| 884 | ✗ | const Vec3s& n = new_s.n; | |
| 885 | ✗ | const Scalar& d = new_s.d; | |
| 886 | |||
| 887 | ✗ | const short D = 8; | |
| 888 | |||
| 889 | ✗ | for (short i = 0; i < D; ++i) | |
| 890 | ✗ | bv.dist(i) = -(std::numeric_limits<Scalar>::max)(); | |
| 891 | ✗ | for (short i = D; i < 2 * D; ++i) | |
| 892 | ✗ | bv.dist(i) = (std::numeric_limits<Scalar>::max)(); | |
| 893 | |||
| 894 | ✗ | if (n[1] == (Scalar)0.0 && n[2] == (Scalar)0.0) { | |
| 895 | ✗ | if (n[0] > 0) | |
| 896 | ✗ | bv.dist(0) = bv.dist(D) = d; | |
| 897 | else | ||
| 898 | ✗ | bv.dist(0) = bv.dist(D) = -d; | |
| 899 | ✗ | } else if (n[0] == (Scalar)0.0 && n[2] == (Scalar)0.0) { | |
| 900 | ✗ | if (n[1] > 0) | |
| 901 | ✗ | bv.dist(1) = bv.dist(D + 1) = d; | |
| 902 | else | ||
| 903 | ✗ | bv.dist(1) = bv.dist(D + 1) = -d; | |
| 904 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] == (Scalar)0.0) { | |
| 905 | ✗ | if (n[2] > 0) | |
| 906 | ✗ | bv.dist(2) = bv.dist(D + 2) = d; | |
| 907 | else | ||
| 908 | ✗ | bv.dist(2) = bv.dist(D + 2) = -d; | |
| 909 | ✗ | } else if (n[2] == (Scalar)0.0 && n[0] == n[1]) { | |
| 910 | ✗ | bv.dist(3) = bv.dist(D + 3) = n[0] * d * 2; | |
| 911 | ✗ | } else if (n[1] == (Scalar)0.0 && n[0] == n[2]) { | |
| 912 | ✗ | bv.dist(4) = bv.dist(D + 4) = n[0] * d * 2; | |
| 913 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] == n[2]) { | |
| 914 | ✗ | bv.dist(6) = bv.dist(D + 5) = n[1] * d * 2; | |
| 915 | ✗ | } else if (n[2] == (Scalar)0.0 && n[0] + n[1] == (Scalar)0.0) { | |
| 916 | ✗ | bv.dist(6) = bv.dist(D + 6) = n[0] * d * 2; | |
| 917 | ✗ | } else if (n[1] == (Scalar)0.0 && n[0] + n[2] == (Scalar)0.0) { | |
| 918 | ✗ | bv.dist(7) = bv.dist(D + 7) = n[0] * d * 2; | |
| 919 | } | ||
| 920 | ✗ | } | |
| 921 | |||
| 922 | template <> | ||
| 923 | ✗ | void computeBV<KDOP<18>, Plane>(const Plane& s, const Transform3s& tf, | |
| 924 | KDOP<18>& bv) { | ||
| 925 | ✗ | if (s.getSweptSphereRadius() > 0) { | |
| 926 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 927 | std::runtime_error); | ||
| 928 | } | ||
| 929 | ✗ | Plane new_s = transform(s, tf); | |
| 930 | ✗ | const Vec3s& n = new_s.n; | |
| 931 | ✗ | const Scalar& d = new_s.d; | |
| 932 | |||
| 933 | ✗ | const short D = 9; | |
| 934 | |||
| 935 | ✗ | for (short i = 0; i < D; ++i) | |
| 936 | ✗ | bv.dist(i) = -(std::numeric_limits<Scalar>::max)(); | |
| 937 | ✗ | for (short i = D; i < 2 * D; ++i) | |
| 938 | ✗ | bv.dist(i) = (std::numeric_limits<Scalar>::max)(); | |
| 939 | |||
| 940 | ✗ | if (n[1] == (Scalar)0.0 && n[2] == (Scalar)0.0) { | |
| 941 | ✗ | if (n[0] > 0) | |
| 942 | ✗ | bv.dist(0) = bv.dist(D) = d; | |
| 943 | else | ||
| 944 | ✗ | bv.dist(0) = bv.dist(D) = -d; | |
| 945 | ✗ | } else if (n[0] == (Scalar)0.0 && n[2] == (Scalar)0.0) { | |
| 946 | ✗ | if (n[1] > 0) | |
| 947 | ✗ | bv.dist(1) = bv.dist(D + 1) = d; | |
| 948 | else | ||
| 949 | ✗ | bv.dist(1) = bv.dist(D + 1) = -d; | |
| 950 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] == (Scalar)0.0) { | |
| 951 | ✗ | if (n[2] > 0) | |
| 952 | ✗ | bv.dist(2) = bv.dist(D + 2) = d; | |
| 953 | else | ||
| 954 | ✗ | bv.dist(2) = bv.dist(D + 2) = -d; | |
| 955 | ✗ | } else if (n[2] == (Scalar)0.0 && n[0] == n[1]) { | |
| 956 | ✗ | bv.dist(3) = bv.dist(D + 3) = n[0] * d * 2; | |
| 957 | ✗ | } else if (n[1] == (Scalar)0.0 && n[0] == n[2]) { | |
| 958 | ✗ | bv.dist(4) = bv.dist(D + 4) = n[0] * d * 2; | |
| 959 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] == n[2]) { | |
| 960 | ✗ | bv.dist(5) = bv.dist(D + 5) = n[1] * d * 2; | |
| 961 | ✗ | } else if (n[2] == (Scalar)0.0 && n[0] + n[1] == (Scalar)0.0) { | |
| 962 | ✗ | bv.dist(6) = bv.dist(D + 6) = n[0] * d * 2; | |
| 963 | ✗ | } else if (n[1] == (Scalar)0.0 && n[0] + n[2] == (Scalar)0.0) { | |
| 964 | ✗ | bv.dist(7) = bv.dist(D + 7) = n[0] * d * 2; | |
| 965 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] + n[2] == (Scalar)0.0) { | |
| 966 | ✗ | bv.dist(8) = bv.dist(D + 8) = n[1] * d * 2; | |
| 967 | } | ||
| 968 | ✗ | } | |
| 969 | |||
| 970 | template <> | ||
| 971 | ✗ | void computeBV<KDOP<24>, Plane>(const Plane& s, const Transform3s& tf, | |
| 972 | KDOP<24>& bv) { | ||
| 973 | ✗ | if (s.getSweptSphereRadius() > 0) { | |
| 974 | ✗ | COAL_THROW_PRETTY("Swept-sphere radius not yet supported.", | |
| 975 | std::runtime_error); | ||
| 976 | } | ||
| 977 | ✗ | Plane new_s = transform(s, tf); | |
| 978 | ✗ | const Vec3s& n = new_s.n; | |
| 979 | ✗ | const Scalar& d = new_s.d; | |
| 980 | |||
| 981 | ✗ | const short D = 12; | |
| 982 | |||
| 983 | ✗ | for (short i = 0; i < D; ++i) | |
| 984 | ✗ | bv.dist(i) = -(std::numeric_limits<Scalar>::max)(); | |
| 985 | ✗ | for (short i = D; i < 2 * D; ++i) | |
| 986 | ✗ | bv.dist(i) = (std::numeric_limits<Scalar>::max)(); | |
| 987 | |||
| 988 | ✗ | if (n[1] == (Scalar)0.0 && n[2] == (Scalar)0.0) { | |
| 989 | ✗ | if (n[0] > 0) | |
| 990 | ✗ | bv.dist(0) = bv.dist(D) = d; | |
| 991 | else | ||
| 992 | ✗ | bv.dist(0) = bv.dist(D) = -d; | |
| 993 | ✗ | } else if (n[0] == (Scalar)0.0 && n[2] == (Scalar)0.0) { | |
| 994 | ✗ | if (n[1] > 0) | |
| 995 | ✗ | bv.dist(1) = bv.dist(D + 1) = d; | |
| 996 | else | ||
| 997 | ✗ | bv.dist(1) = bv.dist(D + 1) = -d; | |
| 998 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] == (Scalar)0.0) { | |
| 999 | ✗ | if (n[2] > 0) | |
| 1000 | ✗ | bv.dist(2) = bv.dist(D + 2) = d; | |
| 1001 | else | ||
| 1002 | ✗ | bv.dist(2) = bv.dist(D + 2) = -d; | |
| 1003 | ✗ | } else if (n[2] == (Scalar)0.0 && n[0] == n[1]) { | |
| 1004 | ✗ | bv.dist(3) = bv.dist(D + 3) = n[0] * d * 2; | |
| 1005 | ✗ | } else if (n[1] == (Scalar)0.0 && n[0] == n[2]) { | |
| 1006 | ✗ | bv.dist(4) = bv.dist(D + 4) = n[0] * d * 2; | |
| 1007 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] == n[2]) { | |
| 1008 | ✗ | bv.dist(5) = bv.dist(D + 5) = n[1] * d * 2; | |
| 1009 | ✗ | } else if (n[2] == (Scalar)0.0 && n[0] + n[1] == (Scalar)0.0) { | |
| 1010 | ✗ | bv.dist(6) = bv.dist(D + 6) = n[0] * d * 2; | |
| 1011 | ✗ | } else if (n[1] == (Scalar)0.0 && n[0] + n[2] == (Scalar)0.0) { | |
| 1012 | ✗ | bv.dist(7) = bv.dist(D + 7) = n[0] * d * 2; | |
| 1013 | ✗ | } else if (n[0] == (Scalar)0.0 && n[1] + n[2] == (Scalar)0.0) { | |
| 1014 | ✗ | bv.dist(8) = bv.dist(D + 8) = n[1] * d * 2; | |
| 1015 | ✗ | } else if (n[0] + n[2] == (Scalar)0.0 && n[0] + n[1] == (Scalar)0.0) { | |
| 1016 | ✗ | bv.dist(9) = bv.dist(D + 9) = n[0] * d * 3; | |
| 1017 | ✗ | } else if (n[0] + n[1] == (Scalar)0.0 && n[1] + n[2] == (Scalar)0.0) { | |
| 1018 | ✗ | bv.dist(10) = bv.dist(D + 10) = n[0] * d * 3; | |
| 1019 | ✗ | } else if (n[0] + n[1] == (Scalar)0.0 && n[0] + n[2] == (Scalar)0.0) { | |
| 1020 | ✗ | bv.dist(11) = bv.dist(D + 11) = n[1] * d * 3; | |
| 1021 | } | ||
| 1022 | ✗ | } | |
| 1023 | |||
| 1024 | 40 | void constructBox(const AABB& bv, Box& box, Transform3s& tf) { | |
| 1025 |
4/8✓ Branch 1 taken 40 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 40 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 40 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 40 times.
✗ Branch 11 not taken.
|
40 | box = Box(bv.max_ - bv.min_); |
| 1026 |
3/6✓ Branch 1 taken 40 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 40 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 40 times.
✗ Branch 8 not taken.
|
40 | tf = Transform3s(bv.center()); |
| 1027 | 40 | } | |
| 1028 | |||
| 1029 | ✗ | void constructBox(const OBB& bv, Box& box, Transform3s& tf) { | |
| 1030 | ✗ | box = Box(bv.extent * 2); | |
| 1031 | ✗ | tf = Transform3s(bv.axes, bv.To); | |
| 1032 | ✗ | } | |
| 1033 | |||
| 1034 | ✗ | void constructBox(const OBBRSS& bv, Box& box, Transform3s& tf) { | |
| 1035 | ✗ | box = Box(bv.obb.extent * 2); | |
| 1036 | ✗ | tf = Transform3s(bv.obb.axes, bv.obb.To); | |
| 1037 | ✗ | } | |
| 1038 | |||
| 1039 | ✗ | void constructBox(const kIOS& bv, Box& box, Transform3s& tf) { | |
| 1040 | ✗ | box = Box(bv.obb.extent * 2); | |
| 1041 | ✗ | tf = Transform3s(bv.obb.axes, bv.obb.To); | |
| 1042 | ✗ | } | |
| 1043 | |||
| 1044 | ✗ | void constructBox(const RSS& bv, Box& box, Transform3s& tf) { | |
| 1045 | ✗ | box = Box(bv.width(), bv.height(), bv.depth()); | |
| 1046 | ✗ | tf = Transform3s(bv.axes, bv.Tr); | |
| 1047 | ✗ | } | |
| 1048 | |||
| 1049 | ✗ | void constructBox(const KDOP<16>& bv, Box& box, Transform3s& tf) { | |
| 1050 | ✗ | box = Box(bv.width(), bv.height(), bv.depth()); | |
| 1051 | ✗ | tf = Transform3s(bv.center()); | |
| 1052 | ✗ | } | |
| 1053 | |||
| 1054 | ✗ | void constructBox(const KDOP<18>& bv, Box& box, Transform3s& tf) { | |
| 1055 | ✗ | box = Box(bv.width(), bv.height(), bv.depth()); | |
| 1056 | ✗ | tf = Transform3s(bv.center()); | |
| 1057 | ✗ | } | |
| 1058 | |||
| 1059 | ✗ | void constructBox(const KDOP<24>& bv, Box& box, Transform3s& tf) { | |
| 1060 | ✗ | box = Box(bv.width(), bv.height(), bv.depth()); | |
| 1061 | ✗ | tf = Transform3s(bv.center()); | |
| 1062 | ✗ | } | |
| 1063 | |||
| 1064 | 2589 | void constructBox(const AABB& bv, const Transform3s& tf_bv, Box& box, | |
| 1065 | Transform3s& tf) { | ||
| 1066 |
4/8✓ Branch 1 taken 2589 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2589 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2589 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 2589 times.
✗ Branch 11 not taken.
|
2589 | box = Box(bv.max_ - bv.min_); |
| 1067 |
4/8✓ Branch 1 taken 2589 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2589 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2589 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 2589 times.
✗ Branch 11 not taken.
|
2589 | tf = tf_bv * Transform3s(bv.center()); |
| 1068 | 2589 | } | |
| 1069 | |||
| 1070 | ✗ | void constructBox(const OBB& bv, const Transform3s& tf_bv, Box& box, | |
| 1071 | Transform3s& tf) { | ||
| 1072 | ✗ | box = Box(bv.extent * 2); | |
| 1073 | ✗ | tf = tf_bv * Transform3s(bv.axes, bv.To); | |
| 1074 | ✗ | } | |
| 1075 | |||
| 1076 | ✗ | void constructBox(const OBBRSS& bv, const Transform3s& tf_bv, Box& box, | |
| 1077 | Transform3s& tf) { | ||
| 1078 | ✗ | box = Box(bv.obb.extent * 2); | |
| 1079 | ✗ | tf = tf_bv * Transform3s(bv.obb.axes, bv.obb.To); | |
| 1080 | ✗ | } | |
| 1081 | |||
| 1082 | ✗ | void constructBox(const kIOS& bv, const Transform3s& tf_bv, Box& box, | |
| 1083 | Transform3s& tf) { | ||
| 1084 | ✗ | box = Box(bv.obb.extent * 2); | |
| 1085 | ✗ | tf = tf_bv * Transform3s(bv.obb.axes, bv.obb.To); | |
| 1086 | ✗ | } | |
| 1087 | |||
| 1088 | ✗ | void constructBox(const RSS& bv, const Transform3s& tf_bv, Box& box, | |
| 1089 | Transform3s& tf) { | ||
| 1090 | ✗ | box = Box(bv.width(), bv.height(), bv.depth()); | |
| 1091 | ✗ | tf = tf_bv * Transform3s(bv.axes, bv.Tr); | |
| 1092 | ✗ | } | |
| 1093 | |||
| 1094 | ✗ | void constructBox(const KDOP<16>& bv, const Transform3s& tf_bv, Box& box, | |
| 1095 | Transform3s& tf) { | ||
| 1096 | ✗ | box = Box(bv.width(), bv.height(), bv.depth()); | |
| 1097 | ✗ | tf = tf_bv * Transform3s(bv.center()); | |
| 1098 | ✗ | } | |
| 1099 | |||
| 1100 | ✗ | void constructBox(const KDOP<18>& bv, const Transform3s& tf_bv, Box& box, | |
| 1101 | Transform3s& tf) { | ||
| 1102 | ✗ | box = Box(bv.width(), bv.height(), bv.depth()); | |
| 1103 | ✗ | tf = tf_bv * Transform3s(bv.center()); | |
| 1104 | ✗ | } | |
| 1105 | |||
| 1106 | ✗ | void constructBox(const KDOP<24>& bv, const Transform3s& tf_bv, Box& box, | |
| 1107 | Transform3s& tf) { | ||
| 1108 | ✗ | box = Box(bv.width(), bv.height(), bv.depth()); | |
| 1109 | ✗ | tf = tf_bv * Transform3s(bv.center()); | |
| 1110 | ✗ | } | |
| 1111 | |||
| 1112 | } // namespace coal | ||
| 1113 |