test/octree.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, CNRS-LAAS.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
37 #define BOOST_TEST_MODULE FCL_OCTREE
38 #include <fstream>
39 #include <boost/test/included/unit_test.hpp>
40 #include <boost/filesystem.hpp>
41 
42 #include <hpp/fcl/BVH/BVH_model.h>
43 #include <hpp/fcl/collision.h>
44 #include <hpp/fcl/distance.h>
47 
48 #include "utility.h"
49 #include "fcl_resources/config.h"
50 
51 namespace utf = boost::unit_test::framework;
52 
53 using hpp::fcl::BVHModel;
57 using hpp::fcl::FCL_REAL;
58 using hpp::fcl::OBBRSS;
59 using hpp::fcl::OcTree;
61 using hpp::fcl::Triangle;
62 using hpp::fcl::Vec3f;
63 
64 void makeMesh(const std::vector<Vec3f>& vertices,
65  const std::vector<Triangle>& triangles, BVHModel<OBBRSS>& model) {
67  model.bv_splitter.reset(new BVSplitter<OBBRSS>(split_method));
68  model.bv_splitter.reset(new BVSplitter<OBBRSS>(split_method));
69 
70  model.beginModel();
71  model.addSubModel(vertices, triangles);
72  model.endModel();
73 }
74 
76  const FCL_REAL& resolution) {
77  Vec3f m(mesh.aabb_local.min_);
78  Vec3f M(mesh.aabb_local.max_);
79  hpp::fcl::Box box(resolution, resolution, resolution);
81  1);
82  CollisionResult result;
83  Transform3f tfBox;
85 
86  for (FCL_REAL x = resolution * floor(m[0] / resolution); x <= M[0];
87  x += resolution) {
88  for (FCL_REAL y = resolution * floor(m[1] / resolution); y <= M[1];
89  y += resolution) {
90  for (FCL_REAL z = resolution * floor(m[2] / resolution); z <= M[2];
91  z += resolution) {
92  Vec3f center(x + .5 * resolution, y + .5 * resolution,
93  z + .5 * resolution);
94  tfBox.setTranslation(center);
95  hpp::fcl::collide(&box, tfBox, &mesh, Transform3f(), request, result);
96  if (result.isCollision()) {
97  octomap::point3d p((float)center[0], (float)center[1],
98  (float)center[2]);
99  octree->updateNode(p, true);
100  result.clear();
101  }
102  }
103  }
104  }
105 
106  octree->updateInnerOccupancy();
107  octree->writeBinary("./env.octree");
108  return OcTree(octree);
109 }
110 
112  Eigen::IOFormat tuple(Eigen::FullPrecision, Eigen::DontAlignCols, "", ", ",
113  "", "", "(", ")");
114  FCL_REAL resolution(10.);
115  std::vector<Vec3f> pRob, pEnv;
116  std::vector<Triangle> tRob, tEnv;
117  boost::filesystem::path path(TEST_RESOURCES_DIR);
118  loadOBJFile((path / "rob.obj").string().c_str(), pRob, tRob);
119  loadOBJFile((path / "env.obj").string().c_str(), pEnv, tEnv);
120 
121  BVHModel<OBBRSS> robMesh, envMesh;
122  // Build meshes with robot and environment
123  makeMesh(pRob, tRob, robMesh);
124  makeMesh(pEnv, tEnv, envMesh);
125  // Build octomap with environment
126  envMesh.computeLocalAABB();
127  // Load octree built from envMesh by makeOctree(envMesh, resolution)
128  OcTree envOctree(
129  hpp::fcl::loadOctreeFile((path / "env.octree").string(), resolution));
130 
131  std::cout << "Finished loading octree." << std::endl;
132 
133  std::vector<Transform3f> transforms;
134  FCL_REAL extents[] = {-2000, -2000, 0, 2000, 2000, 2000};
135 #ifndef NDEBUG // if debug mode
136  std::size_t N = 100;
137 #else
138  std::size_t N = 10000;
139 #endif
140  N = hpp::fcl::getNbRun(utf::master_test_suite().argc,
141  utf::master_test_suite().argv, N);
142 
143  generateRandomTransforms(extents, transforms, 2 * N);
144 
146  1);
147  for (std::size_t i = 0; i < N; ++i) {
148  CollisionResult resultMesh;
149  CollisionResult resultOctree;
150  Transform3f tf1(transforms[2 * i]);
151  Transform3f tf2(transforms[2 * i + 1]);
152  ;
153  // Test collision between meshes with random transform for robot.
154  hpp::fcl::collide(&robMesh, tf1, &envMesh, tf2, request, resultMesh);
155  // Test collision between mesh and octree for the same transform.
156  hpp::fcl::collide(&robMesh, tf1, &envOctree, tf2, request, resultOctree);
157  bool resMesh(resultMesh.isCollision());
158  bool resOctree(resultOctree.isCollision());
159  BOOST_CHECK(!resMesh || resOctree);
160  if (!resMesh && resOctree) {
163  hpp::fcl::distance(&robMesh, tf1, &envMesh, tf2, dreq, dres);
164  std::cout << "distance mesh mesh: " << dres.min_distance << std::endl;
165  BOOST_CHECK(dres.min_distance < sqrt(2.) * resolution);
166  }
167  }
168 }
generate_distance_plot.m
float m
Definition: generate_distance_plot.py:6
hpp::fcl::Vec3f
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
hpp::fcl::loadOBJFile
void loadOBJFile(const char *filename, std::vector< Vec3f > &points, std::vector< Triangle > &triangles)
Load an obj mesh file.
Definition: utility.cpp:96
collision_manager.box
box
Definition: collision_manager.py:11
hpp::fcl::BVHModelBase::computeLocalAABB
void computeLocalAABB()
Compute the AABB for the BVH, used for broad-phase collision.
Definition: BVH_model.cpp:736
hpp::fcl::OcTreePtr_t
shared_ptr< OcTree > OcTreePtr_t
Definition: include/hpp/fcl/fwd.hh:106
y
y
hpp::fcl::BVHModelBase::beginModel
int beginModel(unsigned int num_tris=0, unsigned int num_vertices=0)
Begin a new BVH model.
Definition: BVH_model.cpp:170
gjk.tf1
tuple tf1
Definition: test/scripts/gjk.py:27
hpp::fcl::CONTACT
@ CONTACT
Definition: collision_data.h:229
makeOctree
hpp::fcl::OcTree makeOctree(const BVHModel< OBBRSS > &mesh, const FCL_REAL &resolution)
Definition: test/octree.cpp:75
utility.h
hpp::fcl::distance
HPP_FCL_DLLAPI FCL_REAL distance(const Matrix3f &R0, const Vec3f &T0, const kIOS &b1, const kIOS &b2, Vec3f *P=NULL, Vec3f *Q=NULL)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS.cpp:181
octree
Definition: octree.py:1
hpp::fcl::CollisionGeometry::aabb_local
AABB aabb_local
AABB in local coordinate, used for tight AABB when only translation transform.
Definition: collision_object.h:159
extents
FCL_REAL extents[6]
Definition: test/geometric_shapes.cpp:51
octomath::Vector3
hpp::fcl::BVHModel::bv_splitter
shared_ptr< BVSplitter< BV > > bv_splitter
Split rule to split one BV node into two children.
Definition: BVH/BVH_model.h:278
octomap::OcTree
hpp::fcl::BVHModelBase::endModel
int endModel()
End BVH model construction, will build the bounding volume hierarchy.
Definition: BVH_model.cpp:473
hpp::fcl::collide
HPP_FCL_DLLAPI std::size_t collide(const CollisionObject *o1, const CollisionObject *o2, const CollisionRequest &request, CollisionResult &result)
Main collision interface: given two collision objects, and the requirements for contacts,...
Definition: src/collision.cpp:63
distance.h
hpp::fcl::FCL_REAL
double FCL_REAL
Definition: data_types.h:65
hpp::fcl::SPLIT_METHOD_MEAN
@ SPLIT_METHOD_MEAN
Definition: internal/BV_splitter.h:52
hpp::fcl::SplitMethodType
SplitMethodType
Three types of split algorithms are provided in FCL as default.
Definition: internal/BV_splitter.h:51
makeMesh
void makeMesh(const std::vector< Vec3f > &vertices, const std::vector< Triangle > &triangles, BVHModel< OBBRSS > &model)
Definition: test/octree.cpp:64
hpp::fcl::CollisionResult::clear
void clear()
clear the results obtained
Definition: collision_data.h:377
hpp::fcl::CollisionRequest
request to the collision algorithm
Definition: collision_data.h:235
x
x
hpp::fcl::getNbRun
std::size_t getNbRun(const int &argc, char const *const *argv, std::size_t defaultValue)
Get the argument –nb-run from argv.
Definition: utility.cpp:382
gjk.tf2
tuple tf2
Definition: test/scripts/gjk.py:36
hpp::fcl::CollisionResult
collision result
Definition: collision_data.h:302
M
M
hpp::fcl::CollisionResult::isCollision
bool isCollision() const
return binary collision result
Definition: collision_data.h:339
hpp::fcl::generateRandomTransforms
void generateRandomTransforms(FCL_REAL extents[6], std::vector< Transform3f > &transforms, std::size_t n)
Generate n random transforms whose translations are constrained by extents.
Definition: utility.cpp:224
collision.path
path
Definition: scripts/collision.py:6
hpp::fcl::DistanceResult::min_distance
FCL_REAL min_distance
minimum distance between two objects. if two objects are in collision, min_distance <= 0.
Definition: collision_data.h:424
hpp::fcl::Transform3f
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
hpp::fcl::BVHModel
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: BVH/BVH_model.h:273
hpp::fcl::DistanceRequest
request to the distance computation
Definition: collision_data.h:392
hpp::fcl::BVSplitter
A class describing the split rule that splits each BV node.
Definition: BVH/BVH_model.h:59
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(OCTREE)
Definition: test/octree.cpp:111
BV_splitter.h
hpp::fcl::DistanceResult
distance result
Definition: collision_data.h:420
BVH_model.h
hpp::fcl::OcTree
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
Definition: octree.h:53
geometric_shapes.h
hpp::fcl::Transform3f::setTranslation
void setTranslation(const Eigen::MatrixBase< Derived > &T_)
set transform from translation
Definition: transform.h:142
hpp::fcl::Triangle
Triangle with 3 indices for points.
Definition: data_types.h:96
hpp::fcl::OBBRSS
Class merging the OBB and RSS, can handle collision and distance simultaneously.
Definition: BV/OBBRSS.h:54
hpp::fcl::DISTANCE_LOWER_BOUND
@ DISTANCE_LOWER_BOUND
Definition: collision_data.h:230
hpp::fcl::BVHModelBase::addSubModel
int addSubModel(const std::vector< Vec3f > &ps, const std::vector< Triangle > &ts)
Add a set of triangles in the new BVH model.
Definition: BVH_model.cpp:410
collision.h
hpp::fcl::Box
Center at zero point, axis aligned box.
Definition: shape/geometric_shapes.h:125


hpp-fcl
Author(s):
autogenerated on Fri Jan 26 2024 03:46:14