diff --git a/.appveyor.yml b/.appveyor.yml index d74414cb3..3c9bfb16c 100644 --- a/.appveyor.yml +++ b/.appveyor.yml @@ -14,8 +14,6 @@ platform: x64 environment: CTEST_OUTPUT_ON_FAILURE: 1 - BOOST_ROOT: C:\Libraries\boost_1_59_0 - BOOST_LIBRARYDIR: C:\Libraries\boost_1_59_0\lib64-msvc-14.0 cache: - C:\Program Files\libccd @@ -36,7 +34,7 @@ before_build: - cmd: set - cmd: mkdir build - cmd: cd build - - cmd: cmake -G "Visual Studio 14 2015 Win64" -DCMAKE_BUILD_TYPE=%Configuration% -DBOOST_ROOT="%BOOST_ROOT%" -DBOOST_LIBRARYDIR="%BOOST_LIBRARYDIR%" -DCCD_INCLUDE_DIRS="C:\Program Files\libccd\include" -DCCD_LIBRARY="C:\Program Files\libccd\lib\ccd.lib" .. + - cmd: cmake -G "Visual Studio 14 2015 Win64" -DCMAKE_BUILD_TYPE=%Configuration% -DCCD_INCLUDE_DIRS="C:\Program Files\libccd\include" -DCCD_LIBRARY="C:\Program Files\libccd\lib\ccd.lib" .. build: project: C:\projects\fcl\build\fcl.sln diff --git a/CHANGELOG.md b/CHANGELOG.md index 1cebc6f7c..0964c8810 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -2,7 +2,7 @@ ### FCL 0.6.0 (2016-XX-XX) -* Removed Boost Test and replaced with Google Test: [#146](https://github.com/flexible-collision-library/fcl/pull/146), [#140](https://github.com/flexible-collision-library/fcl/pull/140) +* Removed dependency on boost: [#148](https://github.com/flexible-collision-library/fcl/pull/148), [#147](https://github.com/flexible-collision-library/fcl/pull/147), [#146](https://github.com/flexible-collision-library/fcl/pull/146), [#140](https://github.com/flexible-collision-library/fcl/pull/140) ### FCL 0.5.0 (2016-07-19) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9ea703a67..376090e84 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -164,8 +164,7 @@ configure_file( add_custom_target(uninstall "${CMAKE_COMMAND}" -P "${CMAKE_CURRENT_BINARY_DIR}/CMakeModules/cmake_uninstall.cmake") -find_package(Boost COMPONENTS filesystem system) -option(FCL_BUILD_TESTS "Build FCL tests" ${Boost_FOUND}) +option(FCL_BUILD_TESTS "Build FCL tests" ON) if(FCL_BUILD_TESTS) enable_testing() add_subdirectory(test) diff --git a/INSTALL b/INSTALL index 85759aa8c..bc618c4b6 100644 --- a/INSTALL +++ b/INSTALL @@ -2,11 +2,10 @@ Dependencies: ============ - - Boost (thread, date_time, unit_test_framework, filesystem) - libccd (available at http://libccd.danfis.cz/) - octomap (optional dependency, available at http://octomap.github.com) -Boost and libccd are mandatory dependencies. If octomap is not found, +libccd is the only mandatory dependency. If octomap is not found, collision detection with octrees will not be possible. For installation, CMake will also be needed (http://cmake.org). diff --git a/README.md b/README.md index 156686704..b815a641e 100644 --- a/README.md +++ b/README.md @@ -31,8 +31,7 @@ FCL has the following features ## Installation -Before compiling FCL, please make libccd (for collision checking between convex objects and is available here https://github.com/danfis/libccd) is installed. For libccd, make sure to compile from github version instead of the zip file from the webpage, because one bug fixing is not included in the zipped version. To compile -the unit tests, Boost also needs to be to installed. +Before compiling FCL, please make libccd (for collision checking between convex objects and is available here https://github.com/danfis/libccd) is installed. For libccd, make sure to compile from github version instead of the zip file from the webpage, because one bug fixing is not included in the zipped version. Some optional libraries need to be installed for some optional capability of FCL. For octree collision, please install the octomap library from http://octomap.github.com. diff --git a/ci/install_osx.sh b/ci/install_osx.sh index 1b1a61070..9e8854374 100755 --- a/ci/install_osx.sh +++ b/ci/install_osx.sh @@ -2,5 +2,4 @@ brew tap homebrew/science brew install git brew install cmake -brew install boost brew install libccd diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 5ce1f77fc..7c7504e3c 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -11,8 +11,7 @@ set_target_properties(${PROJECT_NAME} PROPERTIES target_link_libraries(${PROJECT_NAME} PUBLIC ${OCTOMAP_LIBRARIES} - PRIVATE ${CCD_LIBRARIES} - PRIVATE ${Boost_LIBRARIES}) + PRIVATE ${CCD_LIBRARIES}) target_include_directories(${PROJECT_NAME} INTERFACE $ diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 377fa51dc..01aabdc81 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -59,13 +59,7 @@ macro(add_fcl_test test_file_name) # Get the name (i.e. bla.cpp => bla) get_filename_component(test_name ${ARGV} NAME_WE) add_executable(${test_name} ${ARGV}) - target_link_libraries(${test_name} - fcl - test_fcl_utility - gtest - ${Boost_FILESYSTEM_LIBRARY} # Boost libraries should be removed - ${Boost_SYSTEM_LIBRARY} - ) + target_link_libraries(${test_name} fcl test_fcl_utility gtest) add_test(${test_name} ${EXECUTABLE_OUTPUT_PATH}/${test_name}) endmacro(add_fcl_test) @@ -81,12 +75,6 @@ configure_file("${TEST_RESOURCES_SRC_DIR}/config.h.in" "${TEST_RESOURCES_BIN_DIR include_directories(.) include_directories("${CMAKE_CURRENT_BINARY_DIR}") -include_directories(${Boost_INCLUDE_DIR}) - -if(MSVC) - add_definitions(-DBOOST_ALL_NO_LIB) -endif() -add_definitions(-DBOOST_TEST_DYN_LINK) # Build all the tests foreach(test ${tests}) diff --git a/test/test_fcl_collision.cpp b/test/test_fcl_collision.cpp index 330003fbe..804aa3cbf 100644 --- a/test/test_fcl_collision.cpp +++ b/test/test_fcl_collision.cpp @@ -46,7 +46,6 @@ #include "fcl/narrowphase/narrowphase.h" #include "test_fcl_utility.h" #include "fcl_resources/config.h" -#include using namespace fcl; @@ -241,10 +240,9 @@ GTEST_TEST(FCL_COLLISION, mesh_mesh) { std::vector p1, p2; std::vector t1, 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); + loadOBJFile(TEST_RESOURCES_DIR"/env.obj", p1, t1); + loadOBJFile(TEST_RESOURCES_DIR"/rob.obj", p2, t2); std::vector transforms; FCL_REAL extents[] = {-3000, -3000, 0, 3000, 3000, 3000}; diff --git a/test/test_fcl_distance.cpp b/test/test_fcl_distance.cpp index af1272022..3306adbe2 100644 --- a/test/test_fcl_distance.cpp +++ b/test/test_fcl_distance.cpp @@ -42,7 +42,6 @@ #include "fcl/collision_node.h" #include "test_fcl_utility.h" #include "fcl_resources/config.h" -#include using namespace fcl; @@ -83,9 +82,9 @@ GTEST_TEST(FCL_DISTANCE, mesh_distance) { std::vector p1, p2; std::vector t1, 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); + + loadOBJFile(TEST_RESOURCES_DIR"/env.obj", p1, t1); + loadOBJFile(TEST_RESOURCES_DIR"/rob.obj", p2, t2); std::vector transforms; // t0 FCL_REAL extents[] = {-3000, -3000, 0, 3000, 3000, 3000}; diff --git a/test/test_fcl_frontlist.cpp b/test/test_fcl_frontlist.cpp index d484b2ee2..b53ed1b54 100644 --- a/test/test_fcl_frontlist.cpp +++ b/test/test_fcl_frontlist.cpp @@ -43,7 +43,6 @@ #include "test_fcl_utility.h" #include "fcl_resources/config.h" -#include using namespace fcl; @@ -71,9 +70,9 @@ GTEST_TEST(FCL_FRONT_LIST, front_list) { std::vector p1, p2; std::vector t1, 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); + + loadOBJFile(TEST_RESOURCES_DIR"/env.obj", p1, t1); + loadOBJFile(TEST_RESOURCES_DIR"/rob.obj", p2, t2); std::vector transforms; // t0 std::vector transforms2; // t1 diff --git a/test/test_fcl_octomap.cpp b/test/test_fcl_octomap.cpp index c2fa9a5d3..ff6fbb557 100644 --- a/test/test_fcl_octomap.cpp +++ b/test/test_fcl_octomap.cpp @@ -46,7 +46,6 @@ #include "fcl/math/transform.h" #include "test_fcl_utility.h" #include "fcl_resources/config.h" -#include using namespace fcl; @@ -215,8 +214,8 @@ void octomap_collision_test_BVH(std::size_t n, bool exhaustive) { std::vector p1; std::vector t1; - boost::filesystem::path path(TEST_RESOURCES_DIR); - loadOBJFile((path / "env.obj").string().c_str(), p1, t1); + + loadOBJFile(TEST_RESOURCES_DIR"/env.obj", p1, t1); BVHModel* m1 = new BVHModel(); std::shared_ptr m1_ptr(m1); @@ -281,8 +280,8 @@ void octomap_distance_test_BVH(std::size_t n) { std::vector p1; std::vector t1; - boost::filesystem::path path(TEST_RESOURCES_DIR); - loadOBJFile((path / "env.obj").string().c_str(), p1, t1); + + loadOBJFile(TEST_RESOURCES_DIR"/env.obj", p1, t1); BVHModel* m1 = new BVHModel(); std::shared_ptr m1_ptr(m1); diff --git a/test/test_fcl_simple.cpp b/test/test_fcl_simple.cpp index ee7045868..88b0b5c7a 100644 --- a/test/test_fcl_simple.cpp +++ b/test/test_fcl_simple.cpp @@ -39,7 +39,6 @@ #include "fcl/collision.h" #include "fcl/BVH/BVH_model.h" #include "fcl_resources/config.h" -#include #include #include "fcl/math/vec_nf.h" #include "fcl/math/sampling.h"