38 #include <gtest/gtest.h>
43 #include "fcl_resources/config.h"
52 bool refit_bottomup,
bool verbose);
54 template<
typename BV,
typename TraversalNode>
70 std::vector<Vector3<S>> p1, p2;
71 std::vector<Triangle> t1, t2;
78 S
extents[] = {-3000, -3000, 0, 3000, 3000, 3000};
79 S delta_trans[] = {1, 1, 1};
87 test::generateRandomTransforms<S>(
extents, delta_trans, 0.005 * 2 * 3.1415, transforms, transforms2, n);
91 for(std::size_t i = 0; i < transforms.size(); ++i)
104 for(std::size_t i = 0; i < transforms.size(); ++i)
117 for(std::size_t i = 0; i < transforms.size(); ++i)
131 for(std::size_t i = 0; i < transforms.size(); ++i)
144 for(std::size_t i = 0; i < transforms.size(); ++i)
157 for(std::size_t i = 0; i < transforms.size(); ++i)
170 for(std::size_t i = 0; i < transforms.size(); ++i)
183 for(std::size_t i = 0; i < transforms.size(); ++i)
201 test_front_list<double>();
204 template<
typename BV>
209 bool refit_bottomup,
bool verbose)
211 using S =
typename BV::S;
221 std::vector<Vector3<S>> vertices1_new(vertices1.size());
222 for(std::size_t i = 0; i < vertices1_new.size(); ++i)
224 vertices1_new[i] = tf1 * vertices1[i];
241 if(!detail::initialize<BV>(node, m1, pose1, m2, pose2,
243 std::cout <<
"initialize error" << std::endl;
249 if(
verbose) std::cout <<
"front list size " << front_list.size() << std::endl;
253 for(std::size_t i = 0; i < vertices1.size(); ++i)
255 vertices1_new[i] = tf2 * vertices1[i];
266 local_result.
clear();
278 template<
typename BV,
typename TraversalNode>
284 using S =
typename BV::S;
309 std::cout <<
"initialize error" << std::endl;
311 node.enable_statistics =
verbose;
315 if(
verbose) std::cout <<
"front list size " << front_list.size() << std::endl;
321 std::cout <<
"initialize error" << std::endl;
323 local_result.
clear();
333 template<
typename BV>
338 using S =
typename BV::S;
359 if(!detail::initialize<BV>(node, m1, pose1, m2, pose2,
361 std::cout <<
"initialize error" << std::endl;
375 int main(
int argc,
char* argv[])
377 ::testing::InitGoogleTest(&argc, argv);
378 return RUN_ALL_TESTS();