test_fcl_generate_bvh_model_deferred_finalize.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2016, Open Source Robotics Foundation
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Open Source Robotics Foundation nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
37 #include <gtest/gtest.h>
38 
39 #include "fcl/config.h"
41 #include "test_fcl_utility.h"
42 #include <iostream>
43 
44 using namespace fcl;
45 
62 template<typename BV, typename ShapeType>
63 void checkAddToEmptyModel(BVHModel<BV>& model, const ShapeType& shape)
64 {
65  using S = typename BV::S;
66  uint8_t n = 32; // Hard-coded mesh-resolution. Not testing corner cases where n=0 or such
67  int ret;
68 
69  // Make sure we are given an empty model
70  GTEST_ASSERT_EQ(model.build_state, BVH_BUILD_STATE_EMPTY);
71  uint8_t num_vertices = model.num_vertices;
72  uint8_t num_tris = model.num_tris;
73  GTEST_ASSERT_EQ(num_vertices, 0);
74  GTEST_ASSERT_EQ(num_tris, 0);
75 
76  // Add the shape to the model and count vertices and triangles to make sure it has been created
78  GTEST_ASSERT_EQ(ret, BVH_OK);
79  EXPECT_GT(model.num_vertices, num_vertices);
80  EXPECT_GT(model.num_tris, num_tris);
82 }
83 
84 // Specialization for boxes
85 template<typename BV>
87 {
88  using S = typename BV::S;
89  int ret;
90 
91  // Make sure we are given an empty model
92  GTEST_ASSERT_EQ(model.build_state, BVH_BUILD_STATE_EMPTY);
93  GTEST_ASSERT_EQ(model.num_vertices, 0);
94  GTEST_ASSERT_EQ(model.num_tris, 0);
95 
96  // Add the shape to the model and count vertices and triangles to make sure it has been created
98  GTEST_ASSERT_EQ(ret, BVH_OK);
99  EXPECT_EQ(model.num_vertices, 8);
100  EXPECT_EQ(model.num_tris, 12);
102 }
103 
104 
111 template<typename BV, typename ShapeType>
112 void checkAddToUnfinalizedModel(BVHModel<BV>& model, const ShapeType& shape)
113 {
114  using S = typename BV::S;
115  const uint8_t n = 32;
116  int ret;
117 
118  // Make sure we are given a model that is already begun
119  GTEST_ASSERT_EQ(model.build_state, BVH_BUILD_STATE_BEGUN);
120  uint8_t num_vertices = model.num_vertices;
121  uint8_t num_tris = model.num_tris;
122 
123  // Add the shape to the model and count vertices and triangles to make sure it has been created
124  ret = generateBVHModel(model, shape, Transform3<S>(Translation3<S>(Vector3<S>(2.0, 2.0, 2.0))), n, FinalizeModel::DONT);
125  GTEST_ASSERT_EQ(ret, BVH_OK);
126  EXPECT_GT(model.num_vertices, num_vertices);
127  EXPECT_GT(model.num_tris, num_tris);
129 }
130 
131 // Specialization for boxes
132 template<typename BV>
134 {
135  using S = typename BV::S;
136  int ret;
137 
138  // Make sure we are given a model that is already begun
139  GTEST_ASSERT_EQ(model.build_state, BVH_BUILD_STATE_BEGUN);
140  uint8_t num_vertices = model.num_vertices;
141  uint8_t num_tris = model.num_tris;
142 
143  // Add the shape to the model and count vertices and triangles to make sure it has been created
144  ret = generateBVHModel(model, shape, Transform3<S>(Translation3<S>(Vector3<S>(2.0, 2.0, 2.0))), FinalizeModel::DONT);
145  GTEST_ASSERT_EQ(ret, BVH_OK);
146  EXPECT_EQ(model.num_vertices, num_vertices + 8);
147  EXPECT_EQ(model.num_tris, num_tris + 12);
149 }
150 
158 template<typename BV, typename ShapeType>
159 void checkAddAndFinalizeModel(BVHModel<BV>& model, const ShapeType& shape){
160  using S = typename BV::S;
161  const uint8_t n = 32;
162  int ret;
163 
164  // Make sure we are given a model that is already begun
165  GTEST_ASSERT_EQ(model.build_state, BVH_BUILD_STATE_BEGUN);
166  uint8_t num_vertices = model.num_vertices;
167  uint8_t num_tris = model.num_tris;
168 
169  // Add another instance of the shape and make sure it was added to the model by counting vertices and tris
170  ret = generateBVHModel(model, shape, Transform3<S>(Translation3<S>(Vector3<S>(2.0, 2.0, 2.0))), n, FinalizeModel::DO);
171  GTEST_ASSERT_EQ(ret, BVH_OK);
172  EXPECT_GT(model.num_vertices, num_vertices);
173  EXPECT_GT(model.num_tris, num_tris);
175 }
176 
177 // Specialization for boxes
178 template<typename BV>
180  using S = typename BV::S;
181  int ret;
182 
183  // Make sure we are given a model that is already begun
184  GTEST_ASSERT_EQ(model.build_state, BVH_BUILD_STATE_BEGUN);
185  uint8_t num_vertices = model.num_vertices;
186  uint8_t num_tris = model.num_tris;
187 
188  // Add another instance of the shape and make sure it was added to the model by counting vertices and tris
189  ret = generateBVHModel(model, shape, Transform3<S>(Translation3<S>(Vector3<S>(3.0, 3.0, 3.0))), FinalizeModel::DO);
190  GTEST_ASSERT_EQ(ret, BVH_OK);
191  EXPECT_EQ(model.num_vertices, num_vertices + 8);
192  EXPECT_EQ(model.num_tris, num_tris + 12);
194 }
195 
196 
201 template<typename BV, typename ShapeType>
202 void checkAddToFinalizedModel(BVHModel<BV>& model, const ShapeType& shape)
203 {
204  using S = typename BV::S;
205  const uint8_t n = 32;
206 
207  GTEST_ASSERT_EQ(model.build_state, BVH_BUILD_STATE_PROCESSED);
208  auto ret = generateBVHModel(model, shape, Transform3<S>::Identity(), n, FinalizeModel::DONT);
210 }
211 
212 // Specialization for boxes
213 template<typename BV>
215 {
216  using S = typename BV::S;
217 
218  GTEST_ASSERT_EQ(model.build_state, BVH_BUILD_STATE_PROCESSED);
219  auto ret = generateBVHModel(model, shape, Transform3<S>::Identity(), FinalizeModel::DONT);
221 }
222 
223 template<typename BV>
225 {
226  using S = typename BV::S;
227  const S a = 1.0;
228  const S b = 1.0;
229  const S c = 1.0;
230 
231  std::shared_ptr<BVHModel<BV>> model(new BVHModel<BV>);
232  Box<S> box(a, b, c);
233 
234  checkAddToEmptyModel(*model, box);
235  checkAddToUnfinalizedModel(*model, box);
236  checkAddAndFinalizeModel(*model, box);
237  checkAddToFinalizedModel(*model, box);
238 
239 }
240 
241 template<typename BV>
243 {
244  using S = typename BV::S;
245  const S r = 1.0;
246 
247  Sphere<S> sphere(r);
248  std::shared_ptr<BVHModel<BV>> model(new BVHModel<BV>);
249  checkAddToEmptyModel(*model, sphere);
250  checkAddToUnfinalizedModel(*model, sphere);
251  checkAddAndFinalizeModel(*model, sphere);
252  checkAddToFinalizedModel(*model, sphere);
253 }
254 
255 template<typename BV>
257 {
258  using S = typename BV::S;
259  const S a = 1.0;
260  const S b = 1.0;
261  const S c = 1.0;
262 
263  Ellipsoid<S> ellipsoid(a, b, c);
264  std::shared_ptr<BVHModel<BV>> model(new BVHModel<BV>);
265 
266  checkAddToEmptyModel(*model, ellipsoid);
267  checkAddToUnfinalizedModel(*model, ellipsoid);
268  checkAddAndFinalizeModel(*model, ellipsoid);
269  checkAddToFinalizedModel(*model, ellipsoid);
270 }
271 
272 template<typename BV>
274 {
275  using S = typename BV::S;
276  const S r = 1.0;
277  const S h = 1.0;
278 
279  Cylinder<S> cylinder(r, h);
280  std::shared_ptr<BVHModel<BV>> model(new BVHModel<BV>);
281 
282  checkAddToEmptyModel(*model, cylinder);
283  checkAddToUnfinalizedModel(*model, cylinder);
284  checkAddAndFinalizeModel(*model, cylinder);
285  checkAddToFinalizedModel(*model, cylinder);
286 }
287 
288 template<typename BV>
290 {
291  using S = typename BV::S;
292  const S r = 1.0;
293  const S h = 1.0;
294 
295  Cone<S> cone(r, h);
296  std::shared_ptr<BVHModel<BV>> model(new BVHModel<BV>);
297 
298  checkAddToEmptyModel(*model, cone);
299  checkAddToUnfinalizedModel(*model, cone);
300  checkAddAndFinalizeModel(*model, cone);
301  checkAddToFinalizedModel(*model, cone);
302 }
303 
304 template<typename BV>
306 {
307  testBVHModelFromBox<BV>();
308  testBVHModelFromSphere<BV>();
309  testBVHModelFromEllipsoid<BV>();
310  testBVHModelFromCylinder<BV>();
311  testBVHModelFromCone<BV>();
312 }
313 
314 GTEST_TEST(FCL_GENERATE_BVH_MODELS, generating_bvh_models_from_primitives)
315 {
316  testBVHModelFromPrimitives<AABB<double>>();
317  testBVHModelFromPrimitives<OBB<double>>();
318  testBVHModelFromPrimitives<RSS<double>>();
319  testBVHModelFromPrimitives<kIOS<double>>();
320  testBVHModelFromPrimitives<OBBRSS<double>>();
321  testBVHModelFromPrimitives<KDOP<double, 16> >();
322  testBVHModelFromPrimitives<KDOP<double, 18> >();
323  testBVHModelFromPrimitives<KDOP<double, 24> >();
324 }
325 
326 //==============================================================================
327 int main(int argc, char* argv[])
328 {
329  ::testing::InitGoogleTest(&argc, argv);
330  return RUN_ALL_TESTS();
331 }
checkAddToUnfinalizedModel
void checkAddToUnfinalizedModel(BVHModel< BV > &model, const ShapeType &shape)
Definition: test_fcl_generate_bvh_model_deferred_finalize.cpp:112
testBVHModelFromCone
void testBVHModelFromCone()
Definition: test_fcl_generate_bvh_model_deferred_finalize.cpp:289
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
fcl::BVH_BUILD_STATE_PROCESSED
@ BVH_BUILD_STATE_PROCESSED
after beginModel(), state for adding geometry primitives
Definition: BVH_internal.h:54
testBVHModelFromCylinder
void testBVHModelFromCylinder()
Definition: test_fcl_generate_bvh_model_deferred_finalize.cpp:273
testBVHModelFromPrimitives
void testBVHModelFromPrimitives()
Definition: test_fcl_generate_bvh_model_deferred_finalize.cpp:305
checkAddAndFinalizeModel
void checkAddAndFinalizeModel(BVHModel< BV > &model, const ShapeType &shape)
Definition: test_fcl_generate_bvh_model_deferred_finalize.cpp:159
main
int main(int argc, char *argv[])
Definition: test_fcl_generate_bvh_model_deferred_finalize.cpp:327
checkAddToFinalizedModel
void checkAddToFinalizedModel(BVHModel< BV > &model, const ShapeType &shape)
Definition: test_fcl_generate_bvh_model_deferred_finalize.cpp:202
fcl::FinalizeModel::DONT
@ DONT
fcl::BVH_BUILD_STATE_BEGUN
@ BVH_BUILD_STATE_BEGUN
empty state, immediately after constructor
Definition: BVH_internal.h:53
testBVHModelFromEllipsoid
void testBVHModelFromEllipsoid()
Definition: test_fcl_generate_bvh_model_deferred_finalize.cpp:256
test_fcl_utility.h
testBVHModelFromSphere
void testBVHModelFromSphere()
Definition: test_fcl_generate_bvh_model_deferred_finalize.cpp:242
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
fcl::BVHModel::num_tris
int num_tris
Number of triangles.
Definition: BVH_model.h:171
checkAddToEmptyModel
void checkAddToEmptyModel(BVHModel< BV > &model, const ShapeType &shape)
Definition: test_fcl_generate_bvh_model_deferred_finalize.cpp:63
fcl::BVHModel::build_state
BVHBuildState build_state
The state of BVH building process.
Definition: BVH_model.h:177
fcl::BVH_BUILD_STATE_EMPTY
@ BVH_BUILD_STATE_EMPTY
Definition: BVH_internal.h:52
testBVHModelFromBox
void testBVHModelFromBox()
Definition: test_fcl_generate_bvh_model_deferred_finalize.cpp:224
GTEST_TEST
GTEST_TEST(FCL_GENERATE_BVH_MODELS, generating_bvh_models_from_primitives)
Definition: test_fcl_generate_bvh_model_deferred_finalize.cpp:314
fcl::Translation3
Eigen::Translation< S, 3 > Translation3
Definition: types.h:94
r
S r
Definition: test_sphere_box.cpp:171
fcl::BVHModel
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: BVH_model.h:57
fcl::Cylinder
Center at zero cylinder.
Definition: cylinder.h:51
fcl::Box
Center at zero point, axis aligned box.
Definition: box.h:51
fcl::BVHModel::num_vertices
int num_vertices
Number of points.
Definition: BVH_model.h:174
fcl::FinalizeModel::DO
@ DO
fcl::Sphere
Center at zero point sphere.
Definition: sphere.h:51
geometric_shape_to_BVH_model.h
fcl::generateBVHModel
int generateBVHModel(BVHModel< BV > &model, const Box< typename BV::S > &shape, const Transform3< typename BV::S > &pose, FinalizeModel finalize_model)
Generate BVH model from box.
Definition: geometric_shape_to_BVH_model-inl.h:69
fcl::Cone
Center at zero cone.
Definition: cone.h:51
fcl::BVH_OK
@ BVH_OK
Definition: BVH_internal.h:63
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
EXPECT_EQ
#define EXPECT_EQ(a, b)
fcl::BVH_ERR_BUILD_OUT_OF_SEQUENCE
@ BVH_ERR_BUILD_OUT_OF_SEQUENCE
Cannot allocate memory for vertices and triangles.
Definition: BVH_internal.h:65
fcl::Ellipsoid
Center at zero point ellipsoid.
Definition: ellipsoid.h:51


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:49