Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
Guilhem Saurel
hpp-fcl
Commits
89661e05
Verified
Commit
89661e05
authored
Mar 04, 2019
by
Justin Carpentier
Browse files
all: add missing #ifdef HPP_FCL_HAVE_OCTOMAP
parent
aa5650d8
Changes
3
Hide whitespace changes
Inline
Side-by-side
test/CMakeLists.txt
View file @
89661e05
...
...
@@ -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
)
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
add_executable
(
test-benchmark benchmark.cpp test_fcl_utility.cpp
)
...
...
test/test_fcl_utility.cpp
View file @
89661e05
...
...
@@ -209,7 +209,8 @@ void saveOBJFile(const char* filename, std::vector<Vec3f>& points, std::vector<T
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
;
file
.
open
(
filename
);
...
...
@@ -234,6 +235,7 @@ void saveOBJFile(const char* filename, std::vector<Vec3f>& points, std::vector<T
octree
->
updateInnerOccupancy
();
return
hpp
::
fcl
::
OcTree
(
octree
);
}
#endif
void
eulerToMatrix
(
FCL_REAL
a
,
FCL_REAL
b
,
FCL_REAL
c
,
Matrix3f
&
R
)
{
...
...
test/test_fcl_utility.h
View file @
89661e05
...
...
@@ -41,7 +41,10 @@
#include
<hpp/fcl/math/transform.h>
#include
<hpp/fcl/collision_data.h>
#include
<hpp/fcl/collision_object.h>
#ifdef HPP_FCL_HAVE_OCTOMAP
#include
<hpp/fcl/octree.h>
#endif
#ifdef _WIN32
#define NOMINMAX // required to avoid compilation errors with Visual Studio 2010
...
...
@@ -51,9 +54,11 @@
#endif
#ifdef HPP_FCL_HAVE_OCTOMAP
namespace
octomap
{
typedef
boost
::
shared_ptr
<
OcTree
>
OcTreePtr_t
;
}
#endif
namespace
hpp
{
...
...
@@ -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
);
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.
/// The translation is (x, y, z), and extents[0] <= x <= extents[3], extents[1] <= y <= extents[4], extents[2] <= z <= extents[5]
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment