Skip to content

Commit

Permalink
Remove custom build config macros since it doesn't work for MSVC and …
Browse files Browse the repository at this point in the history
…Xcode
  • Loading branch information
jslee02 committed Aug 12, 2016
1 parent 8c63223 commit d505e4c
Show file tree
Hide file tree
Showing 15 changed files with 287 additions and 311 deletions.
23 changes: 2 additions & 21 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,27 +13,8 @@ option(FCL_ENABLE_PROFILING "Enable profiling" OFF)
option(FCL_TREAT_WARNINGS_AS_ERRORS "Treat warnings as errors" OFF)

# set the default build type
if (NOT CMAKE_BUILD_TYPE)
set(CMAKE_BUILD_TYPE Release)
endif()

# Set build type variable
set(FCL_BUILD_TYPE_RELEASE FALSE)
set(FCL_BUILD_TYPE_DEBUG FALSE)
set(FCL_BUILD_TYPE_RELWITHDEBINFO FALSE)
set(FCL_BUILD_TYPE_MINSIZEREL FALSE)

string(TOUPPER ${CMAKE_BUILD_TYPE} CMAKE_BUILD_TYPE_UPPERCASE)
if("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "RELEASE")
set(FCL_BUILD_TYPE_RELEASE TRUE)
elseif("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "DEBUG")
set(FCL_BUILD_TYPE_DEBUG TRUE)
elseif("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "RELWITHDEBINFO")
set(BUILD_TYPE_RELWITHDEBINFO TRUE)
elseif("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "MINSIZEREL")
set(BUILD_TYPE_MINSIZEREL TRUE)
else()
message(SEND_ERROR "CMAKE_BUILD_TYPE ${CMAKE_BUILD_TYPE} unknown. Valid options are: Debug | Release | RelWithDebInfo | MinSizeRel")
if (NOT MSVC AND NOT CMAKE_BUILD_TYPE)
set(CMAKE_BUILD_TYPE Release)
endif()

# This shouldn't be necessary, but there has been trouble
Expand Down
5 changes: 0 additions & 5 deletions include/fcl/config.h.in
Original file line number Diff line number Diff line change
Expand Up @@ -45,11 +45,6 @@
#cmakedefine01 FCL_HAVE_OCTOMAP
#cmakedefine01 FCL_HAVE_TINYXML

#cmakedefine01 FCL_BUILD_TYPE_DEBUG
#cmakedefine01 FCL_BUILD_TYPE_RELEASE
#cmakedefine01 FCL_BUILD_TYPE_RELWITHDEBINFO
#cmakedefine01 FCL_BUILD_TYPE_MINSIZEREL

#cmakedefine01 FCL_ENABLE_PROFILING

// Detect the compiler
Expand Down
68 changes: 34 additions & 34 deletions test/test_fcl_broadphase_collision_1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,72 +74,72 @@ struct GoogleDenseHashTable : public google::dense_hash_map<U, V, std::tr1::hash
/// check the update, only return collision or not
GTEST_TEST(FCL_BROADPHASE, test_core_bf_broad_phase_update_collision_binary)
{
#if FCL_BUILD_TYPE_DEBUG
broad_phase_update_collision_test<double>(2000, 10, 100, 1, false);
broad_phase_update_collision_test<double>(2000, 100, 100, 1, false);
#else
#ifdef NDEBUG
broad_phase_update_collision_test<double>(2000, 100, 1000, 1, false);
broad_phase_update_collision_test<double>(2000, 1000, 1000, 1, false);
#else
broad_phase_update_collision_test<double>(2000, 10, 100, 1, false);
broad_phase_update_collision_test<double>(2000, 100, 100, 1, false);
#endif
}

/// check the update, return 10 contacts
GTEST_TEST(FCL_BROADPHASE, test_core_bf_broad_phase_update_collision)
{
#if FCL_BUILD_TYPE_DEBUG
broad_phase_update_collision_test<double>(2000, 10, 100, 10, false);
broad_phase_update_collision_test<double>(2000, 100, 100, 10, false);
#else
#ifdef NDEBUG
broad_phase_update_collision_test<double>(2000, 100, 1000, 10, false);
broad_phase_update_collision_test<double>(2000, 1000, 1000, 10, false);
#else
broad_phase_update_collision_test<double>(2000, 10, 100, 10, false);
broad_phase_update_collision_test<double>(2000, 100, 100, 10, false);
#endif
}

/// check the update, exhaustive
GTEST_TEST(FCL_BROADPHASE, test_core_bf_broad_phase_update_collision_exhaustive)
{
#if FCL_BUILD_TYPE_DEBUG
broad_phase_update_collision_test<double>(2000, 10, 100, 1, true);
broad_phase_update_collision_test<double>(2000, 100, 100, 1, true);
#else
#ifdef NDEBUG
broad_phase_update_collision_test<double>(2000, 100, 1000, 1, true);
broad_phase_update_collision_test<double>(2000, 1000, 1000, 1, true);
#else
broad_phase_update_collision_test<double>(2000, 10, 100, 1, true);
broad_phase_update_collision_test<double>(2000, 100, 100, 1, true);
#endif
}

/// check broad phase update, in mesh, only return collision or not
GTEST_TEST(FCL_BROADPHASE, test_core_mesh_bf_broad_phase_update_collision_mesh_binary)
{
#if FCL_BUILD_TYPE_DEBUG
broad_phase_update_collision_test<double>(2000, 2, 4, 1, false, true);
broad_phase_update_collision_test<double>(2000, 4, 4, 1, false, true);
#else
#ifdef NDEBUG
broad_phase_update_collision_test<double>(2000, 100, 1000, 1, false, true);
broad_phase_update_collision_test<double>(2000, 1000, 1000, 1, false, true);
#else
broad_phase_update_collision_test<double>(2000, 2, 4, 1, false, true);
broad_phase_update_collision_test<double>(2000, 4, 4, 1, false, true);
#endif
}

/// check broad phase update, in mesh, return 10 contacts
GTEST_TEST(FCL_BROADPHASE, test_core_mesh_bf_broad_phase_update_collision_mesh)
{
#if FCL_BUILD_TYPE_DEBUG
broad_phase_update_collision_test<double>(200, 2, 4, 10, false, true);
broad_phase_update_collision_test<double>(200, 4, 4, 10, false, true);
#else
#ifdef NDEBUG
broad_phase_update_collision_test<double>(2000, 100, 1000, 10, false, true);
broad_phase_update_collision_test<double>(2000, 1000, 1000, 10, false, true);
#else
broad_phase_update_collision_test<double>(200, 2, 4, 10, false, true);
broad_phase_update_collision_test<double>(200, 4, 4, 10, false, true);
#endif
}

/// check broad phase update, in mesh, exhaustive
GTEST_TEST(FCL_BROADPHASE, test_core_mesh_bf_broad_phase_update_collision_mesh_exhaustive)
{
#if FCL_BUILD_TYPE_DEBUG
broad_phase_update_collision_test<double>(2000, 2, 4, 1, true, true);
broad_phase_update_collision_test<double>(2000, 4, 4, 1, true, true);
#else
#ifdef NDEBUG
broad_phase_update_collision_test<double>(2000, 100, 1000, 1, true, true);
broad_phase_update_collision_test<double>(2000, 1000, 1000, 1, true, true);
#else
broad_phase_update_collision_test<double>(2000, 2, 4, 1, true, true);
broad_phase_update_collision_test<double>(2000, 4, 4, 1, true, true);
#endif
}

Expand All @@ -157,19 +157,19 @@ void broad_phase_update_collision_test(S env_scale, std::size_t env_size, std::s

std::vector<CollisionObject<S>*> query;
if(use_mesh)
generateEnvironmentsMesh(query, env_scale, query_size);
generateEnvironmentsMesh(query, env_scale, query_size);
else
generateEnvironments(query, env_scale, query_size);
generateEnvironments(query, env_scale, query_size);

std::vector<BroadPhaseCollisionManager<S>*> managers;

managers.push_back(new NaiveCollisionManager<S>());
managers.push_back(new SSaPCollisionManager<S>());


managers.push_back(new SaPCollisionManager<S>());
managers.push_back(new IntervalTreeCollisionManager<S>());

Vector3<S> lower_limit, upper_limit;
SpatialHashingCollisionManager<S>::computeBound(env, lower_limit, upper_limit);
S cell_size = std::min(std::min((upper_limit[0] - lower_limit[0]) / 20, (upper_limit[1] - lower_limit[1]) / 20), (upper_limit[2] - lower_limit[2])/20);
Expand Down Expand Up @@ -204,7 +204,7 @@ void broad_phase_update_collision_test(S env_scale, std::size_t env_size, std::s
timers[i].stop();
ts[i].push_back(timers[i].getElapsedTime());
}

for(size_t i = 0; i < managers.size(); ++i)
{
timers[i].start();
Expand All @@ -230,7 +230,7 @@ void broad_phase_update_collision_test(S env_scale, std::size_t env_size, std::s
* AngleAxis<S>(rand_angle_y, Vector3<S>::UnitY())
* AngleAxis<S>(rand_angle_z, Vector3<S>::UnitZ()));
Vector3<S> dT(rand_trans_x, rand_trans_y, rand_trans_z);

Matrix3<S> R = env[i]->getRotation();
Vector3<S> T = env[i]->getTranslation();
env[i]->setTransform(dR * R, dR * T + dT);
Expand Down Expand Up @@ -275,7 +275,7 @@ void broad_phase_update_collision_test(S env_scale, std::size_t env_size, std::s
std::vector<bool> self_res(managers.size());
for(size_t i = 0; i < self_res.size(); ++i)
self_res[i] = (self_data[i].result.numContacts() > 0);

for(size_t i = 1; i < self_res.size(); ++i)
EXPECT_TRUE(self_res[0] == self_res[i]);

Expand Down Expand Up @@ -305,7 +305,7 @@ void broad_phase_update_collision_test(S env_scale, std::size_t env_size, std::s
// for(size_t j = 0; j < managers.size(); ++j)
// std::cout << query_data[j].result.numContacts() << " ";
// std::cout << std::endl;

if(exhaustive)
{
for(size_t j = 1; j < managers.size(); ++j)
Expand All @@ -332,7 +332,7 @@ void broad_phase_update_collision_test(S env_scale, std::size_t env_size, std::s

for(size_t i = 0; i < managers.size(); ++i)
delete managers[i];


std::cout.setf(std::ios_base::left, std::ios_base::adjustfield);
size_t w = 7;
Expand Down
88 changes: 44 additions & 44 deletions test/test_fcl_broadphase_collision_2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,23 +74,7 @@ struct GoogleDenseHashTable : public google::dense_hash_map<U, V, std::tr1::hash
/// check broad phase collision for empty collision object set and queries
GTEST_TEST(FCL_BROADPHASE, test_core_bf_broad_phase_collision_empty)
{
#if FCL_BUILD_TYPE_DEBUG
broad_phase_collision_test<double>(2000, 0, 0, 10, false, false);
broad_phase_collision_test<double>(2000, 0, 5, 10, false, false);
broad_phase_collision_test<double>(2000, 2, 0, 10, false, false);

broad_phase_collision_test<double>(2000, 0, 0, 10, false, true);
broad_phase_collision_test<double>(2000, 0, 5, 10, false, true);
broad_phase_collision_test<double>(2000, 2, 0, 10, false, true);

broad_phase_collision_test<double>(2000, 0, 0, 10, true, false);
broad_phase_collision_test<double>(2000, 0, 5, 10, true, false);
broad_phase_collision_test<double>(2000, 2, 0, 10, true, false);

broad_phase_collision_test<double>(2000, 0, 0, 10, true, true);
broad_phase_collision_test<double>(2000, 0, 5, 10, true, true);
broad_phase_collision_test<double>(2000, 2, 0, 10, true, true);
#else
#ifdef NDEBUG
broad_phase_collision_test<double>(2000, 0, 0, 10, false, false);
broad_phase_collision_test<double>(2000, 0, 1000, 10, false, false);
broad_phase_collision_test<double>(2000, 100, 0, 10, false, false);
Expand All @@ -106,70 +90,86 @@ GTEST_TEST(FCL_BROADPHASE, test_core_bf_broad_phase_collision_empty)
broad_phase_collision_test<double>(2000, 0, 0, 10, true, true);
broad_phase_collision_test<double>(2000, 0, 1000, 10, true, true);
broad_phase_collision_test<double>(2000, 100, 0, 10, true, true);
#else
broad_phase_collision_test<double>(2000, 0, 0, 10, false, false);
broad_phase_collision_test<double>(2000, 0, 5, 10, false, false);
broad_phase_collision_test<double>(2000, 2, 0, 10, false, false);

broad_phase_collision_test<double>(2000, 0, 0, 10, false, true);
broad_phase_collision_test<double>(2000, 0, 5, 10, false, true);
broad_phase_collision_test<double>(2000, 2, 0, 10, false, true);

broad_phase_collision_test<double>(2000, 0, 0, 10, true, false);
broad_phase_collision_test<double>(2000, 0, 5, 10, true, false);
broad_phase_collision_test<double>(2000, 2, 0, 10, true, false);

broad_phase_collision_test<double>(2000, 0, 0, 10, true, true);
broad_phase_collision_test<double>(2000, 0, 5, 10, true, true);
broad_phase_collision_test<double>(2000, 2, 0, 10, true, true);
#endif
}

/// check broad phase collision and self collision, only return collision or not
GTEST_TEST(FCL_BROADPHASE, test_core_bf_broad_phase_collision_binary)
{
#if FCL_BUILD_TYPE_DEBUG
broad_phase_collision_test<double>(2000, 10, 100, 1, false);
broad_phase_collision_test<double>(2000, 100, 100, 1, false);
broad_phase_collision_test<double>(2000, 10, 100, 1, true);
broad_phase_collision_test<double>(2000, 100, 100, 1, true);
#else
#ifdef NDEBUG
broad_phase_collision_test<double>(2000, 100, 1000, 1, false);
broad_phase_collision_test<double>(2000, 1000, 1000, 1, false);
broad_phase_collision_test<double>(2000, 100, 1000, 1, true);
broad_phase_collision_test<double>(2000, 1000, 1000, 1, true);
#else
broad_phase_collision_test<double>(2000, 10, 100, 1, false);
broad_phase_collision_test<double>(2000, 100, 100, 1, false);
broad_phase_collision_test<double>(2000, 10, 100, 1, true);
broad_phase_collision_test<double>(2000, 100, 100, 1, true);
#endif
}

/// check broad phase collision and self collision, return 10 contacts
GTEST_TEST(FCL_BROADPHASE, test_core_bf_broad_phase_collision)
{
#if FCL_BUILD_TYPE_DEBUG
broad_phase_collision_test<double>(2000, 10, 100, 10, false);
broad_phase_collision_test<double>(2000, 100, 100, 10, false);
#else
#ifdef NDEBUG
broad_phase_collision_test<double>(2000, 100, 1000, 10, false);
broad_phase_collision_test<double>(2000, 1000, 1000, 10, false);
#else
broad_phase_collision_test<double>(2000, 10, 100, 10, false);
broad_phase_collision_test<double>(2000, 100, 100, 10, false);
#endif
}

/// check broad phase collision and self collision, return only collision or not, in mesh
GTEST_TEST(FCL_BROADPHASE, test_core_mesh_bf_broad_phase_collision_mesh_binary)
{
#if FCL_BUILD_TYPE_DEBUG
broad_phase_collision_test<double>(2000, 2, 5, 1, false, true);
broad_phase_collision_test<double>(2000, 5, 5, 1, false, true);
#else
#ifdef NDEBUG
broad_phase_collision_test<double>(2000, 100, 1000, 1, false, true);
broad_phase_collision_test<double>(2000, 1000, 1000, 1, false, true);
#else
broad_phase_collision_test<double>(2000, 2, 5, 1, false, true);
broad_phase_collision_test<double>(2000, 5, 5, 1, false, true);
#endif
}

/// check broad phase collision and self collision, return 10 contacts, in mesh
GTEST_TEST(FCL_BROADPHASE, test_core_mesh_bf_broad_phase_collision_mesh)
{
#if FCL_BUILD_TYPE_DEBUG
broad_phase_collision_test<double>(2000, 2, 5, 10, false, true);
broad_phase_collision_test<double>(2000, 5, 5, 10, false, true);
#else
#ifdef NDEBUG
broad_phase_collision_test<double>(2000, 100, 1000, 10, false, true);
broad_phase_collision_test<double>(2000, 1000, 1000, 10, false, true);
#else
broad_phase_collision_test<double>(2000, 2, 5, 10, false, true);
broad_phase_collision_test<double>(2000, 5, 5, 10, false, true);
#endif
}

/// check broad phase collision and self collision, exhaustive, in mesh
GTEST_TEST(FCL_BROADPHASE, test_core_mesh_bf_broad_phase_collision_mesh_exhaustive)
{
#if FCL_BUILD_TYPE_DEBUG
broad_phase_collision_test<double>(2000, 2, 5, 1, true, true);
broad_phase_collision_test<double>(2000, 5, 5, 1, true, true);
#else
#ifdef NDEBUG
broad_phase_collision_test<double>(2000, 100, 1000, 1, true, true);
broad_phase_collision_test<double>(2000, 1000, 1000, 1, true, true);
#else
broad_phase_collision_test<double>(2000, 2, 5, 1, true, true);
broad_phase_collision_test<double>(2000, 5, 5, 1, true, true);
#endif
}

Expand All @@ -192,12 +192,12 @@ void broad_phase_collision_test(S env_scale, std::size_t env_size, std::size_t q
generateEnvironments(query, env_scale, query_size);

std::vector<BroadPhaseCollisionManager<S>*> managers;

managers.push_back(new NaiveCollisionManager<S>());
managers.push_back(new SSaPCollisionManager<S>());
managers.push_back(new SaPCollisionManager<S>());
managers.push_back(new IntervalTreeCollisionManager<S>());

Vector3<S> lower_limit, upper_limit;
SpatialHashingCollisionManager<S>::computeBound(env, lower_limit, upper_limit);
// S ncell_per_axis = std::pow((S)env_size / 10, 1 / 3.0);
Expand Down Expand Up @@ -273,7 +273,7 @@ void broad_phase_collision_test(S env_scale, std::size_t env_size, std::size_t q
std::vector<bool> self_res(managers.size());
for(size_t i = 0; i < self_res.size(); ++i)
self_res[i] = (self_data[i].result.numContacts() > 0);

for(size_t i = 1; i < self_res.size(); ++i)
EXPECT_TRUE(self_res[0] == self_res[i]);

Expand Down Expand Up @@ -303,7 +303,7 @@ void broad_phase_collision_test(S env_scale, std::size_t env_size, std::size_t q
// for(size_t j = 0; j < managers.size(); ++j)
// std::cout << query_data[j].result.numContacts() << " ";
// std::cout << std::endl;

if(exhaustive)
{
for(size_t j = 1; j < managers.size(); ++j)
Expand All @@ -328,7 +328,7 @@ void broad_phase_collision_test(S env_scale, std::size_t env_size, std::size_t q
delete query[i];

for(size_t i = 0; i < managers.size(); ++i)
delete managers[i];
delete managers[i];

std::cout.setf(std::ios_base::left, std::ios_base::adjustfield);
size_t w = 7;
Expand Down
Loading

0 comments on commit d505e4c

Please sign in to comment.