diff --git a/trunk/fcl/CMakeLists.txt b/trunk/fcl/CMakeLists.txt index 30bf764a273f6b203f0797bd5301bd5c968a7666..177821ee4b021f9b0994604c042ff3668967161b 100644 --- a/trunk/fcl/CMakeLists.txt +++ b/trunk/fcl/CMakeLists.txt @@ -44,13 +44,14 @@ else() message(STATUS "FCL does not use Octomap") endif() +find_package(Boost COMPONENTS thread date_time filesystem system unit_test_framework REQUIRED) +include_directories(${Boost_INCLUDE_DIR}) + if(MSVC OR MSVC90 OR MSVC10) add_definitions(-DBOOST_ALL_NO_LIB) endif() -find_package(Boost COMPONENTS thread system REQUIRED) -include_directories(${Boost_INCLUDE_DIR}) +add_definitions(-DBOOST_TEST_DYN_LINK) -# make sure we know what flag we used for SSE include_directories("include") if(PKG_CONFIG_FOUND) @@ -88,39 +89,4 @@ install(FILES "${pkg_conf_file}" DESTINATION lib/pkgconfig/ COMPONENT pkgconfig) enable_testing() -find_package(GTest REQUIRED) -include_directories(${GTEST_INCLUDE_DIRS}) - -add_executable(test_fcl_collision test/test_fcl_collision.cpp test/test_fcl_utility.cpp) -target_link_libraries(test_fcl_collision ${PROJECT_NAME} ${GTEST_BOTH_LIBRARIES}) -GTEST_ADD_TESTS(test_fcl_collision "" test/test_fcl_collision.cpp) - -add_executable(test_fcl_distance test/test_fcl_distance.cpp test/test_fcl_utility.cpp) -target_link_libraries(test_fcl_distance ${PROJECT_NAME} ${GTEST_BOTH_LIBRARIES}) -GTEST_ADD_TESTS(test_fcl_distance "" test/test_fcl_distance.cpp) - -add_executable(test_fcl_geometric_shapes test/test_fcl_geometric_shapes.cpp test/test_fcl_utility.cpp) -target_link_libraries(test_fcl_geometric_shapes ${PROJECT_NAME} ${GTEST_BOTH_LIBRARIES}) -GTEST_ADD_TESTS(test_fcl_geometric_shapes "" test/test_fcl_geometric_shapes.cpp) - -add_executable(test_fcl_broadphase test/test_fcl_broadphase.cpp test/test_fcl_utility.cpp) -target_link_libraries(test_fcl_broadphase ${PROJECT_NAME} ${GTEST_BOTH_LIBRARIES}) -GTEST_ADD_TESTS(test_fcl_broadphase "" test/test_fcl_broadphase.cpp) - -add_executable(test_fcl_shape_mesh_consistency test/test_fcl_shape_mesh_consistency.cpp test/test_fcl_utility.cpp) -target_link_libraries(test_fcl_shape_mesh_consistency ${PROJECT_NAME} ${GTEST_BOTH_LIBRARIES}) -GTEST_ADD_TESTS(test_fcl_shape_mesh_consistency "" test/test_fcl_shape_mesh_consistency.cpp) - -add_executable(test_fcl_frontlist test/test_fcl_frontlist.cpp test/test_fcl_utility.cpp) -target_link_libraries(test_fcl_frontlist ${PROJECT_NAME} ${GTEST_BOTH_LIBRARIES}) -GTEST_ADD_TESTS(test_fcl_frontlist "" test/test_fcl_frontlist.cpp) - -add_executable(test_fcl_math test/test_fcl_math.cpp test/test_fcl_utility.cpp) -target_link_libraries(test_fcl_math ${PROJECT_NAME} ${GTEST_BOTH_LIBRARIES}) -GTEST_ADD_TESTS(test_fcl_math "" test/test_fcl_math.cpp) - -if (FCL_HAVE_OCTOMAP) - add_executable(test_fcl_octomap test/test_fcl_octomap.cpp test/test_fcl_utility.cpp) - target_link_libraries(test_fcl_octomap ${PROJECT_NAME} ${GTEST_BOTH_LIBRARIES}) - GTEST_ADD_TESTS(test_fcl_octomap "" test/test_fcl_octomap.cpp) -endif() +add_subdirectory(test) diff --git a/trunk/fcl/manifest.xml b/trunk/fcl/manifest.xml index 87ce8f46ce637e0cdb9aa190feaef2fc64dc403d..b155136f6159a033201834d21020a6b957c7f2b5 100644 --- a/trunk/fcl/manifest.xml +++ b/trunk/fcl/manifest.xml @@ -14,7 +14,7 @@ <rosdep name="octomap" /> <export> - <cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lfcl"/> + <cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/build/lib -L${prefix}/build/lib -lfcl"/> </export> </package> diff --git a/trunk/fcl/test/CMakeLists.txt b/trunk/fcl/test/CMakeLists.txt new file mode 100644 index 0000000000000000000000000000000000000000..5c21b4cc501e616f778670dba7c12403445149b3 --- /dev/null +++ b/trunk/fcl/test/CMakeLists.txt @@ -0,0 +1,32 @@ +macro(add_fcl_test test_name) + add_executable(${ARGV}) + target_link_libraries(${test_name} + fcl + ${Boost_SYSTEM_LIBRARY} + ${Boost_THREAD_LIBRARY} + ${Boost_DATE_TIME_LIBRARY} + ${Boost_UNIT_TEST_FRAMEWORK_LIBRARY}) + add_test(${test_name} ${EXECUTABLE_OUTPUT_PATH}/${test_name}) +endmacro(add_fcl_test) + +# configure location of resources +file(TO_NATIVE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/fcl_resources" TEST_RESOURCES_DIR) +if(WIN32) + # Correct directory separator for Windows + string(REPLACE "\\" "\\\\" TEST_RESOURCES_DIR ${TEST_RESOURCES_DIR}) +endif(WIN32) +configure_file("${TEST_RESOURCES_DIR}/config.h.in" "${TEST_RESOURCES_DIR}/config.h") + +include_directories(.) + +add_fcl_test(test_fcl_collision test_fcl_collision.cpp test_fcl_utility.cpp) +add_fcl_test(test_fcl_distance test_fcl_distance.cpp test_fcl_utility.cpp) +add_fcl_test(test_fcl_geometric_shapes test_fcl_geometric_shapes.cpp test_fcl_utility.cpp) +add_fcl_test(test_fcl_broadphase test_fcl_broadphase.cpp test_fcl_utility.cpp) +add_fcl_test(test_fcl_shape_mesh_consistency test_fcl_shape_mesh_consistency.cpp test_fcl_utility.cpp) +add_fcl_test(test_fcl_frontlist test_fcl_frontlist.cpp test_fcl_utility.cpp) +add_fcl_test(test_fcl_math test_fcl_math.cpp test_fcl_utility.cpp) + +if (FCL_HAVE_OCTOMAP) + add_fcl_test(test_fcl_octomap test_fcl_octomap.cpp test_fcl_utility.cpp) +endif() diff --git a/trunk/fcl/test/fcl_resources/config.h.in b/trunk/fcl/test/fcl_resources/config.h.in new file mode 100644 index 0000000000000000000000000000000000000000..1f8e8cf69d347b5c33bbce4754154dc10ec6cf0d --- /dev/null +++ b/trunk/fcl/test/fcl_resources/config.h.in @@ -0,0 +1,41 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2010, Rice University. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Rice University nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Mark Moll */ + +#ifndef FCL_TEST_RESOURCES_CONFIG_ +#define FCL_TEST_RESOURCES_CONFIG_ + +#define TEST_RESOURCES_DIR "@TEST_RESOURCES_DIR@" +#endif diff --git a/trunk/fcl/test/env.obj b/trunk/fcl/test/fcl_resources/env.obj similarity index 100% rename from trunk/fcl/test/env.obj rename to trunk/fcl/test/fcl_resources/env.obj diff --git a/trunk/fcl/test/rob.obj b/trunk/fcl/test/fcl_resources/rob.obj similarity index 100% rename from trunk/fcl/test/rob.obj rename to trunk/fcl/test/fcl_resources/rob.obj diff --git a/trunk/fcl/test/test_fcl_broadphase.cpp b/trunk/fcl/test/test_fcl_broadphase.cpp index d4d0155b74836389c5998fde02200f2dc7a7b251..7101b720835bc291a0d57ede0f43f077ae15ca24 100644 --- a/trunk/fcl/test/test_fcl_broadphase.cpp +++ b/trunk/fcl/test/test_fcl_broadphase.cpp @@ -34,11 +34,14 @@ /** \author Jia Pan */ + +#define BOOST_TEST_MODULE "FCL_BROADPHASE" +#include <boost/test/unit_test.hpp> + #include "fcl/broadphase/broadphase.h" #include "fcl/shape/geometric_shape_to_BVH_model.h" #include "fcl/math/transform.h" #include "test_fcl_utility.h" -#include <gtest/gtest.h> #if USE_GOOGLEHASH #include <sparsehash/sparse_hash_map> @@ -47,6 +50,8 @@ #endif #include <boost/math/constants/constants.hpp> +#include <iostream> +#include <iomanip> using namespace fcl; @@ -106,28 +111,28 @@ struct GoogleDenseHashTable : public google::dense_hash_map<U, V, std::tr1::hash #endif /// check the update, only return collision or not -TEST(test_core_bf, broad_phase_update_collision_binary) +BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_update_collision_binary) { broad_phase_update_collision_test(2000, 100, 1000, 1, false); broad_phase_update_collision_test(2000, 1000, 1000, 1, false); } /// check the update, return 10 contacts -TEST(test_core_bf, broad_phase_update_collision) +BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_update_collision) { broad_phase_update_collision_test(2000, 100, 1000, 10, false); broad_phase_update_collision_test(2000, 1000, 1000, 10, false); } /// check the update, exhaustive -TEST(test_core_bf, broad_phase_update_collision_exhaustive) +BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_update_collision_exhaustive) { broad_phase_update_collision_test(2000, 100, 1000, 1, true); broad_phase_update_collision_test(2000, 1000, 1000, 1, true); } /// check broad phase distance -TEST(test_core_bf, broad_phase_distance) +BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_distance) { broad_phase_distance_test(200, 100, 100); broad_phase_distance_test(200, 1000, 100); @@ -136,7 +141,7 @@ TEST(test_core_bf, broad_phase_distance) } /// check broad phase self distance -TEST(test_core_bf, broad_phase_self_distance) +BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_self_distance) { broad_phase_self_distance_test(200, 512); broad_phase_self_distance_test(200, 1000); @@ -144,7 +149,7 @@ TEST(test_core_bf, broad_phase_self_distance) } /// check broad phase collision and self collision, only return collision or not -TEST(test_core_bf, broad_phase_collision_binary) +BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_collision_binary) { broad_phase_collision_test(2000, 100, 1000, 1, false); broad_phase_collision_test(2000, 1000, 1000, 1, false); @@ -153,35 +158,35 @@ TEST(test_core_bf, broad_phase_collision_binary) } /// check broad phase collision and self collision, return 10 contacts -TEST(test_core_bf, broad_phase_collision) +BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_collision) { broad_phase_collision_test(2000, 100, 1000, 10, false); broad_phase_collision_test(2000, 1000, 1000, 10, false); } /// check broad phase update, in mesh, only return collision or not -TEST(test_core_mesh_bf, broad_phase_update_collision_mesh_binary) +BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_update_collision_mesh_binary) { broad_phase_update_collision_test(2000, 100, 1000, false, true); broad_phase_update_collision_test(2000, 1000, 1000, false, true); } /// check broad phase update, in mesh, return 10 contacts -TEST(test_core_mesh_bf, broad_phase_update_collision_mesh) +BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_update_collision_mesh) { broad_phase_update_collision_test(2000, 100, 1000, 10, false, true); broad_phase_update_collision_test(2000, 1000, 1000, 10, false, true); } /// check broad phase update, in mesh, exhaustive -TEST(test_core_mesh_bf, broad_phase_update_collision_mesh_exhaustive) +BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_update_collision_mesh_exhaustive) { broad_phase_update_collision_test(2000, 100, 1000, 1, true, true); broad_phase_update_collision_test(2000, 1000, 1000, 1, true, true); } /// check broad phase distance -TEST(test_core_mesh_bf, broad_phase_distance_mesh) +BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_distance_mesh) { broad_phase_distance_test(200, 100, 100, true); broad_phase_distance_test(200, 1000, 100, true); @@ -190,7 +195,7 @@ TEST(test_core_mesh_bf, broad_phase_distance_mesh) } /// check broad phase self distance -TEST(test_core_mesh_bf, broad_phase_self_distance_mesh) +BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_self_distance_mesh) { broad_phase_self_distance_test(200, 512, true); broad_phase_self_distance_test(200, 1000, true); @@ -198,35 +203,26 @@ TEST(test_core_mesh_bf, broad_phase_self_distance_mesh) } /// check broad phase collision and self collision, return only collision or not, in mesh -TEST(test_core_mesh_bf, broad_phase_collision_mesh_binary) +BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_collision_mesh_binary) { broad_phase_collision_test(2000, 100, 1000, 1, false, true); broad_phase_collision_test(2000, 1000, 1000, 1, false, true); } /// check broad phase collision and self collision, return 10 contacts, in mesh -TEST(test_core_mesh_bf, broad_phase_collision_mesh) +BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_collision_mesh) { broad_phase_collision_test(2000, 100, 1000, 10, false, true); broad_phase_collision_test(2000, 1000, 1000, 10, false, true); } /// check broad phase collision and self collision, exhaustive, in mesh -TEST(test_core_mesh_bf, broad_phase_collision_mesh_exhaustive) +BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_collision_mesh_exhaustive) { broad_phase_collision_test(2000, 100, 1000, 1, true, true); broad_phase_collision_test(2000, 1000, 1000, 1, true, true); } - - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} - - void generateEnvironments(std::vector<CollisionObject*>& env, double env_scale, std::size_t n) { FCL_REAL extents[] = {-env_scale, env_scale, -env_scale, env_scale, -env_scale, env_scale}; @@ -512,7 +508,7 @@ void broad_phase_collision_test(double env_scale, std::size_t env_size, std::siz if(exhaustive) { for(size_t i = 1; i < managers.size(); ++i) - ASSERT_TRUE(self_data[i].result.numContacts() == self_data[0].result.numContacts()); + BOOST_CHECK(self_data[i].result.numContacts() == self_data[0].result.numContacts()); } else { @@ -521,10 +517,10 @@ void broad_phase_collision_test(double env_scale, std::size_t env_size, std::siz self_res[i] = (self_data[i].result.numContacts() > 0); for(size_t i = 1; i < self_res.size(); ++i) - ASSERT_TRUE(self_res[0] == self_res[i]); + BOOST_CHECK(self_res[0] == self_res[i]); for(size_t i = 1; i < managers.size(); ++i) - ASSERT_TRUE(self_data[i].result.numContacts() == self_data[0].result.numContacts()); + BOOST_CHECK(self_data[i].result.numContacts() == self_data[0].result.numContacts()); } @@ -553,7 +549,7 @@ void broad_phase_collision_test(double env_scale, std::size_t env_size, std::siz if(exhaustive) { for(size_t j = 1; j < managers.size(); ++j) - ASSERT_TRUE(query_data[j].result.numContacts() == query_data[0].result.numContacts()); + BOOST_CHECK(query_data[j].result.numContacts() == query_data[0].result.numContacts()); } else { @@ -561,10 +557,10 @@ void broad_phase_collision_test(double env_scale, std::size_t env_size, std::siz for(size_t j = 0; j < query_res.size(); ++j) query_res[j] = (query_data[j].result.numContacts() > 0); for(size_t j = 1; j < query_res.size(); ++j) - ASSERT_TRUE(query_res[0] == query_res[j]); + BOOST_CHECK(query_res[0] == query_res[j]); for(size_t j = 1; j < managers.size(); ++j) - ASSERT_TRUE(query_data[j].result.numContacts() == query_data[0].result.numContacts()); + BOOST_CHECK(query_data[j].result.numContacts() == query_data[0].result.numContacts()); } } @@ -690,7 +686,7 @@ void broad_phase_self_distance_test(double env_scale, std::size_t env_size, bool // std::cout << std::endl; for(size_t i = 1; i < managers.size(); ++i) - ASSERT_TRUE(fabs(self_data[0].result.min_distance - self_data[i].result.min_distance) < DELTA || + BOOST_CHECK(fabs(self_data[0].result.min_distance - self_data[i].result.min_distance) < DELTA || fabs(self_data[0].result.min_distance - self_data[i].result.min_distance) / fabs(self_data[0].result.min_distance) < DELTA); for(size_t i = 0; i < env.size(); ++i) @@ -834,7 +830,7 @@ void broad_phase_distance_test(double env_scale, std::size_t env_size, std::size // std::cout << std::endl; for(size_t j = 1; j < managers.size(); ++j) - ASSERT_TRUE(fabs(query_data[0].result.min_distance - query_data[j].result.min_distance) < DELTA || + BOOST_CHECK(fabs(query_data[0].result.min_distance - query_data[j].result.min_distance) < DELTA || fabs(query_data[0].result.min_distance - query_data[j].result.min_distance) / fabs(query_data[0].result.min_distance) < DELTA); } @@ -1008,7 +1004,7 @@ void broad_phase_update_collision_test(double env_scale, std::size_t env_size, s if(exhaustive) { for(size_t i = 1; i < managers.size(); ++i) - ASSERT_TRUE(self_data[i].result.numContacts() == self_data[0].result.numContacts()); + BOOST_CHECK(self_data[i].result.numContacts() == self_data[0].result.numContacts()); } else { @@ -1017,10 +1013,10 @@ void broad_phase_update_collision_test(double env_scale, std::size_t env_size, s self_res[i] = (self_data[i].result.numContacts() > 0); for(size_t i = 1; i < self_res.size(); ++i) - ASSERT_TRUE(self_res[0] == self_res[i]); + BOOST_CHECK(self_res[0] == self_res[i]); for(size_t i = 1; i < managers.size(); ++i) - ASSERT_TRUE(self_data[i].result.numContacts() == self_data[0].result.numContacts()); + BOOST_CHECK(self_data[i].result.numContacts() == self_data[0].result.numContacts()); } @@ -1049,7 +1045,7 @@ void broad_phase_update_collision_test(double env_scale, std::size_t env_size, s if(exhaustive) { for(size_t j = 1; j < managers.size(); ++j) - ASSERT_TRUE(query_data[j].result.numContacts() == query_data[0].result.numContacts()); + BOOST_CHECK(query_data[j].result.numContacts() == query_data[0].result.numContacts()); } else { @@ -1057,10 +1053,10 @@ void broad_phase_update_collision_test(double env_scale, std::size_t env_size, s for(size_t j = 0; j < query_res.size(); ++j) query_res[j] = (query_data[j].result.numContacts() > 0); for(size_t j = 1; j < query_res.size(); ++j) - ASSERT_TRUE(query_res[0] == query_res[j]); + BOOST_CHECK(query_res[0] == query_res[j]); for(size_t j = 1; j < managers.size(); ++j) - ASSERT_TRUE(query_data[j].result.numContacts() == query_data[0].result.numContacts()); + BOOST_CHECK(query_data[j].result.numContacts() == query_data[0].result.numContacts()); } } diff --git a/trunk/fcl/test/test_fcl_collision.cpp b/trunk/fcl/test/test_fcl_collision.cpp index 5456cfb03432ba7b57ffd117cee166c36797fc1c..d69b93ea71408c0de5dc785ce127a40020c5f471 100644 --- a/trunk/fcl/test/test_fcl_collision.cpp +++ b/trunk/fcl/test/test_fcl_collision.cpp @@ -34,6 +34,9 @@ /** \author Jia Pan */ +#define BOOST_TEST_MODULE "FCL_COLLISION" +#include <boost/test/unit_test.hpp> + #include "fcl/traversal/traversal_node_bvhs.h" #include "fcl/traversal/traversal_node_setup.h" #include "fcl/collision_node.h" @@ -42,8 +45,8 @@ #include "fcl/shape/geometric_shapes.h" #include "fcl/narrowphase/narrowphase.h" #include "test_fcl_utility.h" -#include <gtest/gtest.h> - +#include "fcl_resources/config.h" +#include <boost/filesystem.hpp> using namespace fcl; @@ -74,7 +77,7 @@ bool enable_contact = true; std::vector<Contact> global_pairs; std::vector<Contact> global_pairs_now; -TEST(OBB_test, OBB_Box_test) +BOOST_AUTO_TEST_CASE(OBB_Box_test) { FCL_REAL r_extents[] = {-1000, -1000, -1000, 1000, 1000, 1000}; std::vector<Transform3f> rotate_transform; @@ -114,11 +117,11 @@ TEST(OBB_test, OBB_Box_test) bool overlap_obb = obb1.overlap(obb2); bool overlap_box = solver.shapeIntersect(box1, box1_tf, box2, box2_tf, NULL, NULL, NULL); - ASSERT_TRUE(overlap_obb == overlap_box); + BOOST_CHECK(overlap_obb == overlap_box); } } -TEST(OBB_test, OBB_shape_test) +BOOST_AUTO_TEST_CASE(OBB_shape_test) { FCL_REAL r_extents[] = {-1000, -1000, -1000, 1000, 1000, 1000}; std::vector<Transform3f> rotate_transform; @@ -152,7 +155,7 @@ TEST(OBB_test, OBB_shape_test) bool overlap_obb = obb1.overlap(obb2); bool overlap_sphere = solver.shapeIntersect(box1, box1_tf, sphere, transforms[i], NULL, NULL, NULL); - ASSERT_TRUE(overlap_obb >= overlap_sphere); + BOOST_CHECK(overlap_obb >= overlap_sphere); } { @@ -161,7 +164,7 @@ TEST(OBB_test, OBB_shape_test) bool overlap_obb = obb1.overlap(obb2); bool overlap_capsule = solver.shapeIntersect(box1, box1_tf, capsule, transforms[i], NULL, NULL, NULL); - ASSERT_TRUE(overlap_obb >= overlap_capsule); + BOOST_CHECK(overlap_obb >= overlap_capsule); } { @@ -170,7 +173,7 @@ TEST(OBB_test, OBB_shape_test) bool overlap_obb = obb1.overlap(obb2); bool overlap_cone = solver.shapeIntersect(box1, box1_tf, cone, transforms[i], NULL, NULL, NULL); - ASSERT_TRUE(overlap_obb >= overlap_cone); + BOOST_CHECK(overlap_obb >= overlap_cone); } { @@ -179,12 +182,12 @@ TEST(OBB_test, OBB_shape_test) bool overlap_obb = obb1.overlap(obb2); bool overlap_cylinder = solver.shapeIntersect(box1, box1_tf, cylinder, transforms[i], NULL, NULL, NULL); - ASSERT_TRUE(overlap_obb >= overlap_cylinder); + BOOST_CHECK(overlap_obb >= overlap_cylinder); } } } -TEST(OBB_test, OBB_AABB_test) +BOOST_AUTO_TEST_CASE(OBB_AABB_test) { FCL_REAL extents[] = {-1000, -1000, -1000, 1000, 1000, 1000}; std::size_t n = 1000; @@ -220,17 +223,19 @@ TEST(OBB_test, OBB_AABB_test) std::cout << obb2.To << " " << obb2.extent << " " << obb2.axis[0] << " " << obb2.axis[1] << " " << obb2.axis[2] << std::endl; } - ASSERT_TRUE(overlap_aabb == overlap_obb); + BOOST_CHECK(overlap_aabb == overlap_obb); } std::cout << std::endl; } -TEST(collision_test, mesh_mesh) +BOOST_AUTO_TEST_CASE(mesh_mesh) { std::vector<Vec3f> p1, p2; std::vector<Triangle> t1, t2; - loadOBJFile("../test/env.obj", p1, t1); - loadOBJFile("../test/rob.obj", p2, t2); + boost::filesystem::path path(TEST_RESOURCES_DIR); + + loadOBJFile((path / "env.obj").string().c_str(), p1, t1); + loadOBJFile((path / "rob.obj").string().c_str(), p2, t2); std::vector<Transform3f> transforms; FCL_REAL extents[] = {-3000, -3000, 0, 3000, 3000, 3000}; @@ -248,560 +253,554 @@ TEST(collision_test, mesh_mesh) collide_Test<OBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); collide_Test<OBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<OBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<AABB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<AABB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<AABB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<KDOP<24> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<KDOP<24> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<KDOP<24> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<KDOP<18> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<KDOP<18> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<KDOP<18> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<KDOP<16> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<KDOP<16> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<KDOP<16> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<OBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<OBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<OBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<AABB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<AABB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<AABB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<KDOP<24> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<KDOP<24> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<KDOP<24> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<KDOP<18> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<KDOP<18> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<KDOP<18> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<KDOP<16> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<KDOP<16> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<KDOP<16> >(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test_Oriented<OBB, MeshCollisionTraversalNodeOBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test_Oriented<OBB, MeshCollisionTraversalNodeOBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test_Oriented<OBB, MeshCollisionTraversalNodeOBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test_Oriented<RSS, MeshCollisionTraversalNodeRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test_Oriented<RSS, MeshCollisionTraversalNodeRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test_Oriented<RSS, MeshCollisionTraversalNodeRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } test_collide_func<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } test_collide_func<OBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } test_collide_func<AABB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test_Oriented<kIOS, MeshCollisionTraversalNodekIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test_Oriented<kIOS, MeshCollisionTraversalNodekIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test_Oriented<kIOS, MeshCollisionTraversalNodekIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } test_collide_func<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } test_collide_func<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } test_collide_func<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test2<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test_Oriented<OBBRSS, MeshCollisionTraversalNodeOBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test_Oriented<OBBRSS, MeshCollisionTraversalNodeOBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } collide_Test_Oriented<OBBRSS, MeshCollisionTraversalNodeOBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } test_collide_func<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } test_collide_func<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } test_collide_func<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER); - ASSERT_TRUE(global_pairs.size() == global_pairs_now.size()); + BOOST_CHECK(global_pairs.size() == global_pairs_now.size()); for(std::size_t j = 0; j < global_pairs.size(); ++j) { - ASSERT_TRUE(global_pairs[j].b1 == global_pairs_now[j].b1); - ASSERT_TRUE(global_pairs[j].b2 == global_pairs_now[j].b2); + BOOST_CHECK(global_pairs[j].b1 == global_pairs_now[j].b1); + BOOST_CHECK(global_pairs[j].b2 == global_pairs_now[j].b2); } } } -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} - template<typename BV> bool collide_Test2(const Transform3f& tf, diff --git a/trunk/fcl/test/test_fcl_distance.cpp b/trunk/fcl/test/test_fcl_distance.cpp index 295412fb9819f13d5cc07771c29e92b85177c33c..8689b8802cd0e1d795336a26df46123193bd1e53 100644 --- a/trunk/fcl/test/test_fcl_distance.cpp +++ b/trunk/fcl/test/test_fcl_distance.cpp @@ -34,12 +34,16 @@ /** \author Jia Pan */ +#define BOOST_TEST_MODULE "FCL_DISTANCE" +#include <boost/test/unit_test.hpp> + #include "fcl/traversal/traversal_node_bvhs.h" #include "fcl/traversal/traversal_node_setup.h" #include "fcl/collision_node.h" #include "test_fcl_utility.h" -#include <gtest/gtest.h> #include <boost/timer.hpp> +#include "fcl_resources/config.h" +#include <boost/filesystem.hpp> using namespace fcl; @@ -77,12 +81,13 @@ inline bool nearlyEqual(const Vec3f& a, const Vec3f& b) } -TEST(collision_core, mesh_distance) +BOOST_AUTO_TEST_CASE(mesh_distance) { std::vector<Vec3f> p1, p2; std::vector<Triangle> t1, t2; - loadOBJFile("../test/env.obj", p1, t1); - loadOBJFile("../test/rob.obj", p2, t2); + boost::filesystem::path path(TEST_RESOURCES_DIR); + loadOBJFile((path / "env.obj").string().c_str(), p1, t1); + loadOBJFile((path / "rob.obj").string().c_str(), p2, t2); std::vector<Transform3f> transforms; // t0 FCL_REAL extents[] = {-3000, -3000, 0, 3000, 3000, 3000}; @@ -106,181 +111,181 @@ TEST(collision_core, mesh_distance) distance_Test_Oriented<RSS, MeshDistanceTraversalNodeRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<RSS, MeshDistanceTraversalNodeRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<RSS, MeshDistanceTraversalNodeRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<RSS, MeshDistanceTraversalNodeRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<RSS, MeshDistanceTraversalNodeRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<kIOS, MeshDistanceTraversalNodekIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<kIOS, MeshDistanceTraversalNodekIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<kIOS, MeshDistanceTraversalNodekIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<kIOS, MeshDistanceTraversalNodekIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<kIOS, MeshDistanceTraversalNodekIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<kIOS, MeshDistanceTraversalNodekIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<OBBRSS, MeshDistanceTraversalNodeOBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<OBBRSS, MeshDistanceTraversalNodeOBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<OBBRSS, MeshDistanceTraversalNodeOBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<OBBRSS, MeshDistanceTraversalNodeOBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<OBBRSS, MeshDistanceTraversalNodeOBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test_Oriented<OBBRSS, MeshDistanceTraversalNodeOBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 2, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); distance_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 20, res_now, verbose); - ASSERT_TRUE(fabs(res.distance - res_now.distance) < DELTA); - ASSERT_TRUE(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); + BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA); + BOOST_CHECK(fabs(res.distance) < DELTA || (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) && nearlyEqual(res.p2, res_now.p2))); } @@ -288,14 +293,6 @@ TEST(collision_core, mesh_distance) std::cout << "collision timing: " << col_time << " sec" << std::endl; } - -int main(int argc, char **argv) -{ - srand(time(NULL)); - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} - template<typename BV, typename TraversalNode> void distance_Test_Oriented(const Transform3f& tf, const std::vector<Vec3f>& vertices1, const std::vector<Triangle>& triangles1, diff --git a/trunk/fcl/test/test_fcl_frontlist.cpp b/trunk/fcl/test/test_fcl_frontlist.cpp index aaf7dccd499762b83b6c1722d967ce1f22809174..94f0a149a248cbdc0571e2f862a3c070ef164f58 100644 --- a/trunk/fcl/test/test_fcl_frontlist.cpp +++ b/trunk/fcl/test/test_fcl_frontlist.cpp @@ -34,11 +34,17 @@ /** \author Jia Pan */ + +#define BOOST_TEST_MODULE "FCL_FRONT_LIST" +#include <boost/test/unit_test.hpp> + #include "fcl/traversal/traversal_node_bvhs.h" #include "fcl/traversal/traversal_node_setup.h" #include "fcl/collision_node.h" #include "test_fcl_utility.h" -#include <gtest/gtest.h> + +#include "fcl_resources/config.h" +#include <boost/filesystem.hpp> using namespace fcl; @@ -62,12 +68,13 @@ bool collide_Test(const Transform3f& tf, const std::vector<Vec3f>& vertices2, const std::vector<Triangle>& triangles2, SplitMethodType split_method, bool verbose); // TODO: randomly still have some runtime error -TEST(collision_test, front_list) +BOOST_AUTO_TEST_CASE(front_list) { std::vector<Vec3f> p1, p2; std::vector<Triangle> t1, t2; - loadOBJFile("../test/env.obj", p1, t1); - loadOBJFile("../test/rob.obj", p2, t2); + boost::filesystem::path path(TEST_RESOURCES_DIR); + loadOBJFile((path / "env.obj").string().c_str(), p1, t1); + loadOBJFile((path / "rob.obj").string().c_str(), p2, t2); std::vector<Transform3f> transforms; // t0 std::vector<Transform3f> transforms2; // t1 @@ -84,116 +91,108 @@ TEST(collision_test, front_list) { res = collide_Test<AABB>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); res2 = collide_front_list_Test<AABB>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<AABB>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); res2 = collide_front_list_Test<AABB>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<AABB>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); res2 = collide_front_list_Test<AABB>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); } for(std::size_t i = 0; i < transforms.size(); ++i) { res = collide_Test<OBB>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); res2 = collide_front_list_Test<OBB>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<OBB>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); res2 = collide_front_list_Test<OBB>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<OBB>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); res2 = collide_front_list_Test<OBB>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); } for(std::size_t i = 0; i < transforms.size(); ++i) { res = collide_Test<RSS>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); res2 = collide_front_list_Test<RSS>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<RSS>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); res2 = collide_front_list_Test<RSS>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<RSS>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); res2 = collide_front_list_Test<RSS>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); } for(std::size_t i = 0; i < transforms.size(); ++i) { res = collide_Test<KDOP<16> >(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); res2 = collide_front_list_Test<KDOP<16> >(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<KDOP<16> >(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); res2 = collide_front_list_Test<KDOP<16> >(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<KDOP<16> >(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); res2 = collide_front_list_Test<KDOP<16> >(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); } for(std::size_t i = 0; i < transforms.size(); ++i) { res = collide_Test<KDOP<18> >(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); res2 = collide_front_list_Test<KDOP<18> >(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<KDOP<18> >(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); res2 = collide_front_list_Test<KDOP<18> >(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<KDOP<18> >(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); res2 = collide_front_list_Test<KDOP<18> >(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); } for(std::size_t i = 0; i < transforms.size(); ++i) { res = collide_Test<KDOP<24> >(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); res2 = collide_front_list_Test<KDOP<24> >(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<KDOP<24> >(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); res2 = collide_front_list_Test<KDOP<24> >(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<KDOP<24> >(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); res2 = collide_front_list_Test<KDOP<24> >(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, false, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); } for(std::size_t i = 0; i < transforms.size(); ++i) { res = collide_Test<RSS>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); res2 = collide_front_list_Test_Oriented<RSS, MeshCollisionTraversalNodeRSS>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<RSS>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); res2 = collide_front_list_Test_Oriented<RSS, MeshCollisionTraversalNodeRSS>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<RSS>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); res2 = collide_front_list_Test_Oriented<RSS, MeshCollisionTraversalNodeRSS>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); } for(std::size_t i = 0; i < transforms.size(); ++i) { res = collide_Test<OBB>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); res2 = collide_front_list_Test_Oriented<OBB, MeshCollisionTraversalNodeOBB>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<OBB>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); res2 = collide_front_list_Test_Oriented<OBB, MeshCollisionTraversalNodeOBB>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); res = collide_Test<OBB>(transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); res2 = collide_front_list_Test_Oriented<OBB, MeshCollisionTraversalNodeOBB>(transforms[i], transforms2[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, verbose); - ASSERT_TRUE(res == res2); + BOOST_CHECK(res == res2); } } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} - - template<typename BV> bool collide_front_list_Test(const Transform3f& tf1, const Transform3f& tf2, const std::vector<Vec3f>& vertices1, const std::vector<Triangle>& triangles1, diff --git a/trunk/fcl/test/test_fcl_geometric_shapes.cpp b/trunk/fcl/test/test_fcl_geometric_shapes.cpp index ee198da8b6b1837e678df2787dcdd69fdd08413f..1dc40c98d21ec656e673e72b631c2eba2e80fdc7 100644 --- a/trunk/fcl/test/test_fcl_geometric_shapes.cpp +++ b/trunk/fcl/test/test_fcl_geometric_shapes.cpp @@ -34,6 +34,10 @@ /** \author Jia Pan */ + +#define BOOST_TEST_MODULE "FCL_GEOMETRIC_SHAPES" +#include <boost/test/unit_test.hpp> + #include "fcl/narrowphase/narrowphase.h" #include "fcl/collision.h" #include "test_fcl_utility.h" @@ -47,7 +51,9 @@ FCL_REAL extents [6] = {0, 0, 0, 10, 10, 10}; GJKSolver_libccd solver1; GJKSolver_indep solver2; -TEST(shapeIntersection, spheresphere) +#define BOOST_CHECK_FALSE(p) BOOST_CHECK(!(p)) + +BOOST_AUTO_TEST_CASE(shapeIntersection_spheresphere) { Sphere s1(20); Sphere s2(10); @@ -61,79 +67,79 @@ TEST(shapeIntersection, spheresphere) bool res; res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(40, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(40, 0, 0)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(40, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(40, 0, 0)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(30, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(30, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(30.01, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(30.01, 0, 0)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(29.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(29.9, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(29.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(29.9, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(-29.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(-29.9, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(-29.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(-29.9, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(-30, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(-30, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(-30.01, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(-30.01, 0, 0)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(shapeIntersection, boxbox) +BOOST_AUTO_TEST_CASE(shapeIntersection_boxbox) { Box s1(20, 40, 50); Box s2(10, 10, 10); @@ -148,45 +154,45 @@ TEST(shapeIntersection, boxbox) bool res; res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(15, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(15, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(15.01, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(15.01, 0, 0)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); Quaternion3f q; q.fromAxisAngle(Vec3f(0, 0, 1), (FCL_REAL)3.140 / 6); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(q), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(q), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(q), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(q), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); } -TEST(shapeIntersection, spherebox) +BOOST_AUTO_TEST_CASE(shapeIntersection_spherebox) { Sphere s1(20); Box s2(5, 5, 5); @@ -201,44 +207,44 @@ TEST(shapeIntersection, spherebox) bool res; res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(22.5, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(22.5, 0, 0)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(22.501, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(22.501, 0, 0)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(22.4, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(22.4, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(22.4, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(22.4, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); } -TEST(shapeIntersection, cylindercylinder) +BOOST_AUTO_TEST_CASE(shapeIntersection_cylindercylinder) { Cylinder s1(5, 10); Cylinder s2(5, 10); @@ -253,43 +259,43 @@ TEST(shapeIntersection, cylindercylinder) bool res; res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(9.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(9.9, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(9.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(9.9, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(10, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(10, 0, 0)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(10.01, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(10.01, 0, 0)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(shapeIntersection, conecone) +BOOST_AUTO_TEST_CASE(shapeIntersection_conecone) { Cone s1(5, 10); Cone s2(5, 10); @@ -304,55 +310,55 @@ TEST(shapeIntersection, conecone) bool res; res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(9.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(9.9, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(9.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(9.9, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(10.001, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(10.001, 0, 0)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(10.001, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(10.001, 0, 0)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(0, 0, 9.9)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(0, 0, 9.9)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(0, 0, 9.9)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(0, 0, 9.9)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); } -TEST(shapeIntersection, conecylinder) +BOOST_AUTO_TEST_CASE(shapeIntersection_conecylinder) { Cylinder s1(5, 10); Cone s2(5, 10); @@ -367,67 +373,67 @@ TEST(shapeIntersection, conecylinder) bool res; res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(9.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(9.9, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(9.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(9.9, 0, 0)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(10.01, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(10, 0, 0)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(10.01, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(10.01, 0, 0)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(0, 0, 9.9)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(0, 0, 9.9)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(0, 0, 9.9)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(0, 0, 9.9)), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(0, 0, 10.01)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(0, 0, 10)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(0, 0, 10.01)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(0, 0, 10.01)), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(shapeIntersection, spheretriangle) +BOOST_AUTO_TEST_CASE(shapeIntersection_spheretriangle) { Sphere s(10); Vec3f t[3]; @@ -442,23 +448,23 @@ TEST(shapeIntersection, spheretriangle) bool res; res = solver1.shapeTriangleIntersect(s, Transform3f(), t[0], t[1], t[2], NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeTriangleIntersect(s, transform, t[0], t[1], t[2], transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); t[0].setValue(30, 0, 0); t[1].setValue(9.9, -20, 0); t[2].setValue(9.9, 20, 0); res = solver1.shapeTriangleIntersect(s, Transform3f(), t[0], t[1], t[2], NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver1.shapeTriangleIntersect(s, transform, t[0], t[1], t[2], transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); } -TEST(shapeIntersection, halfspacesphere) +BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacesphere) { Sphere s(10); Halfspace hs(Vec3f(1, 0, 0), 0); @@ -472,61 +478,61 @@ TEST(shapeIntersection, halfspacesphere) bool res; res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-5, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-5, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-5, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-5, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 15) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-2.5, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 15) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-2.5, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 15) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-2.5, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 15) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-2.5, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-7.5, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-7.5, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-7.5, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-7.5, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-10.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-10.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(10.1, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 20.1) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0.05, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 20.1) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(0.05, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(10.1, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 20.1) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0.05, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 20.1) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0.05, 0, 0)))); } -TEST(shapeIntersection, planesphere) +BOOST_AUTO_TEST_CASE(shapeIntersection_planesphere) { Sphere s(10); Plane hs(Vec3f(1, 0, 0), 0); @@ -540,56 +546,56 @@ TEST(shapeIntersection, planesphere) bool res; res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0)) || normal.equal(Vec3f(1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0)) || normal.equal(Vec3f(1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(5, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(5, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(5, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(5, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-5, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-5, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-5, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-5, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-10.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-10.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(10.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(10.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(shapeIntersection, halfspacebox) +BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacebox) { Box s(5, 10, 20); Halfspace hs(Vec3f(1, 0, 0), 0); @@ -603,64 +609,64 @@ TEST(shapeIntersection, halfspacebox) bool res; res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-1.25, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-1.25, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-1.25, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-1.25, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(1.25, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 3.75) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-0.625, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 3.75) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-0.625, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(1.25, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 3.75) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-0.625, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 3.75) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-0.625, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-1.25, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 1.25) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-1.875, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 1.25) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-1.875, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-1.25, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 1.25) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-1.875, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 1.25) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-1.875, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(2.51, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5.01) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0.005, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5.01) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(0.005, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(2.51, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5.01) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0.005, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5.01) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0.005, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-2.51, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-2.51, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, Transform3f(transform.getQuatRotation()), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); } -TEST(shapeIntersection, planebox) +BOOST_AUTO_TEST_CASE(shapeIntersection_planebox) { Box s(5, 10, 20); Plane hs(Vec3f(1, 0, 0), 0); @@ -674,58 +680,58 @@ TEST(shapeIntersection, planebox) bool res; res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0)) || normal.equal(Vec3f(1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0)) || normal.equal(Vec3f(1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(1.25, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 1.25) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(1.25, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 1.25) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(1.25, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(1.25, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 1.25) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(1.25, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 1.25) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(1.25, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-1.25, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 1.25) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-1.25, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 1.25) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-1.25, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-1.25, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 1.25) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-1.25, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 1.25) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-1.25, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(2.51, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(2.51, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-2.51, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-2.51, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, Transform3f(transform.getQuatRotation()), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); } -TEST(shapeIntersection, halfspacecapsule) +BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacecapsule) { Capsule s(5, 10); Halfspace hs(Vec3f(1, 0, 0), 0); @@ -739,58 +745,58 @@ TEST(shapeIntersection, halfspacecapsule) bool res; res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-2.5, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-2.5, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-2.5, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-2.5, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-1.25, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-1.25, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-1.25, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-1.25, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-3.75, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-3.75, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-3.75, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-3.75, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0.05, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(0.05, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0.05, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0.05, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); @@ -798,58 +804,58 @@ TEST(shapeIntersection, halfspacecapsule) hs = Halfspace(Vec3f(0, 1, 0), 0); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, -2.5, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, -2.5, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, -2.5, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, -2.5, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, -1.25, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, -1.25, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, -1.25, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, -1.25, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, -2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, -3.75, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, -3.75, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, -2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, -3.75, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, -3.75, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 5.1, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0.05, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, 0.05, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 5.1, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0.05, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0.05, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, -5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, -5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); @@ -857,61 +863,61 @@ TEST(shapeIntersection, halfspacecapsule) hs = Halfspace(Vec3f(0, 0, 1), 0); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, -5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, -5))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, -5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, -5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, 2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 12.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, -3.75))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 12.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, -3.75))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, 2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 12.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, -3.75)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 12.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, -3.75)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, -2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, -6.25))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, -6.25))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, -2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, -6.25)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, -6.25)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, 10.1)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 20.1) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 0.05))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 20.1) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 0.05))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, 10.1)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 20.1) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 0.05)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 20.1) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 0.05)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, -10.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, -10.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(shapeIntersection, planecapsule) +BOOST_AUTO_TEST_CASE(shapeIntersection_planecapsule) { Capsule s(5, 10); Plane hs(Vec3f(1, 0, 0), 0); @@ -925,52 +931,52 @@ TEST(shapeIntersection, planecapsule) bool res; res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0)) || normal.equal(Vec3f(1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0)) || normal.equal(Vec3f(1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(2.5, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(2.5, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(2.5, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(2.5, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-2.5, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-2.5, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-2.5, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-2.5, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); @@ -978,52 +984,52 @@ TEST(shapeIntersection, planecapsule) hs = Plane(Vec3f(0, 1, 0), 0); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0)) || normal.equal(Vec3f(0, 1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0)) || normal.equal(Vec3f(0, 1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(0, 1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(0, 1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, 2.5, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, 2.5, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 2.5, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 2.5, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, -2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, -2.5, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, -2.5, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, -2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, -2.5, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, -2.5, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, -5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, -5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); @@ -1031,55 +1037,55 @@ TEST(shapeIntersection, planecapsule) hs = Plane(Vec3f(0, 0, 1), 0); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1)) || normal.equal(Vec3f(0, 0, 1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1)) || normal.equal(Vec3f(0, 0, 1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1))) || normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, 1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1))) || normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, 1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, 2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, 1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 2.5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, 1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 2.5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, 2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, 1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 2.5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, 1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 2.5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, -2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, -2.5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, -2.5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, -2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, -2.5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, -2.5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, 10.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, 10.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, -10.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, -10.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(shapeIntersection, halfspacecylinder) +BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacecylinder) { Cylinder s(5, 10); Halfspace hs(Vec3f(1, 0, 0), 0); @@ -1093,58 +1099,58 @@ TEST(shapeIntersection, halfspacecylinder) bool res; res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-2.5, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-2.5, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-2.5, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-2.5, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-1.25, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-1.25, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-1.25, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-1.25, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-3.75, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-3.75, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-3.75, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-3.75, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0.05, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(0.05, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0.05, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0.05, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); @@ -1152,58 +1158,58 @@ TEST(shapeIntersection, halfspacecylinder) hs = Halfspace(Vec3f(0, 1, 0), 0); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, -2.5, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, -2.5, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, -2.5, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, -2.5, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, -1.25, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, -1.25, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, -1.25, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, -1.25, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, -2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, -3.75, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, -3.75, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, -2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, -3.75, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, -3.75, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 5.1, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0.05, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, 0.05, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 5.1, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0.05, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0.05, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, -5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, -5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); @@ -1211,61 +1217,61 @@ TEST(shapeIntersection, halfspacecylinder) hs = Halfspace(Vec3f(0, 0, 1), 0); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, -2.5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, -2.5))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, -2.5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, -2.5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, 2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, -1.25))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, -1.25))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, 2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, -1.25)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, -1.25)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, -2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, -3.75))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, -3.75))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, -2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, -3.75)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, -3.75)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, 5.1)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 0.05))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 0.05))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, 5.1)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 0.05)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 0.05)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, -5.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, -5.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(shapeIntersection, planecylinder) +BOOST_AUTO_TEST_CASE(shapeIntersection_planecylinder) { Cylinder s(5, 10); Plane hs(Vec3f(1, 0, 0), 0); @@ -1279,52 +1285,52 @@ TEST(shapeIntersection, planecylinder) bool res; res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0)) || normal.equal(Vec3f(1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0)) || normal.equal(Vec3f(1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(2.5, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(2.5, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(2.5, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(2.5, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-2.5, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-2.5, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-2.5, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-2.5, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); @@ -1332,52 +1338,52 @@ TEST(shapeIntersection, planecylinder) hs = Plane(Vec3f(0, 1, 0), 0); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0)) || normal.equal(Vec3f(0, 1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0)) || normal.equal(Vec3f(0, 1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(0, 1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(0, 1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, 2.5, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, 2.5, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 2.5, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 2.5, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, -2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, -2.5, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, -2.5, 0))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, -2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, -2.5, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, -2.5, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, -5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, -5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); @@ -1385,56 +1391,56 @@ TEST(shapeIntersection, planecylinder) hs = Plane(Vec3f(0, 0, 1), 0); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1)) || normal.equal(Vec3f(0, 0, 1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1)) || normal.equal(Vec3f(0, 0, 1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1))) || normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, 1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1))) || normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, 1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, 2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, 1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 2.5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, 1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 2.5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, 2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, 1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 2.5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, 1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 2.5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, -2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, -2.5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, -2.5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, -2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, -2.5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, -2.5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, 10.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, 10.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, -10.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, -10.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(shapeIntersection, halfspacecone) +BOOST_AUTO_TEST_CASE(shapeIntersection_halfspacecone) { Cone s(5, 10); Halfspace hs(Vec3f(1, 0, 0), 0); @@ -1448,58 +1454,58 @@ TEST(shapeIntersection, halfspacecone) bool res; res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-2.5, 0, -5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-2.5, 0, -5))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-2.5, 0, -5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-2.5, 0, -5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-1.25, 0, -5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-1.25, 0, -5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-1.25, 0, -5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-1.25, 0, -5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-3.75, 0, -5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-3.75, 0, -5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-3.75, 0, -5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-3.75, 0, -5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0.05, 0, -5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(0.05, 0, -5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0.05, 0, -5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0.05, 0, -5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); @@ -1507,58 +1513,58 @@ TEST(shapeIntersection, halfspacecone) hs = Halfspace(Vec3f(0, 1, 0), 0); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, -2.5, -5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, -2.5, -5))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, -2.5, -5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, -2.5, -5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, -1.25, -5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, -1.25, -5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, -1.25, -5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, -1.25, -5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, -2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, -3.75, -5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, -3.75, -5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, -2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, -3.75, -5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, -3.75, -5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 5.1, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0.05, -5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, 0.05, -5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 5.1, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0.05, -5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0.05, -5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, -5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, -5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); @@ -1566,61 +1572,61 @@ TEST(shapeIntersection, halfspacecone) hs = Halfspace(Vec3f(0, 0, 1), 0); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, -2.5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, -2.5))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, -2.5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, -2.5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, 2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, -1.25))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, -1.25))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, 2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 7.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, -1.25)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 7.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, -1.25)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, -2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, -3.75))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, -3.75))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, -2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, -3.75)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, -3.75)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, 5.1)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 0.05))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 0.05))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, 5.1)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 10.1) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 0.05)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 10.1) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 0.05)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, -5.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, -5.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(shapeIntersection, planecone) +BOOST_AUTO_TEST_CASE(shapeIntersection_planecone) { Cone s(5, 10); Plane hs(Vec3f(1, 0, 0), 0); @@ -1634,52 +1640,52 @@ TEST(shapeIntersection, planecone) bool res; res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0)) || normal.equal(Vec3f(1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0)) || normal.equal(Vec3f(1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(2.5, 0, -2.5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(2.5, 0, -2.5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(2.5, 0, -2.5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(2.5, 0, -2.5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(-1, 0, 0))); - ASSERT_TRUE(contact.equal(Vec3f(-2.5, 0, -2.5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(-1, 0, 0))); + BOOST_CHECK(contact.equal(Vec3f(-2.5, 0, -2.5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-2.5, 0, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(-2.5, 0, -2.5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(-1, 0, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(-2.5, 0, -2.5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(-5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(-5.1, 0, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); @@ -1687,52 +1693,52 @@ TEST(shapeIntersection, planecone) hs = Plane(Vec3f(0, 1, 0), 0); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0)) || normal.equal(Vec3f(0, 1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0)) || normal.equal(Vec3f(0, 1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(0, 1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0))) || normal.equal(transform.getQuatRotation().transform(Vec3f(0, 1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, 2.5, -2.5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, 2.5, -2.5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 2.5, -2.5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 2.5, -2.5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, -2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, -1, 0))); - ASSERT_TRUE(contact.equal(Vec3f(0, -2.5, -2.5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, -1, 0))); + BOOST_CHECK(contact.equal(Vec3f(0, -2.5, -2.5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, -2.5, 0)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, -2.5, -2.5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, -1, 0)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, -2.5, -2.5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, -5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, -5.1, 0)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); @@ -1740,57 +1746,57 @@ TEST(shapeIntersection, planecone) hs = Plane(Vec3f(0, 0, 1), 0); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1)) || normal.equal(Vec3f(0, 0, 1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 0))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1)) || normal.equal(Vec3f(0, 0, 1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 0))); res = solver1.shapeIntersect(s, transform, hs, transform, &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1))) || normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, 1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 0)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1))) || normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, 1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 0)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, 2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, 1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, 2.5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, 1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, 2.5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, 2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, 1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, 2.5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, 1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, 2.5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, -2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(Vec3f(0, 0, -1))); - ASSERT_TRUE(contact.equal(Vec3f(0, 0, -2.5))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(Vec3f(0, 0, -1))); + BOOST_CHECK(contact.equal(Vec3f(0, 0, -2.5))); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, -2.5)), &contact, &depth, &normal); - ASSERT_TRUE(res); - ASSERT_TRUE(std::abs(depth - 2.5) < 0.001); - ASSERT_TRUE(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); - ASSERT_TRUE(contact.equal(transform.transform(Vec3f(0, 0, -2.5)))); + BOOST_CHECK(res); + BOOST_CHECK(std::abs(depth - 2.5) < 0.001); + BOOST_CHECK(normal.equal(transform.getQuatRotation().transform(Vec3f(0, 0, -1)))); + BOOST_CHECK(contact.equal(transform.transform(Vec3f(0, 0, -2.5)))); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, 10.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, 10.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, Transform3f(), hs, Transform3f(Vec3f(0, 0, -10.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver1.shapeIntersect(s, transform, hs, transform * Transform3f(Vec3f(0, 0, -10.1)), &contact, &depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(shapeDistance, spheresphere) +BOOST_AUTO_TEST_CASE(shapeDistance_spheresphere) { Sphere s1(20); Sphere s2(10); @@ -1802,57 +1808,57 @@ TEST(shapeDistance, spheresphere) FCL_REAL dist = -1; res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 10) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 10) < 0.001); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(30.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(29.9, 0, 0)), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver1.shapeDistance(s1, Transform3f(Vec3f(40, 0, 0)), s2, Transform3f(), &dist); - ASSERT_TRUE(fabs(dist - 10) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 10) < 0.001); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, Transform3f(Vec3f(30.1, 0, 0)), s2, Transform3f(), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, Transform3f(Vec3f(29.9, 0, 0)), s2, Transform3f(), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver1.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(40, 0, 0)), &dist); // this is one problem: the precise is low sometimes - ASSERT_TRUE(fabs(dist - 10) < 0.1); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 10) < 0.1); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(30.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.06); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.06); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(29.9, 0, 0)), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver1.shapeDistance(s1, transform * Transform3f(Vec3f(40, 0, 0)), s2, transform, &dist); - ASSERT_TRUE(fabs(dist - 10) < 0.1); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 10) < 0.1); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, transform * Transform3f(Vec3f(30.1, 0, 0)), s2, transform, &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.1); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.1); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, transform * Transform3f(Vec3f(29.9, 0, 0)), s2, transform, &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); } -TEST(shapeDistance, boxbox) +BOOST_AUTO_TEST_CASE(shapeDistance_boxbox) { Box s1(20, 40, 50); Box s2(10, 10, 10); @@ -1864,31 +1870,31 @@ TEST(shapeDistance, boxbox) FCL_REAL dist; res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver1.shapeDistance(s1, transform, s2, transform, &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(15.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(15.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(20, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 5) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 5) < 0.001); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(20, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 5) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 5) < 0.001); + BOOST_CHECK(res); } -TEST(shapeDistance, boxsphere) +BOOST_AUTO_TEST_CASE(shapeDistance_boxsphere) { Sphere s1(20); Box s2(5, 5, 5); @@ -1900,31 +1906,31 @@ TEST(shapeDistance, boxsphere) FCL_REAL dist; res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver1.shapeDistance(s1, transform, s2, transform, &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(22.6, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(22.6, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.05); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.05); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 17.5) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 17.5) < 0.001); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 17.5) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 17.5) < 0.001); + BOOST_CHECK(res); } -TEST(shapeDistance, cylindercylinder) +BOOST_AUTO_TEST_CASE(shapeDistance_cylindercylinder) { Cylinder s1(5, 10); Cylinder s2(5, 10); @@ -1936,33 +1942,33 @@ TEST(shapeDistance, cylindercylinder) FCL_REAL dist; res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver1.shapeDistance(s1, transform, s2, transform, &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(10.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(10.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 30) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 30) < 0.001); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 30) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 30) < 0.001); + BOOST_CHECK(res); } -TEST(shapeDistance, conecone) +BOOST_AUTO_TEST_CASE(shapeDistance_conecone) { Cone s1(5, 10); Cone s2(5, 10); @@ -1974,31 +1980,31 @@ TEST(shapeDistance, conecone) FCL_REAL dist; res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver1.shapeDistance(s1, transform, s2, transform, &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(10.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(10.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(0, 0, 40)), &dist); - ASSERT_TRUE(fabs(dist - 30) < 1); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 30) < 1); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(0, 0, 40)), &dist); - ASSERT_TRUE(fabs(dist - 30) < 1); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 30) < 1); + BOOST_CHECK(res); } -TEST(shapeDistance, conecylinder) +BOOST_AUTO_TEST_CASE(shapeDistance_conecylinder) { Cylinder s1(5, 10); Cone s2(5, 10); @@ -2010,33 +2016,33 @@ TEST(shapeDistance, conecylinder) FCL_REAL dist; res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver1.shapeDistance(s1, transform, s2, transform, &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(10.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.01); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.01); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(10.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.02); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.02); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 30) < 0.01); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 30) < 0.01); + BOOST_CHECK(res); res = solver1.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 30) < 0.1); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 30) < 0.1); + BOOST_CHECK(res); } -TEST(shapeIntersectionGJK, spheresphere) +BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_spheresphere) { Sphere s1(20); Sphere s2(10); @@ -2053,113 +2059,113 @@ TEST(shapeIntersectionGJK, spheresphere) bool res; res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(40, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(40, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(40, 0, 0)), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(40, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(40, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(40, 0, 0)), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(30, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(30, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(30, 0, 0)), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(30.01, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(30.01, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(30.01, 0, 0)), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(29.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(29.9, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(29.9, 0, 0)), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(29.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(29.9, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(29.9, 0, 0)), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform, &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(-29.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(-29.9, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(-29.9, 0, 0)), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(-29.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(-29.9, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(-29.9, 0, 0)), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(-30, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(-30, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2, Transform3f(Vec3f(-30, 0, 0)), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(-30.01, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(-30.01, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, transform, &s2, transform * Transform3f(Vec3f(-30.01, 0, 0)), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(shapeIntersectionGJK, boxbox) +BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_boxbox) { Box s1(20, 40, 50); Box s2(10, 10, 10); @@ -2173,39 +2179,39 @@ TEST(shapeIntersectionGJK, boxbox) bool res; res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform, &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(15, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(15, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(15.01, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(15.01, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); Quaternion3f q; q.fromAxisAngle(Vec3f(0, 0, 1), (FCL_REAL)3.140 / 6); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(q), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(q), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(q), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(q), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); } -TEST(shapeIntersectionGJK, spherebox) +BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_spherebox) { Sphere s1(20); Box s2(5, 5, 5); @@ -2219,37 +2225,37 @@ TEST(shapeIntersectionGJK, spherebox) bool res; res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform, &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(22.5, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(22.5, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(22.51, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(22.51, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(22.4, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(22.4, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(22.4, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(22.4, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); } -TEST(shapeIntersectionGJK, cylindercylinder) +BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_cylindercylinder) { Cylinder s1(5, 10); Cylinder s2(5, 10); @@ -2263,37 +2269,37 @@ TEST(shapeIntersectionGJK, cylindercylinder) bool res; res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform, &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(9.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(9.9, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(9.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(9.9, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(10, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(10, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(10.1, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(10.1, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(shapeIntersectionGJK, conecone) +BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_conecone) { Cone s1(5, 10); Cone s2(5, 10); @@ -2307,47 +2313,47 @@ TEST(shapeIntersectionGJK, conecone) bool res; res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform, &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(9.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(9.9, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(9.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(9.9, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(10.1, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(10.1, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(10.1, 0, 0)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(10.1, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(0, 0, 9.9)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(0, 0, 9.9)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(0, 0, 9.9)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(0, 0, 9.9)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); } -TEST(shapeIntersectionGJK, conecylinder) +BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_conecylinder) { Cylinder s1(5, 10); Cone s2(5, 10); @@ -2361,58 +2367,58 @@ TEST(shapeIntersectionGJK, conecylinder) bool res; res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform, &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(9.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(9.9, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(9.9, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(9.9, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(10, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(10, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(10, 0, 0)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(10, 0, 0)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(0, 0, 9.9)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(0, 0, 9.9)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(0, 0, 9.9)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(0, 0, 9.9)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(0, 0, 10)), NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, Transform3f(), s2, Transform3f(Vec3f(0, 0, 10)), &contact, &penetration_depth, &normal); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(0, 0, 10.1)), NULL, NULL, NULL); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); res = solver2.shapeIntersect(s1, transform, s2, transform * Transform3f(Vec3f(0, 0, 10.1)), &contact, &penetration_depth, &normal); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(shapeIntersectionGJK, spheretriangle) +BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_spheretriangle) { Sphere s(10); Vec3f t[3]; @@ -2426,25 +2432,25 @@ TEST(shapeIntersectionGJK, spheretriangle) bool res; res = solver2.shapeTriangleIntersect(s, Transform3f(), t[0], t[1], t[2], NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeTriangleIntersect(s, transform, t[0], t[1], t[2], transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); t[0].setValue(30, 0, 0); t[1].setValue(9.9, -20, 0); t[2].setValue(9.9, 20, 0); res = solver2.shapeTriangleIntersect(s, Transform3f(), t[0], t[1], t[2], NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); res = solver2.shapeTriangleIntersect(s, transform, t[0], t[1], t[2], transform, NULL, NULL, NULL); - ASSERT_TRUE(res); + BOOST_CHECK(res); } -TEST(shapeDistanceGJK, spheresphere) +BOOST_AUTO_TEST_CASE(spheresphere) { Sphere s1(20); Sphere s2(10); @@ -2456,56 +2462,56 @@ TEST(shapeDistanceGJK, spheresphere) FCL_REAL dist = -1; res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 10) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 10) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(30.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(29.9, 0, 0)), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver2.shapeDistance(s1, Transform3f(Vec3f(40, 0, 0)), s2, Transform3f(), &dist); - ASSERT_TRUE(fabs(dist - 10) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 10) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, Transform3f(Vec3f(30.1, 0, 0)), s2, Transform3f(), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, Transform3f(Vec3f(29.9, 0, 0)), s2, Transform3f(), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver2.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 10) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 10) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(30.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(29.9, 0, 0)), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver2.shapeDistance(s1, transform * Transform3f(Vec3f(40, 0, 0)), s2, transform, &dist); - ASSERT_TRUE(fabs(dist - 10) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 10) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, transform * Transform3f(Vec3f(30.1, 0, 0)), s2, transform, &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, transform * Transform3f(Vec3f(29.9, 0, 0)), s2, transform, &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); } -TEST(shapeDistanceGJK, boxbox) +BOOST_AUTO_TEST_CASE(boxbox) { Box s1(20, 40, 50); Box s2(10, 10, 10); @@ -2517,31 +2523,31 @@ TEST(shapeDistanceGJK, boxbox) FCL_REAL dist; res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver2.shapeDistance(s1, transform, s2, transform, &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(15.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(15.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(20, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 5) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 5) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(20, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 5) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 5) < 0.001); + BOOST_CHECK(res); } -TEST(shapeDistanceGJK, boxsphere) +BOOST_AUTO_TEST_CASE(boxsphere) { Sphere s1(20); Box s2(5, 5, 5); @@ -2553,31 +2559,31 @@ TEST(shapeDistanceGJK, boxsphere) FCL_REAL dist; res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver2.shapeDistance(s1, transform, s2, transform, &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(22.6, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.01); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.01); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(22.6, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.01); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.01); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 17.5) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 17.5) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 17.5) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 17.5) < 0.001); + BOOST_CHECK(res); } -TEST(shapeDistanceGJK, cylindercylinder) +BOOST_AUTO_TEST_CASE(cylindercylinder) { Cylinder s1(5, 10); Cylinder s2(5, 10); @@ -2589,33 +2595,33 @@ TEST(shapeDistanceGJK, cylindercylinder) FCL_REAL dist; res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver2.shapeDistance(s1, transform, s2, transform, &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(10.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(10.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 30) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 30) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 30) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 30) < 0.001); + BOOST_CHECK(res); } -TEST(shapeDistanceGJK, conecone) +BOOST_AUTO_TEST_CASE(conecone) { Cone s1(5, 10); Cone s2(5, 10); @@ -2627,31 +2633,31 @@ TEST(shapeDistanceGJK, conecone) FCL_REAL dist; res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver2.shapeDistance(s1, transform, s2, transform, &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(10.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(10.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(0, 0, 40)), &dist); - ASSERT_TRUE(fabs(dist - 30) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 30) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(0, 0, 40)), &dist); - ASSERT_TRUE(fabs(dist - 30) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 30) < 0.001); + BOOST_CHECK(res); } -TEST(shapeDistanceGJK, conecylinder) +BOOST_AUTO_TEST_CASE(conecylinder) { Cylinder s1(5, 10); Cone s2(5, 10); @@ -2663,34 +2669,28 @@ TEST(shapeDistanceGJK, conecylinder) FCL_REAL dist; res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(), &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver2.shapeDistance(s1, transform, s2, transform, &dist); - ASSERT_TRUE(dist < 0); - ASSERT_FALSE(res); + BOOST_CHECK(dist < 0); + BOOST_CHECK_FALSE(res); res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(10.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(10.1, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 0.1) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 0.1) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, Transform3f(), s2, Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 30) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 30) < 0.001); + BOOST_CHECK(res); res = solver2.shapeDistance(s1, transform, s2, transform * Transform3f(Vec3f(40, 0, 0)), &dist); - ASSERT_TRUE(fabs(dist - 30) < 0.001); - ASSERT_TRUE(res); + BOOST_CHECK(fabs(dist - 30) < 0.001); + BOOST_CHECK(res); } -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} - diff --git a/trunk/fcl/test/test_fcl_math.cpp b/trunk/fcl/test/test_fcl_math.cpp index 755cacc1a370596bbc85538297a9c6a6afe7c24e..db57b14384dad64aa557d5a311696c947585e99f 100644 --- a/trunk/fcl/test/test_fcl_math.cpp +++ b/trunk/fcl/test/test_fcl_math.cpp @@ -33,248 +33,252 @@ */ +#define BOOST_TEST_MODULE "FCL_MATH" +#include <boost/test/unit_test.hpp> + #include "fcl/simd/math_simd_details.h" #include "fcl/math/vec_3f.h" #include "fcl/math/matrix_3f.h" #include "fcl/broadphase/morton.h" -#include <gtest/gtest.h> +#include "fcl/config.h" using namespace fcl; -TEST(vec_test, basic_vec32) +BOOST_AUTO_TEST_CASE(vec_test_basic_vec32) { typedef Vec3fX<details::Vec3Data<float> > Vec3f32; Vec3f32 v1(1.0f, 2.0f, 3.0f); - ASSERT_TRUE(v1[0] == 1.0f); - ASSERT_TRUE(v1[1] == 2.0f); - ASSERT_TRUE(v1[2] == 3.0f); + BOOST_CHECK(v1[0] == 1.0f); + BOOST_CHECK(v1[1] == 2.0f); + BOOST_CHECK(v1[2] == 3.0f); Vec3f32 v2 = v1; Vec3f32 v3(3.3f, 4.3f, 5.3f); v1 += v3; - ASSERT_TRUE(v1.equal(v2 + v3)); + BOOST_CHECK(v1.equal(v2 + v3)); v1 -= v3; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 -= v3; - ASSERT_TRUE(v1.equal(v2 - v3)); + BOOST_CHECK(v1.equal(v2 - v3)); v1 += v3; v1 *= v3; - ASSERT_TRUE(v1.equal(v2 * v3)); + BOOST_CHECK(v1.equal(v2 * v3)); v1 /= v3; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 /= v3; - ASSERT_TRUE(v1.equal(v2 / v3)); + BOOST_CHECK(v1.equal(v2 / v3)); v1 *= v3; v1 *= 2.0f; - ASSERT_TRUE(v1.equal(v2 * 2.0f)); + BOOST_CHECK(v1.equal(v2 * 2.0f)); v1 /= 2.0f; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 /= 2.0f; - ASSERT_TRUE(v1.equal(v2 / 2.0f)); + BOOST_CHECK(v1.equal(v2 / 2.0f)); v1 *= 2.0f; v1 += 2.0f; - ASSERT_TRUE(v1.equal(v2 + 2.0f)); + BOOST_CHECK(v1.equal(v2 + 2.0f)); v1 -= 2.0f; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 -= 2.0f; - ASSERT_TRUE(v1.equal(v2 - 2.0f)); + BOOST_CHECK(v1.equal(v2 - 2.0f)); v1 += 2.0f; - ASSERT_TRUE((-Vec3f32(1.0f, 2.0f, 3.0f)).equal(Vec3f32(-1.0f, -2.0f, -3.0f))); + BOOST_CHECK((-Vec3f32(1.0f, 2.0f, 3.0f)).equal(Vec3f32(-1.0f, -2.0f, -3.0f))); v1 = Vec3f32(1.0f, 2.0f, 3.0f); v2 = Vec3f32(3.0f, 4.0f, 5.0f); - ASSERT_TRUE((v1.cross(v2)).equal(Vec3f32(-2.0f, 4.0f, -2.0f))); - ASSERT_TRUE(abs(v1.dot(v2) - 26) < 1e-5); + BOOST_CHECK((v1.cross(v2)).equal(Vec3f32(-2.0f, 4.0f, -2.0f))); + BOOST_CHECK(abs(v1.dot(v2) - 26) < 1e-5); v1 = Vec3f32(3.0f, 4.0f, 5.0f); - ASSERT_TRUE(abs(v1.sqrLength() - 50) < 1e-5); - ASSERT_TRUE(abs(v1.length() - sqrt(50)) < 1e-5); - ASSERT_TRUE(normalize(v1).equal(v1 / v1.length())); + BOOST_CHECK(abs(v1.sqrLength() - 50) < 1e-5); + BOOST_CHECK(abs(v1.length() - sqrt(50)) < 1e-5); + BOOST_CHECK(normalize(v1).equal(v1 / v1.length())); } -TEST(vec_test, basic_vec64) +BOOST_AUTO_TEST_CASE(vec_test_basic_vec64) { typedef Vec3fX<details::Vec3Data<double> > Vec3f64; Vec3f64 v1(1.0, 2.0, 3.0); - ASSERT_TRUE(v1[0] == 1.0); - ASSERT_TRUE(v1[1] == 2.0); - ASSERT_TRUE(v1[2] == 3.0); + BOOST_CHECK(v1[0] == 1.0); + BOOST_CHECK(v1[1] == 2.0); + BOOST_CHECK(v1[2] == 3.0); Vec3f64 v2 = v1; Vec3f64 v3(3.3, 4.3, 5.3); v1 += v3; - ASSERT_TRUE(v1.equal(v2 + v3)); + BOOST_CHECK(v1.equal(v2 + v3)); v1 -= v3; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 -= v3; - ASSERT_TRUE(v1.equal(v2 - v3)); + BOOST_CHECK(v1.equal(v2 - v3)); v1 += v3; v1 *= v3; - ASSERT_TRUE(v1.equal(v2 * v3)); + BOOST_CHECK(v1.equal(v2 * v3)); v1 /= v3; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 /= v3; - ASSERT_TRUE(v1.equal(v2 / v3)); + BOOST_CHECK(v1.equal(v2 / v3)); v1 *= v3; v1 *= 2.0; - ASSERT_TRUE(v1.equal(v2 * 2.0)); + BOOST_CHECK(v1.equal(v2 * 2.0)); v1 /= 2.0; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 /= 2.0; - ASSERT_TRUE(v1.equal(v2 / 2.0)); + BOOST_CHECK(v1.equal(v2 / 2.0)); v1 *= 2.0; v1 += 2.0; - ASSERT_TRUE(v1.equal(v2 + 2.0)); + BOOST_CHECK(v1.equal(v2 + 2.0)); v1 -= 2.0; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 -= 2.0; - ASSERT_TRUE(v1.equal(v2 - 2.0)); + BOOST_CHECK(v1.equal(v2 - 2.0)); v1 += 2.0; - ASSERT_TRUE((-Vec3f64(1.0, 2.0, 3.0)).equal(Vec3f64(-1.0, -2.0, -3.0))); + BOOST_CHECK((-Vec3f64(1.0, 2.0, 3.0)).equal(Vec3f64(-1.0, -2.0, -3.0))); v1 = Vec3f64(1.0, 2.0, 3.0); v2 = Vec3f64(3.0, 4.0, 5.0); - ASSERT_TRUE((v1.cross(v2)).equal(Vec3f64(-2.0, 4.0, -2.0))); - ASSERT_TRUE(abs(v1.dot(v2) - 26) < 1e-5); + BOOST_CHECK((v1.cross(v2)).equal(Vec3f64(-2.0, 4.0, -2.0))); + BOOST_CHECK(abs(v1.dot(v2) - 26) < 1e-5); v1 = Vec3f64(3.0, 4.0, 5.0); - ASSERT_TRUE(abs(v1.sqrLength() - 50) < 1e-5); - ASSERT_TRUE(abs(v1.length() - sqrt(50)) < 1e-5); - ASSERT_TRUE(normalize(v1).equal(v1 / v1.length())); + BOOST_CHECK(abs(v1.sqrLength() - 50) < 1e-5); + BOOST_CHECK(abs(v1.length() - sqrt(50)) < 1e-5); + BOOST_CHECK(normalize(v1).equal(v1 / v1.length())); v1 = Vec3f64(1.0, 2.0, 3.0); v2 = Vec3f64(3.0, 4.0, 5.0); - ASSERT_TRUE((v1.cross(v2)).equal(Vec3f64(-2.0, 4.0, -2.0))); - ASSERT_TRUE(v1.dot(v2) == 26); + BOOST_CHECK((v1.cross(v2)).equal(Vec3f64(-2.0, 4.0, -2.0))); + BOOST_CHECK(v1.dot(v2) == 26); } +#if FCL_HAVE_SSE -TEST(vec_test, sse_vec32) +BOOST_AUTO_TEST_CASE(vec_test_sse_vec32) { typedef Vec3fX<details::sse_meta_f4> Vec3f32; Vec3f32 v1(1.0f, 2.0f, 3.0f); - ASSERT_TRUE(v1[0] == 1.0f); - ASSERT_TRUE(v1[1] == 2.0f); - ASSERT_TRUE(v1[2] == 3.0f); + BOOST_CHECK(v1[0] == 1.0f); + BOOST_CHECK(v1[1] == 2.0f); + BOOST_CHECK(v1[2] == 3.0f); Vec3f32 v2 = v1; Vec3f32 v3(3.3f, 4.3f, 5.3f); v1 += v3; - ASSERT_TRUE(v1.equal(v2 + v3)); + BOOST_CHECK(v1.equal(v2 + v3)); v1 -= v3; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 -= v3; - ASSERT_TRUE(v1.equal(v2 - v3)); + BOOST_CHECK(v1.equal(v2 - v3)); v1 += v3; v1 *= v3; - ASSERT_TRUE(v1.equal(v2 * v3)); + BOOST_CHECK(v1.equal(v2 * v3)); v1 /= v3; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 /= v3; - ASSERT_TRUE(v1.equal(v2 / v3)); + BOOST_CHECK(v1.equal(v2 / v3)); v1 *= v3; v1 *= 2.0f; - ASSERT_TRUE(v1.equal(v2 * 2.0f)); + BOOST_CHECK(v1.equal(v2 * 2.0f)); v1 /= 2.0f; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 /= 2.0f; - ASSERT_TRUE(v1.equal(v2 / 2.0f)); + BOOST_CHECK(v1.equal(v2 / 2.0f)); v1 *= 2.0f; v1 += 2.0f; - ASSERT_TRUE(v1.equal(v2 + 2.0f)); + BOOST_CHECK(v1.equal(v2 + 2.0f)); v1 -= 2.0f; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 -= 2.0f; - ASSERT_TRUE(v1.equal(v2 - 2.0f)); + BOOST_CHECK(v1.equal(v2 - 2.0f)); v1 += 2.0f; - ASSERT_TRUE((-Vec3f32(1.0f, 2.0f, 3.0f)).equal(Vec3f32(-1.0f, -2.0f, -3.0f))); + BOOST_CHECK((-Vec3f32(1.0f, 2.0f, 3.0f)).equal(Vec3f32(-1.0f, -2.0f, -3.0f))); v1 = Vec3f32(1.0f, 2.0f, 3.0f); v2 = Vec3f32(3.0f, 4.0f, 5.0f); - ASSERT_TRUE((v1.cross(v2)).equal(Vec3f32(-2.0f, 4.0f, -2.0f))); - ASSERT_TRUE(abs(v1.dot(v2) - 26) < 1e-5); + BOOST_CHECK((v1.cross(v2)).equal(Vec3f32(-2.0f, 4.0f, -2.0f))); + BOOST_CHECK(abs(v1.dot(v2) - 26) < 1e-5); v1 = Vec3f32(3.0f, 4.0f, 5.0f); - ASSERT_TRUE(abs(v1.sqrLength() - 50) < 1e-5); - ASSERT_TRUE(abs(v1.length() - sqrt(50)) < 1e-5); - ASSERT_TRUE(normalize(v1).equal(v1 / v1.length())); + BOOST_CHECK(abs(v1.sqrLength() - 50) < 1e-5); + BOOST_CHECK(abs(v1.length() - sqrt(50)) < 1e-5); + BOOST_CHECK(normalize(v1).equal(v1 / v1.length())); } -TEST(vec_test, sse_vec64) +BOOST_AUTO_TEST_CASE(vec_test_sse_vec64) { typedef Vec3fX<details::sse_meta_d4> Vec3f64; Vec3f64 v1(1.0, 2.0, 3.0); - ASSERT_TRUE(v1[0] == 1.0); - ASSERT_TRUE(v1[1] == 2.0); - ASSERT_TRUE(v1[2] == 3.0); + BOOST_CHECK(v1[0] == 1.0); + BOOST_CHECK(v1[1] == 2.0); + BOOST_CHECK(v1[2] == 3.0); Vec3f64 v2 = v1; Vec3f64 v3(3.3, 4.3, 5.3); v1 += v3; - ASSERT_TRUE(v1.equal(v2 + v3)); + BOOST_CHECK(v1.equal(v2 + v3)); v1 -= v3; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 -= v3; - ASSERT_TRUE(v1.equal(v2 - v3)); + BOOST_CHECK(v1.equal(v2 - v3)); v1 += v3; v1 *= v3; - ASSERT_TRUE(v1.equal(v2 * v3)); + BOOST_CHECK(v1.equal(v2 * v3)); v1 /= v3; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 /= v3; - ASSERT_TRUE(v1.equal(v2 / v3)); + BOOST_CHECK(v1.equal(v2 / v3)); v1 *= v3; v1 *= 2.0; - ASSERT_TRUE(v1.equal(v2 * 2.0)); + BOOST_CHECK(v1.equal(v2 * 2.0)); v1 /= 2.0; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 /= 2.0; - ASSERT_TRUE(v1.equal(v2 / 2.0)); + BOOST_CHECK(v1.equal(v2 / 2.0)); v1 *= 2.0; v1 += 2.0; - ASSERT_TRUE(v1.equal(v2 + 2.0)); + BOOST_CHECK(v1.equal(v2 + 2.0)); v1 -= 2.0; - ASSERT_TRUE(v1.equal(v2)); + BOOST_CHECK(v1.equal(v2)); v1 -= 2.0; - ASSERT_TRUE(v1.equal(v2 - 2.0)); + BOOST_CHECK(v1.equal(v2 - 2.0)); v1 += 2.0; - ASSERT_TRUE((-Vec3f64(1.0, 2.0, 3.0)).equal(Vec3f64(-1.0, -2.0, -3.0))); + BOOST_CHECK((-Vec3f64(1.0, 2.0, 3.0)).equal(Vec3f64(-1.0, -2.0, -3.0))); v1 = Vec3f64(1.0, 2.0, 3.0); v2 = Vec3f64(3.0, 4.0, 5.0); - ASSERT_TRUE((v1.cross(v2)).equal(Vec3f64(-2.0, 4.0, -2.0))); - ASSERT_TRUE(abs(v1.dot(v2) - 26) < 1e-5); + BOOST_CHECK((v1.cross(v2)).equal(Vec3f64(-2.0, 4.0, -2.0))); + BOOST_CHECK(abs(v1.dot(v2) - 26) < 1e-5); v1 = Vec3f64(3.0, 4.0, 5.0); - ASSERT_TRUE(abs(v1.sqrLength() - 50) < 1e-5); - ASSERT_TRUE(abs(v1.length() - sqrt(50)) < 1e-5); - ASSERT_TRUE(normalize(v1).equal(v1 / v1.length())); + BOOST_CHECK(abs(v1.sqrLength() - 50) < 1e-5); + BOOST_CHECK(abs(v1.length() - sqrt(50)) < 1e-5); + BOOST_CHECK(normalize(v1).equal(v1 / v1.length())); v1 = Vec3f64(1.0, 2.0, 3.0); v2 = Vec3f64(3.0, 4.0, 5.0); - ASSERT_TRUE((v1.cross(v2)).equal(Vec3f64(-2.0, 4.0, -2.0))); - ASSERT_TRUE(v1.dot(v2) == 26); + BOOST_CHECK((v1.cross(v2)).equal(Vec3f64(-2.0, 4.0, -2.0))); + BOOST_CHECK(v1.dot(v2) == 26); } -TEST(mat_test, sse_mat32_consistent) +BOOST_AUTO_TEST_CASE(sse_mat32_consistent) { typedef Vec3fX<details::Vec3Data<float> > Vec3f32; typedef Vec3fX<details::sse_meta_f4> Vec3f32SSE; @@ -290,38 +294,38 @@ TEST(mat_test, sse_mat32_consistent) for(size_t i = 0; i < 3; ++i) for(size_t j = 0; j < 3; ++j) - ASSERT_TRUE((m1(i, j) - m2(i, j) < 1e-1)); + BOOST_CHECK((m1(i, j) - m2(i, j) < 1e-1)); Matrix3f32 m3(transpose(m1)); Matrix3f32SSE m4(transpose(m2)); for(size_t i = 0; i < 3; ++i) for(size_t j = 0; j < 3; ++j) - ASSERT_TRUE((m3(i, j) - m4(i, j) < 1e-1)); + BOOST_CHECK((m3(i, j) - m4(i, j) < 1e-1)); m3 = m1; m3.transpose(); m4 = m2; m4.transpose(); for(size_t i = 0; i < 3; ++i) for(size_t j = 0; j < 3; ++j) - ASSERT_TRUE((m3(i, j) - m4(i, j) < 1e-1)); + BOOST_CHECK((m3(i, j) - m4(i, j) < 1e-1)); m3 = inverse(m1); m4 = inverse(m2); for(size_t i = 0; i < 3; ++i) for(size_t j = 0; j < 3; ++j) - ASSERT_TRUE((m3(i, j) - m4(i, j) < 1e-1)); + BOOST_CHECK((m3(i, j) - m4(i, j) < 1e-1)); m3 = m1; m3.inverse(); m4 = m2; m4.inverse(); for(size_t i = 0; i < 3; ++i) for(size_t j = 0; j < 3; ++j) - ASSERT_TRUE((m3(i, j) - m4(i, j) < 1e-1)); + BOOST_CHECK((m3(i, j) - m4(i, j) < 1e-1)); } -TEST(vec_test, sse_vec32_consistent) +BOOST_AUTO_TEST_CASE(vec_test_sse_vec32_consistent) { typedef Vec3fX<details::Vec3Data<float> > Vec3f32; typedef Vec3fX<details::sse_meta_f4> Vec3f32SSE; @@ -330,146 +334,146 @@ TEST(vec_test, sse_vec32_consistent) Vec3f32SSE v3(3.4f, 4.2f, 10.5f), v4(3.1f, 0.1f, -50.4f); Vec3f32 v12 = v1 + v2; Vec3f32SSE v34 = v3 + v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1 - v2; v34 = v3 - v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1 * v2; v34 = v3 * v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1 / v2; v34 = v3 / v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); float t = 1234.433f; v12 = v1 + t; v34 = v3 + t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1 - t; v34 = v3 - t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1 * t; v34 = v3 * t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1 / t; v34 = v3 / t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 += v2; v34 = v3; v34 += v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 -= v2; v34 = v3; v34 -= v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 *= v2; v34 = v3; v34 *= v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 /= v2; v34 = v3; v34 /= v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 += t; v34 = v3; v34 += t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 -= t; v34 = v3; v34 -= t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 *= t; v34 = v3; v34 *= t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 /= t; v34 = v3; v34 /= t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = -v1; v34 = -v3; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1.cross(v2); v34 = v3.cross(v4); - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); - ASSERT_TRUE(abs(v1.dot(v2) - v3.dot(v4)) < 1e-5); + BOOST_CHECK(abs(v1.dot(v2) - v3.dot(v4)) < 1e-5); v12 = min(v1, v2); v34 = min(v3, v4); - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = max(v1, v2); v34 = max(v3, v4); - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = abs(v2); v34 = abs(v4); - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); Vec3f32 delta1(1e-9f, 1e-9f, 1e-9f); Vec3f32SSE delta2(1e-9f, 1e-9f, 1e-9f); - ASSERT_TRUE((v1 + delta1).equal(v1)); - ASSERT_TRUE((v3 + delta2).equal(v3)); + BOOST_CHECK((v1 + delta1).equal(v1)); + BOOST_CHECK((v3 + delta2).equal(v3)); - ASSERT_TRUE(abs(v1.length() - v3.length()) < 1e-5); - ASSERT_TRUE(abs(v1.sqrLength() - v3.sqrLength()) < 1e-5); + BOOST_CHECK(abs(v1.length() - v3.length()) < 1e-5); + BOOST_CHECK(abs(v1.sqrLength() - v3.sqrLength()) < 1e-5); v12 = v1; v12.negate(); v34 = v3; v34.negate(); - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12.normalize(); v34 = v3; v34.normalize(); - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = normalize(v1); v34 = normalize(v3); - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); } -TEST(vec_test, sse_vec64_consistent) +BOOST_AUTO_TEST_CASE(vec_test_sse_vec64_consistent) { typedef Vec3fX<details::Vec3Data<double> > Vec3f64; typedef Vec3fX<details::sse_meta_d4> Vec3f64SSE; @@ -478,146 +482,148 @@ TEST(vec_test, sse_vec64_consistent) Vec3f64SSE v3(3.4, 4.2, 10.5), v4(3.1, 0.1, -50.4); Vec3f64 v12 = v1 + v2; Vec3f64SSE v34 = v3 + v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1 - v2; v34 = v3 - v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1 * v2; v34 = v3 * v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1 / v2; v34 = v3 / v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); double t = 1234.433; v12 = v1 + t; v34 = v3 + t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1 - t; v34 = v3 - t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1 * t; v34 = v3 * t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1 / t; v34 = v3 / t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 += v2; v34 = v3; v34 += v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 -= v2; v34 = v3; v34 -= v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 *= v2; v34 = v3; v34 *= v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 /= v2; v34 = v3; v34 /= v4; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 += t; v34 = v3; v34 += t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 -= t; v34 = v3; v34 -= t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 *= t; v34 = v3; v34 *= t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12 /= t; v34 = v3; v34 /= t; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = -v1; v34 = -v3; - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1.cross(v2); v34 = v3.cross(v4); - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); - ASSERT_TRUE(abs(v1.dot(v2) - v3.dot(v4)) < 1e-5); + BOOST_CHECK(abs(v1.dot(v2) - v3.dot(v4)) < 1e-5); v12 = min(v1, v2); v34 = min(v3, v4); - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = max(v1, v2); v34 = max(v3, v4); - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = abs(v2); v34 = abs(v4); - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); Vec3f64 delta1(1e-15, 1e-15, 1e-15); Vec3f64SSE delta2(1e-15, 1e-15, 1e-15); - ASSERT_TRUE((v1 + delta1).equal(v1)); - ASSERT_TRUE((v3 + delta2).equal(v3)); + BOOST_CHECK((v1 + delta1).equal(v1)); + BOOST_CHECK((v3 + delta2).equal(v3)); - ASSERT_TRUE(abs(v1.length() - v3.length()) < 1e-5); - ASSERT_TRUE(abs(v1.sqrLength() - v3.sqrLength()) < 1e-5); + BOOST_CHECK(abs(v1.length() - v3.length()) < 1e-5); + BOOST_CHECK(abs(v1.sqrLength() - v3.sqrLength()) < 1e-5); v12 = v1; v12.negate(); v34 = v3; v34.negate(); - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = v1; v12.normalize(); v34 = v3; v34.normalize(); - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); v12 = normalize(v1); v34 = normalize(v3); - ASSERT_TRUE(abs(v12[0] - v34[0]) < 1e-5); - ASSERT_TRUE(abs(v12[1] - v34[1]) < 1e-5); - ASSERT_TRUE(abs(v12[2] - v34[2]) < 1e-5); + BOOST_CHECK(abs(v12[0] - v34[0]) < 1e-5); + BOOST_CHECK(abs(v12[1] - v34[1]) < 1e-5); + BOOST_CHECK(abs(v12[2] - v34[2]) < 1e-5); } -TEST(morton_test, morton) +#endif + +BOOST_AUTO_TEST_CASE(morton) { AABB bbox(Vec3f(0, 0, 0), Vec3f(1000, 1000, 1000)); morton_functor<boost::dynamic_bitset<> > F1(bbox, 10); @@ -632,9 +638,3 @@ TEST(morton_test, morton) std::cout << std::hex << F4(p) << std::endl; } - -int main(int argc, char** argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/trunk/fcl/test/test_fcl_octomap.cpp b/trunk/fcl/test/test_fcl_octomap.cpp index 13bcfcebf6740a3869a59efc3c01e8a15d1e256c..79822293d8760452b57fddd3dfbd6c5908b32933 100644 --- a/trunk/fcl/test/test_fcl_octomap.cpp +++ b/trunk/fcl/test/test_fcl_octomap.cpp @@ -34,16 +34,21 @@ /** \author Jia Pan */ +#define BOOST_TEST_MODULE "FCL_OCTOMAP" +#include <boost/test/unit_test.hpp> + #include "fcl/octree.h" #include "fcl/traversal/traversal_node_octree.h" #include "fcl/broadphase/broadphase.h" #include "fcl/shape/geometric_shape_to_BVH_model.h" #include "fcl/math/transform.h" #include "test_fcl_utility.h" -#include <gtest/gtest.h> +#include "fcl_resources/config.h" +#include <boost/filesystem.hpp> using namespace fcl; + struct TStruct { std::vector<double> records; @@ -90,19 +95,19 @@ void octomap_collision_test_BVH(std::size_t n, bool exhaustive); template<typename BV> void octomap_distance_test_BVH(std::size_t n); -TEST(test_octomap_cost, cost) +BOOST_AUTO_TEST_CASE(test_octomap_cost) { octomap_cost_test(200, 100, 10, false, false); octomap_cost_test(200, 1000, 10, false, false); } -TEST(test_octomap_cost, cost_mesh) +BOOST_AUTO_TEST_CASE(test_octomap_cost_mesh) { octomap_cost_test(200, 100, 10, true, false); octomap_cost_test(200, 1000, 10, true, false); } -TEST(test_octomap, collision) +BOOST_AUTO_TEST_CASE(test_octomap_collision) { octomap_collision_test(200, 100, false, 10, false, false); octomap_collision_test(200, 1000, false, 10, false, false); @@ -110,7 +115,7 @@ TEST(test_octomap, collision) octomap_collision_test(200, 1000, true, 1, false, false); } -TEST(test_octomap, collision_mesh) +BOOST_AUTO_TEST_CASE(test_octomap_collision_mesh) { octomap_collision_test(200, 100, false, 10, true, true); octomap_collision_test(200, 1000, false, 10, true, true); @@ -118,7 +123,7 @@ TEST(test_octomap, collision_mesh) octomap_collision_test(200, 1000, true, 1, true, true); } -TEST(test_octomap, collision_mesh_octomap_box) +BOOST_AUTO_TEST_CASE(test_octomap_collision_mesh_octomap_box) { octomap_collision_test(200, 100, false, 10, true, false); octomap_collision_test(200, 1000, false, 10, true, false); @@ -126,58 +131,54 @@ TEST(test_octomap, collision_mesh_octomap_box) octomap_collision_test(200, 1000, true, 1, true, false); } -TEST(test_octomap, distance) +BOOST_AUTO_TEST_CASE(test_octomap_distance) { octomap_distance_test(200, 100, false, false); octomap_distance_test(200, 1000, false, false); } -TEST(test_octomap, distance_mesh) +BOOST_AUTO_TEST_CASE(test_octomap_distance_mesh) { octomap_distance_test(200, 100, true, true); octomap_distance_test(200, 1000, true, true); } -TEST(test_octomap, distance_mesh_octomap_box) +BOOST_AUTO_TEST_CASE(test_octomap_distance_mesh_octomap_box) { octomap_distance_test(200, 100, true, false); octomap_distance_test(200, 1000, true, false); } -TEST(test_octomap_bvh_obb, collision_obb) +BOOST_AUTO_TEST_CASE(test_octomap_bvh_obb_collision_obb) { octomap_collision_test_BVH<OBB>(5, false); octomap_collision_test_BVH<OBB>(5, true); } -TEST(test_octomap_bvh_rss_d, distance_rss) +BOOST_AUTO_TEST_CASE(test_octomap_bvh_rss_d_distance_rss) { octomap_distance_test_BVH<RSS>(5); } -TEST(test_octomap_bvh_obb_d, distance_obb) +BOOST_AUTO_TEST_CASE(test_octomap_bvh_obb_d_distance_obb) { octomap_distance_test_BVH<OBBRSS>(5); } -TEST(test_octomap_bvh_kios_d, distance_kios) +BOOST_AUTO_TEST_CASE(test_octomap_bvh_kios_d_distance_kios) { octomap_distance_test_BVH<kIOS>(5); } -int main(int argc, char** argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} - template<typename BV> void octomap_collision_test_BVH(std::size_t n, bool exhaustive) { std::vector<Vec3f> p1; std::vector<Triangle> t1; - loadOBJFile("../test/env.obj", p1, t1); + boost::filesystem::path path(TEST_RESOURCES_DIR); + loadOBJFile((path / "env.obj").string().c_str(), p1, t1); + BVHModel<BV>* m1 = new BVHModel<BV>(); boost::shared_ptr<CollisionGeometry> m1_ptr(m1); @@ -225,12 +226,12 @@ void octomap_collision_test_BVH(std::size_t n, bool exhaustive) if(exhaustive) { std::cout << cdata.result.numContacts() << " " << cdata2.result.numContacts() << std::endl; - ASSERT_TRUE(cdata.result.numContacts() == cdata2.result.numContacts()); + BOOST_CHECK(cdata.result.numContacts() == cdata2.result.numContacts()); } else { std::cout << (cdata.result.numContacts() > 0) << " " << (cdata2.result.numContacts() > 0) << std::endl; - ASSERT_TRUE((cdata.result.numContacts() > 0) == (cdata2.result.numContacts() > 0)); + BOOST_CHECK((cdata.result.numContacts() > 0) == (cdata2.result.numContacts() > 0)); } } } @@ -241,7 +242,9 @@ void octomap_distance_test_BVH(std::size_t n) { std::vector<Vec3f> p1; std::vector<Triangle> t1; - loadOBJFile("../test/env.obj", p1, t1); + boost::filesystem::path path(TEST_RESOURCES_DIR); + loadOBJFile((path / "env.obj").string().c_str(), p1, t1); + BVHModel<BV>* m1 = new BVHModel<BV>(); boost::shared_ptr<CollisionGeometry> m1_ptr(m1); @@ -286,7 +289,7 @@ void octomap_distance_test_BVH(std::size_t n) delete manager; std::cout << dist1 << " " << dist2 << std::endl; - ASSERT_TRUE(std::abs(dist1 - dist2) < 0.001); + BOOST_CHECK(std::abs(dist1 - dist2) < 0.001); } } @@ -391,8 +394,8 @@ void octomap_cost_test(double env_scale, std::size_t env_size, std::size_t num_m } - if(use_mesh) ASSERT_TRUE((cdata.result.numContacts() > 0) >= (cdata2.result.numContacts() > 0)); - else ASSERT_TRUE(cdata.result.numContacts() >= cdata2.result.numContacts()); + if(use_mesh) BOOST_CHECK((cdata.result.numContacts() > 0) >= (cdata2.result.numContacts() > 0)); + else BOOST_CHECK(cdata.result.numContacts() >= cdata2.result.numContacts()); delete manager; delete manager2; @@ -483,13 +486,13 @@ void octomap_collision_test(double env_scale, std::size_t env_size, bool exhaust std::cout << cdata.result.numContacts() << " " << cdata3.result.numContacts() << " " << cdata2.result.numContacts() << std::endl; if(exhaustive) { - if(use_mesh) ASSERT_TRUE((cdata.result.numContacts() > 0) >= (cdata2.result.numContacts() > 0)); - else ASSERT_TRUE(cdata.result.numContacts() == cdata2.result.numContacts()); + if(use_mesh) BOOST_CHECK((cdata.result.numContacts() > 0) >= (cdata2.result.numContacts() > 0)); + else BOOST_CHECK(cdata.result.numContacts() == cdata2.result.numContacts()); } else { - if(use_mesh) ASSERT_TRUE((cdata.result.numContacts() > 0) >= (cdata2.result.numContacts() > 0)); - else ASSERT_TRUE((cdata.result.numContacts() > 0) >= (cdata2.result.numContacts() > 0)); // because AABB return collision when two boxes contact + if(use_mesh) BOOST_CHECK((cdata.result.numContacts() > 0) >= (cdata2.result.numContacts() > 0)); + else BOOST_CHECK((cdata.result.numContacts() > 0) >= (cdata2.result.numContacts() > 0)); // because AABB return collision when two boxes contact } delete manager; @@ -576,9 +579,9 @@ void octomap_distance_test(double env_scale, std::size_t env_size, bool use_mesh std::cout << cdata.result.min_distance << " " << cdata3.result.min_distance << " " << cdata2.result.min_distance << std::endl; if(cdata.result.min_distance < 0) - ASSERT_TRUE(cdata2.result.min_distance <= 0); + BOOST_CHECK(cdata2.result.min_distance <= 0); else - ASSERT_TRUE(std::abs(cdata.result.min_distance - cdata2.result.min_distance) < 1e-3); + BOOST_CHECK(std::abs(cdata.result.min_distance - cdata2.result.min_distance) < 1e-3); delete manager; delete manager2; diff --git a/trunk/fcl/test/test_fcl_shape_mesh_consistency.cpp b/trunk/fcl/test/test_fcl_shape_mesh_consistency.cpp index 882002a600433d55d1217d95779a0155c7d82b96..5119b08e7663d9f09a5dc4a3b3c7f1ad53f7cb71 100644 --- a/trunk/fcl/test/test_fcl_shape_mesh_consistency.cpp +++ b/trunk/fcl/test/test_fcl_shape_mesh_consistency.cpp @@ -34,22 +34,26 @@ /** \author Jia Pan */ +#define BOOST_TEST_MODULE "FCL_SHAPE_MESH_CONSISTENCY" +#include <boost/test/unit_test.hpp> + #include "fcl/narrowphase/narrowphase.h" #include "fcl/shape/geometric_shape_to_BVH_model.h" #include "fcl/distance.h" #include "fcl/collision.h" #include "test_fcl_utility.h" -#include <gtest/gtest.h> using namespace fcl; +#define BOOST_CHECK_FALSE(p) BOOST_CHECK(!(p)) + GJKSolver_libccd solver1; GJKSolver_indep solver2; FCL_REAL extents[6] = {0, 0, 0, 10, 10, 10}; -TEST(consistency_distance, spheresphere_libccd) +BOOST_AUTO_TEST_CASE(consistency_distance_spheresphere_libccd) { Sphere s1(20); Sphere s2(20); @@ -69,15 +73,15 @@ TEST(consistency_distance, spheresphere_libccd) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver1, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); for(std::size_t i = 0; i < 10; ++i) { @@ -90,15 +94,15 @@ TEST(consistency_distance, spheresphere_libccd) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); } pose.setTranslation(Vec3f(40.1, 0, 0)); @@ -106,15 +110,15 @@ TEST(consistency_distance, spheresphere_libccd) res.clear(), res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver1, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); for(std::size_t i = 0; i < 10; ++i) @@ -128,19 +132,19 @@ TEST(consistency_distance, spheresphere_libccd) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, &solver1, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); } } -TEST(consistency_distance, boxbox_libccd) +BOOST_AUTO_TEST_CASE(consistency_distance_boxbox_libccd) { Box s1(20, 40, 50); Box s2(10, 10, 10); @@ -161,15 +165,15 @@ TEST(consistency_distance, boxbox_libccd) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver1, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); for(std::size_t i = 0; i < 10; ++i) { @@ -182,15 +186,15 @@ TEST(consistency_distance, boxbox_libccd) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, &solver1, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); } pose.setTranslation(Vec3f(15.1, 0, 0)); @@ -198,15 +202,15 @@ TEST(consistency_distance, boxbox_libccd) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver1, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); for(std::size_t i = 0; i < 10; ++i) { @@ -219,19 +223,19 @@ TEST(consistency_distance, boxbox_libccd) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, &solver1, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); } } -TEST(consistency_distance, cylindercylinder_libccd) +BOOST_AUTO_TEST_CASE(consistency_distance_cylindercylinder_libccd) { Cylinder s1(5, 10); Cylinder s2(5, 10); @@ -252,15 +256,15 @@ TEST(consistency_distance, cylindercylinder_libccd) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver1, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); for(std::size_t i = 0; i < 10; ++i) { @@ -273,15 +277,15 @@ TEST(consistency_distance, cylindercylinder_libccd) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, &solver1, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); } pose.setTranslation(Vec3f(15, 0, 0)); // libccd cannot use small value here :( @@ -289,15 +293,15 @@ TEST(consistency_distance, cylindercylinder_libccd) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver1, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); for(std::size_t i = 0; i < 10; ++i) { @@ -310,19 +314,19 @@ TEST(consistency_distance, cylindercylinder_libccd) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, &solver1, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); } } -TEST(consistency_distance, conecone_libccd) +BOOST_AUTO_TEST_CASE(consistency_distance_conecone_libccd) { Cone s1(5, 10); Cone s2(5, 10); @@ -343,14 +347,14 @@ TEST(consistency_distance, conecone_libccd) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver1, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); distance(&s1_rss, Transform3f(), &s2, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); for(std::size_t i = 0; i < 10; ++i) { @@ -363,15 +367,15 @@ TEST(consistency_distance, conecone_libccd) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, &solver1, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); } pose.setTranslation(Vec3f(15, 0, 0)); // libccd cannot use small value here :( @@ -379,15 +383,15 @@ TEST(consistency_distance, conecone_libccd) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver1, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); for(std::size_t i = 0; i < 10; ++i) { @@ -400,20 +404,20 @@ TEST(consistency_distance, conecone_libccd) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, &solver1, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver1, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); } } -TEST(consistency_distance, spheresphere_GJK) +BOOST_AUTO_TEST_CASE(consistency_distance_spheresphere_GJK) { Sphere s1(20); Sphere s2(20); @@ -433,15 +437,15 @@ TEST(consistency_distance, spheresphere_GJK) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver2, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); for(std::size_t i = 0; i < 10; ++i) @@ -455,15 +459,15 @@ TEST(consistency_distance, spheresphere_GJK) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); } pose.setTranslation(Vec3f(40.1, 0, 0)); @@ -471,15 +475,15 @@ TEST(consistency_distance, spheresphere_GJK) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver2, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 4); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 4); for(std::size_t i = 0; i < 10; ++i) @@ -493,19 +497,19 @@ TEST(consistency_distance, spheresphere_GJK) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, &solver2, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 4); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 4); } } -TEST(consistency_distance, boxbox_GJK) +BOOST_AUTO_TEST_CASE(consistency_distance_boxbox_GJK) { Box s1(20, 40, 50); Box s2(10, 10, 10); @@ -526,15 +530,15 @@ TEST(consistency_distance, boxbox_GJK) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver2, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); for(std::size_t i = 0; i < 10; ++i) { @@ -547,15 +551,15 @@ TEST(consistency_distance, boxbox_GJK) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, &solver2, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.01); } pose.setTranslation(Vec3f(15.1, 0, 0)); @@ -563,15 +567,15 @@ TEST(consistency_distance, boxbox_GJK) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver2, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); for(std::size_t i = 0; i < 10; ++i) { @@ -584,19 +588,19 @@ TEST(consistency_distance, boxbox_GJK) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, &solver2, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); } } -TEST(consistency_distance, cylindercylinder_GJK) +BOOST_AUTO_TEST_CASE(consistency_distance_cylindercylinder_GJK) { Cylinder s1(5, 10); Cylinder s2(5, 10); @@ -617,15 +621,15 @@ TEST(consistency_distance, cylindercylinder_GJK) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver2, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); for(std::size_t i = 0; i < 10; ++i) { @@ -641,21 +645,21 @@ TEST(consistency_distance, cylindercylinder_GJK) if(fabs(res1.min_distance - res.min_distance) / res.min_distance > 0.05) std::cout << "low resolution: " << res1.min_distance << " " << res.min_distance << std::endl; else - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver2, request, res1); if(fabs(res1.min_distance - res.min_distance) / res.min_distance > 0.05) std::cout << "low resolution: " << res1.min_distance << " " << res.min_distance << std::endl; else - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver2, request, res1); if(fabs(res1.min_distance - res.min_distance) / res.min_distance > 0.05) std::cout << "low resolution: " << res1.min_distance << " " << res.min_distance << std::endl; else - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); } pose.setTranslation(Vec3f(10.1, 0, 0)); @@ -663,15 +667,15 @@ TEST(consistency_distance, cylindercylinder_GJK) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver2, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); for(std::size_t i = 0; i < 10; ++i) { @@ -684,19 +688,19 @@ TEST(consistency_distance, cylindercylinder_GJK) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, &solver2, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); } } -TEST(consistency_distance, conecone_GJK) +BOOST_AUTO_TEST_CASE(consistency_distance_conecone_GJK) { Cone s1(5, 10); Cone s2(5, 10); @@ -717,15 +721,15 @@ TEST(consistency_distance, conecone_GJK) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver2, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); for(std::size_t i = 0; i < 10; ++i) { @@ -738,15 +742,15 @@ TEST(consistency_distance, conecone_GJK) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, &solver2, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 0.05); } pose.setTranslation(Vec3f(10.1, 0, 0)); @@ -754,15 +758,15 @@ TEST(consistency_distance, conecone_GJK) res.clear(); res1.clear(); distance(&s1, Transform3f(), &s2, pose, &solver2, request, res); distance(&s1_rss, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, Transform3f(), &s2_rss, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, Transform3f(), &s2, pose, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); for(std::size_t i = 0; i < 10; ++i) { @@ -775,21 +779,21 @@ TEST(consistency_distance, conecone_GJK) res.clear(); res1.clear(); distance(&s1, pose1, &s2, pose2, &solver2, request, res); distance(&s1_rss, pose1, &s2_rss, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1, pose1, &s2_rss, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); res1.clear(); distance(&s1_rss, pose1, &s2, pose2, &solver2, request, res1); - ASSERT_TRUE(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); + BOOST_CHECK(fabs(res1.min_distance - res.min_distance) / res.min_distance < 2); } } -TEST(consistency_collision, spheresphere_libccd) +BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere_libccd) { Sphere s1(20); Sphere s2(10); @@ -818,31 +822,31 @@ TEST(consistency_collision, spheresphere_libccd) // all are reasonable result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); pose.setTranslation(Vec3f(40, 0, 0)); pose_aabb.setTranslation(Vec3f(40, 0, 0)); @@ -850,31 +854,31 @@ TEST(consistency_collision, spheresphere_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); pose.setTranslation(Vec3f(30, 0, 0)); pose_aabb.setTranslation(Vec3f(30, 0, 0)); @@ -882,31 +886,31 @@ TEST(consistency_collision, spheresphere_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); pose.setTranslation(Vec3f(29.9, 0, 0)); pose_aabb.setTranslation(Vec3f(29.8, 0, 0)); // 29.9 fails, result depends on mesh precision @@ -914,31 +918,31 @@ TEST(consistency_collision, spheresphere_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); pose.setTranslation(Vec3f(-29.9, 0, 0)); @@ -947,31 +951,31 @@ TEST(consistency_collision, spheresphere_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); pose.setTranslation(Vec3f(-30, 0, 0)); pose_aabb.setTranslation(Vec3f(-30, 0, 0)); @@ -979,34 +983,34 @@ TEST(consistency_collision, spheresphere_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(consistency_collision, boxbox_libccd) +BOOST_AUTO_TEST_CASE(consistency_collision_boxbox_libccd) { Box s1(20, 40, 50); Box s2(10, 10, 10); @@ -1035,31 +1039,31 @@ TEST(consistency_collision, boxbox_libccd) // all are reasonable result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); pose.setTranslation(Vec3f(15.01, 0, 0)); pose_aabb.setTranslation(Vec3f(15.01, 0, 0)); @@ -1067,31 +1071,31 @@ TEST(consistency_collision, boxbox_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); pose.setTranslation(Vec3f(14.99, 0, 0)); pose_aabb.setTranslation(Vec3f(14.99, 0, 0)); @@ -1099,34 +1103,34 @@ TEST(consistency_collision, boxbox_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); } -TEST(consistency_collision, spherebox_libccd) +BOOST_AUTO_TEST_CASE(consistency_collision_spherebox_libccd) { Sphere s1(20); Box s2(5, 5, 5); @@ -1155,31 +1159,31 @@ TEST(consistency_collision, spherebox_libccd) // all are reasonable result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); pose.setTranslation(Vec3f(22.4, 0, 0)); pose_aabb.setTranslation(Vec3f(22.4, 0, 0)); @@ -1187,31 +1191,31 @@ TEST(consistency_collision, spherebox_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); pose.setTranslation(Vec3f(22.51, 0, 0)); pose_aabb.setTranslation(Vec3f(22.51, 0, 0)); @@ -1219,34 +1223,34 @@ TEST(consistency_collision, spherebox_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(consistency_collision, cylindercylinder_libccd) +BOOST_AUTO_TEST_CASE(consistency_collision_cylindercylinder_libccd) { Cylinder s1(5, 10); Cylinder s2(5, 10); @@ -1274,31 +1278,31 @@ TEST(consistency_collision, cylindercylinder_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); pose.setTranslation(Vec3f(10.01, 0, 0)); pose_aabb.setTranslation(Vec3f(10.01, 0, 0)); @@ -1306,34 +1310,34 @@ TEST(consistency_collision, cylindercylinder_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(consistency_collision, conecone_libccd) +BOOST_AUTO_TEST_CASE(consistency_collision_conecone_libccd) { Cone s1(5, 10); Cone s2(5, 10); @@ -1361,31 +1365,31 @@ TEST(consistency_collision, conecone_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); pose.setTranslation(Vec3f(10.1, 0, 0)); pose_aabb.setTranslation(Vec3f(10.1, 0, 0)); @@ -1393,31 +1397,31 @@ TEST(consistency_collision, conecone_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); pose.setTranslation(Vec3f(0, 0, 9.9)); pose_aabb.setTranslation(Vec3f(0, 0, 9.9)); @@ -1425,31 +1429,31 @@ TEST(consistency_collision, conecone_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); pose.setTranslation(Vec3f(0, 0, 10.1)); pose_aabb.setTranslation(Vec3f(0, 0, 10.1)); @@ -1457,37 +1461,37 @@ TEST(consistency_collision, conecone_libccd) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver1, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(consistency_collision, spheresphere_GJK) +BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere_GJK) { Sphere s1(20); Sphere s2(10); @@ -1516,31 +1520,31 @@ TEST(consistency_collision, spheresphere_GJK) // all are reasonable result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); pose.setTranslation(Vec3f(40, 0, 0)); pose_aabb.setTranslation(Vec3f(40, 0, 0)); @@ -1548,31 +1552,31 @@ TEST(consistency_collision, spheresphere_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); pose.setTranslation(Vec3f(30, 0, 0)); pose_aabb.setTranslation(Vec3f(30, 0, 0)); @@ -1580,31 +1584,31 @@ TEST(consistency_collision, spheresphere_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); pose.setTranslation(Vec3f(29.9, 0, 0)); pose_aabb.setTranslation(Vec3f(29.8, 0, 0)); // 29.9 fails, result depends on mesh precision @@ -1612,31 +1616,31 @@ TEST(consistency_collision, spheresphere_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); pose.setTranslation(Vec3f(-29.9, 0, 0)); @@ -1645,31 +1649,31 @@ TEST(consistency_collision, spheresphere_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); pose.setTranslation(Vec3f(-30, 0, 0)); pose_aabb.setTranslation(Vec3f(-30, 0, 0)); @@ -1677,34 +1681,34 @@ TEST(consistency_collision, spheresphere_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(consistency_collision, boxbox_GJK) +BOOST_AUTO_TEST_CASE(consistency_collision_boxbox_GJK) { Box s1(20, 40, 50); Box s2(10, 10, 10); @@ -1733,31 +1737,31 @@ TEST(consistency_collision, boxbox_GJK) // all are reasonable result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); pose.setTranslation(Vec3f(15.01, 0, 0)); pose_aabb.setTranslation(Vec3f(15.01, 0, 0)); @@ -1765,31 +1769,31 @@ TEST(consistency_collision, boxbox_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); pose.setTranslation(Vec3f(14.99, 0, 0)); pose_aabb.setTranslation(Vec3f(14.99, 0, 0)); @@ -1797,34 +1801,34 @@ TEST(consistency_collision, boxbox_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); } -TEST(consistency_collision, spherebox_GJK) +BOOST_AUTO_TEST_CASE(consistency_collision_spherebox_GJK) { Sphere s1(20); Box s2(5, 5, 5); @@ -1853,31 +1857,31 @@ TEST(consistency_collision, spherebox_GJK) // all are reasonable result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); pose.setTranslation(Vec3f(22.4, 0, 0)); pose_aabb.setTranslation(Vec3f(22.4, 0, 0)); @@ -1885,31 +1889,31 @@ TEST(consistency_collision, spherebox_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); pose.setTranslation(Vec3f(22.51, 0, 0)); pose_aabb.setTranslation(Vec3f(22.51, 0, 0)); @@ -1917,34 +1921,34 @@ TEST(consistency_collision, spherebox_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(consistency_collision, cylindercylinder_GJK) +BOOST_AUTO_TEST_CASE(consistency_collision_cylindercylinder_GJK) { Cylinder s1(5, 10); Cylinder s2(5, 10); @@ -1972,31 +1976,31 @@ TEST(consistency_collision, cylindercylinder_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); pose.setTranslation(Vec3f(10.01, 0, 0)); pose_aabb.setTranslation(Vec3f(10.01, 0, 0)); @@ -2004,34 +2008,34 @@ TEST(consistency_collision, cylindercylinder_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); } -TEST(consistency_collision, conecone_GJK) +BOOST_AUTO_TEST_CASE(consistency_collision_conecone_GJK) { Cone s1(5, 10); Cone s2(5, 10); @@ -2059,31 +2063,31 @@ TEST(consistency_collision, conecone_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); pose.setTranslation(Vec3f(10.1, 0, 0)); pose_aabb.setTranslation(Vec3f(10.1, 0, 0)); @@ -2091,31 +2095,31 @@ TEST(consistency_collision, conecone_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); pose.setTranslation(Vec3f(0, 0, 9.9)); pose_aabb.setTranslation(Vec3f(0, 0, 9.9)); @@ -2123,31 +2127,31 @@ TEST(consistency_collision, conecone_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_TRUE(res); + BOOST_CHECK(res); pose.setTranslation(Vec3f(0, 0, 10.1)); pose_aabb.setTranslation(Vec3f(0, 0, 10.1)); @@ -2155,41 +2159,29 @@ TEST(consistency_collision, conecone_GJK) result.clear(); res = (collide(&s1, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_aabb, pose_aabb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2_obb, pose_obb, &s1, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_aabb, pose_aabb, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1, Transform3f(), &s2_obb, pose_obb, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_aabb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s2, pose, &s1_obb, Transform3f(), &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); + BOOST_CHECK_FALSE(res); result.clear(); res = (collide(&s1_aabb, Transform3f(), &s2, pose, &solver2, request, result) > 0); - ASSERT_FALSE(res); -} - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); + BOOST_CHECK_FALSE(res); } - - - - - -