Skip to content
Snippets Groups Projects
Verified Commit 89661e05 authored by Justin Carpentier's avatar Justin Carpentier
Browse files

all: add missing #ifdef HPP_FCL_HAVE_OCTOMAP

parent aa5650d8
No related branches found
No related tags found
No related merge requests found
...@@ -47,7 +47,9 @@ add_fcl_test(test_fcl_profiling test_fcl_profiling.cpp test_fcl_utility.cpp) ...@@ -47,7 +47,9 @@ add_fcl_test(test_fcl_profiling test_fcl_profiling.cpp test_fcl_utility.cpp)
PKG_CONFIG_USE_DEPENDENCY(test_fcl_profiling assimp) PKG_CONFIG_USE_DEPENDENCY(test_fcl_profiling assimp)
add_fcl_test(test_fcl_gjk test_fcl_gjk.cpp) add_fcl_test(test_fcl_gjk test_fcl_gjk.cpp)
add_fcl_test(test_fcl_octree test_fcl_octree.cpp test_fcl_utility.cpp) if(HPP_FCL_HAVE_OCTOMAP)
add_fcl_test(test_fcl_octree test_fcl_octree.cpp test_fcl_utility.cpp)
endif(HPP_FCL_HAVE_OCTOMAP)
## Benchmark ## Benchmark
add_executable(test-benchmark benchmark.cpp test_fcl_utility.cpp) add_executable(test-benchmark benchmark.cpp test_fcl_utility.cpp)
......
...@@ -209,7 +209,8 @@ void saveOBJFile(const char* filename, std::vector<Vec3f>& points, std::vector<T ...@@ -209,7 +209,8 @@ void saveOBJFile(const char* filename, std::vector<Vec3f>& points, std::vector<T
os.close(); os.close();
} }
OcTree loadOctreeFile (const char* filename, const FCL_REAL& resolution) #ifdef HPP_FCL_HAVE_OCTOMAP
OcTree loadOctreeFile (const char* filename, const FCL_REAL& resolution)
{ {
std::ifstream file; std::ifstream file;
file.open(filename); file.open(filename);
...@@ -234,6 +235,7 @@ void saveOBJFile(const char* filename, std::vector<Vec3f>& points, std::vector<T ...@@ -234,6 +235,7 @@ void saveOBJFile(const char* filename, std::vector<Vec3f>& points, std::vector<T
octree->updateInnerOccupancy (); octree->updateInnerOccupancy ();
return hpp::fcl::OcTree (octree); return hpp::fcl::OcTree (octree);
} }
#endif
void eulerToMatrix(FCL_REAL a, FCL_REAL b, FCL_REAL c, Matrix3f& R) void eulerToMatrix(FCL_REAL a, FCL_REAL b, FCL_REAL c, Matrix3f& R)
{ {
......
...@@ -41,7 +41,10 @@ ...@@ -41,7 +41,10 @@
#include <hpp/fcl/math/transform.h> #include <hpp/fcl/math/transform.h>
#include <hpp/fcl/collision_data.h> #include <hpp/fcl/collision_data.h>
#include <hpp/fcl/collision_object.h> #include <hpp/fcl/collision_object.h>
#ifdef HPP_FCL_HAVE_OCTOMAP
#include <hpp/fcl/octree.h> #include <hpp/fcl/octree.h>
#endif
#ifdef _WIN32 #ifdef _WIN32
#define NOMINMAX // required to avoid compilation errors with Visual Studio 2010 #define NOMINMAX // required to avoid compilation errors with Visual Studio 2010
...@@ -51,9 +54,11 @@ ...@@ -51,9 +54,11 @@
#endif #endif
#ifdef HPP_FCL_HAVE_OCTOMAP
namespace octomap { namespace octomap {
typedef boost::shared_ptr<OcTree> OcTreePtr_t; typedef boost::shared_ptr<OcTree> OcTreePtr_t;
} }
#endif
namespace hpp namespace hpp
{ {
...@@ -93,7 +98,9 @@ void loadOBJFile(const char* filename, std::vector<Vec3f>& points, std::vector<T ...@@ -93,7 +98,9 @@ void loadOBJFile(const char* filename, std::vector<Vec3f>& points, std::vector<T
void saveOBJFile(const char* filename, std::vector<Vec3f>& points, std::vector<Triangle>& triangles); void saveOBJFile(const char* filename, std::vector<Vec3f>& points, std::vector<Triangle>& triangles);
fcl::OcTree loadOctreeFile (const char* filename, const FCL_REAL& resolution); #ifdef HPP_FCL_HAVE_OCTOMAP
fcl::OcTree loadOctreeFile (const char* filename, const FCL_REAL& resolution);
#endif
/// @brief Generate one random transform whose translation is constrained by extents and rotation without constraints. /// @brief Generate one random transform whose translation is constrained by extents and rotation without constraints.
/// The translation is (x, y, z), and extents[0] <= x <= extents[3], extents[1] <= y <= extents[4], extents[2] <= z <= extents[5] /// The translation is (x, y, z), and extents[0] <= x <= extents[3], extents[1] <= y <= extents[4], extents[2] <= z <= extents[5]
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment