Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
H
hpp-fcl
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Container Registry
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Guilhem Saurel
hpp-fcl
Commits
89661e05
Verified
Commit
89661e05
authored
6 years ago
by
Justin Carpentier
Browse files
Options
Downloads
Patches
Plain Diff
all: add missing #ifdef HPP_FCL_HAVE_OCTOMAP
parent
aa5650d8
No related branches found
No related tags found
No related merge requests found
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
test/CMakeLists.txt
+3
-1
3 additions, 1 deletion
test/CMakeLists.txt
test/test_fcl_utility.cpp
+3
-1
3 additions, 1 deletion
test/test_fcl_utility.cpp
test/test_fcl_utility.h
+8
-1
8 additions, 1 deletion
test/test_fcl_utility.h
with
14 additions
and
3 deletions
test/CMakeLists.txt
+
3
−
1
View file @
89661e05
...
@@ -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
)
...
...
This diff is collapsed.
Click to expand it.
test/test_fcl_utility.cpp
+
3
−
1
View file @
89661e05
...
@@ -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
)
{
{
...
...
This diff is collapsed.
Click to expand it.
test/test_fcl_utility.h
+
8
−
1
View file @
89661e05
...
@@ -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]
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
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!
Save comment
Cancel
Please
register
or
sign in
to comment