diff --git a/CMakeLists.txt b/CMakeLists.txt index b04fce14514c935744b89b95a6fcb9dbf72d6db4..a74a5c0c22f4d1234a21066ea4140a18124c3586 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -7,14 +7,14 @@ if (NOT CMAKE_BUILD_TYPE) endif() # Set build type variable -set(BUILD_TYPE_RELEASE FALSE) -set(BUILD_TYPE_DEBUG FALSE) +set(FCL_BUILD_TYPE_RELEASE FALSE) +set(FCL_BUILD_TYPE_DEBUG FALSE) string(TOUPPER ${CMAKE_BUILD_TYPE} CMAKE_BUILD_TYPE_UPPERCASE) if("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "RELEASE") - set(BUILD_TYPE_RELEASE TRUE) + set(FCL_BUILD_TYPE_RELEASE TRUE) elseif("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "DEBUG") - set(BUILD_TYPE_DEBUG TRUE) + set(FCL_BUILD_TYPE_DEBUG TRUE) else() message(STATUS "CMAKE_BUILD_TYPE ${CMAKE_BUILD_TYPE} unknown. Valid options are: Debug Release") endif() diff --git a/include/fcl/config.h.in b/include/fcl/config.h.in index dc723a1ec005dbc51afabf717fe5ad8239b45967..1ef93715aa88d2fc852e5843972640be5125b214 100644 --- a/include/fcl/config.h.in +++ b/include/fcl/config.h.in @@ -45,7 +45,7 @@ #cmakedefine01 FCL_HAVE_FLANN #cmakedefine01 FCL_HAVE_TINYXML -#cmakedefine01 BUILD_TYPE_DEBUG -#cmakedefine01 BUILD_TYPE_RELEASE +#cmakedefine01 FCL_BUILD_TYPE_DEBUG +#cmakedefine01 FCL_BUILD_TYPE_RELEASE #endif diff --git a/test/test_fcl_broadphase.cpp b/test/test_fcl_broadphase.cpp index fe0f483b583f83c3f8cf0d784cfcbbeb273eee0a..55382ade8b5a159883e0e1f63e8acbcd0d93a4f1 100644 --- a/test/test_fcl_broadphase.cpp +++ b/test/test_fcl_broadphase.cpp @@ -152,7 +152,7 @@ BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_self_distance) /// check broad phase collision and self collision, only return collision or not BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_collision_binary) { -#ifdef BUILD_TYPE_DEBUG +#ifdef FCL_BUILD_TYPE_DEBUG broad_phase_collision_test(2000, 10, 100, 1, false); broad_phase_collision_test(2000, 100, 100, 1, false); broad_phase_collision_test(2000, 10, 100, 1, true); @@ -182,7 +182,7 @@ BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_update_collision_mesh_binary) /// check broad phase update, in mesh, return 10 contacts BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_update_collision_mesh) { -#ifdef BUILD_TYPE_DEBUG +#ifdef FCL_BUILD_TYPE_DEBUG broad_phase_update_collision_test(200, 10, 100, 10, false, true); broad_phase_update_collision_test(200, 100, 100, 10, false, true); #else @@ -194,7 +194,7 @@ BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_update_collision_mesh) /// check broad phase update, in mesh, exhaustive BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_update_collision_mesh_exhaustive) { -#ifdef BUILD_TYPE_DEBUG +#ifdef FCL_BUILD_TYPE_DEBUG broad_phase_update_collision_test(2000, 10, 100, 1, true, true); broad_phase_update_collision_test(2000, 100, 100, 1, true, true); #else @@ -206,7 +206,7 @@ BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_update_collision_mesh_exhaust /// check broad phase distance BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_distance_mesh) { -#ifdef BUILD_TYPE_DEBUG +#ifdef FCL_BUILD_TYPE_DEBUG broad_phase_distance_test(200, 10, 10, true); broad_phase_distance_test(200, 100, 10, true); broad_phase_distance_test(2000, 10, 10, true); @@ -230,7 +230,7 @@ BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_self_distance_mesh) /// check broad phase collision and self collision, return only collision or not, in mesh BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_collision_mesh_binary) { -#ifdef BUILD_TYPE_DEBUG +#ifdef FCL_BUILD_TYPE_DEBUG broad_phase_collision_test(2000, 10, 100, 1, false, true); broad_phase_collision_test(2000, 100, 100, 1, false, true); #else @@ -242,7 +242,7 @@ BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_collision_mesh_binary) /// check broad phase collision and self collision, return 10 contacts, in mesh BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_collision_mesh) { -#ifdef BUILD_TYPE_DEBUG +#ifdef FCL_BUILD_TYPE_DEBUG broad_phase_collision_test(2000, 10, 100, 10, false, true); broad_phase_collision_test(2000, 100, 100, 10, false, true); #else @@ -254,7 +254,7 @@ BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_collision_mesh) /// check broad phase collision and self collision, exhaustive, in mesh BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_collision_mesh_exhaustive) { -#ifdef BUILD_TYPE_DEBUG +#ifdef FCL_BUILD_TYPE_DEBUG broad_phase_collision_test(2000, 10, 100, 1, true, true); broad_phase_collision_test(2000, 100, 100, 1, true, true); #else diff --git a/test/test_fcl_octomap.cpp b/test/test_fcl_octomap.cpp index 4b097307564a28d2cbc7f30c89c39e25da925a5e..6b964b26ffff3bec92c58bfe10387f235f87eb40 100644 --- a/test/test_fcl_octomap.cpp +++ b/test/test_fcl_octomap.cpp @@ -118,7 +118,7 @@ BOOST_AUTO_TEST_CASE(test_octomap_collision) BOOST_AUTO_TEST_CASE(test_octomap_collision_mesh) { -#ifdef BUILD_TYPE_DEBUG +#ifdef FCL_BUILD_TYPE_DEBUG octomap_collision_test(200, 10, false, 10, true, true); octomap_collision_test(200, 100, false, 10, true, true); octomap_collision_test(200, 10, true, 1, true, true); @@ -133,7 +133,7 @@ BOOST_AUTO_TEST_CASE(test_octomap_collision_mesh) BOOST_AUTO_TEST_CASE(test_octomap_collision_mesh_octomap_box) { -#ifdef BUILD_TYPE_DEBUG +#ifdef FCL_BUILD_TYPE_DEBUG octomap_collision_test(200, 10, false, 10, true, false); octomap_collision_test(200, 100, false, 10, true, false); octomap_collision_test(200, 10, true, 1, true, false); @@ -154,7 +154,7 @@ BOOST_AUTO_TEST_CASE(test_octomap_distance) BOOST_AUTO_TEST_CASE(test_octomap_distance_mesh) { -#ifdef BUILD_TYPE_DEBUG +#ifdef FCL_BUILD_TYPE_DEBUG octomap_distance_test(200, 5, true, true); octomap_distance_test(200, 50, true, true); #else @@ -165,7 +165,7 @@ BOOST_AUTO_TEST_CASE(test_octomap_distance_mesh) BOOST_AUTO_TEST_CASE(test_octomap_distance_mesh_octomap_box) { -#ifdef BUILD_TYPE_DEBUG +#ifdef FCL_BUILD_TYPE_DEBUG octomap_distance_test(200, 10, true, false); octomap_distance_test(200, 100, true, false); #else @@ -192,7 +192,7 @@ BOOST_AUTO_TEST_CASE(test_octomap_bvh_obb_d_distance_obb) BOOST_AUTO_TEST_CASE(test_octomap_bvh_kios_d_distance_kios) { -#ifdef BUILD_TYPE_DEBUG +#ifdef FCL_BUILD_TYPE_DEBUG octomap_distance_test_BVH<kIOS>(2); #else octomap_distance_test_BVH<kIOS>(5);