Go to the documentation of this file.
37 #define BOOST_TEST_MODULE FCL_OCTREE
39 #include <boost/test/included/unit_test.hpp>
40 #include <boost/filesystem.hpp>
49 #include "fcl_resources/config.h"
51 namespace utf = boost::unit_test::framework;
64 void makeMesh(
const std::vector<Vec3f>& vertices,
86 for (
FCL_REAL x = resolution * floor(
m[0] / resolution);
x <=
M[0];
88 for (
FCL_REAL y = resolution * floor(
m[1] / resolution);
y <=
M[1];
90 for (
FCL_REAL z = resolution * floor(
m[2] / resolution); z <=
M[2];
92 Vec3f center(
x + .5 * resolution,
y + .5 * resolution,
97 octomap::point3d p((
float)center[0], (
float)center[1],
99 octree->updateNode(p,
true);
106 octree->updateInnerOccupancy();
107 octree->writeBinary(
"./env.octree");
112 Eigen::IOFormat tuple(Eigen::FullPrecision, Eigen::DontAlignCols,
"",
", ",
115 std::vector<Vec3f> pRob, pEnv;
116 std::vector<Triangle> tRob, tEnv;
129 hpp::fcl::loadOctreeFile((
path /
"env.octree").
string(), resolution));
131 std::cout <<
"Finished loading octree." << std::endl;
133 std::vector<Transform3f> transforms;
135 #ifndef NDEBUG // if debug mode
138 std::size_t N = 10000;
141 utf::master_test_suite().argv, N);
147 for (std::size_t i = 0; i < N; ++i) {
159 BOOST_CHECK(!resMesh || resOctree);
160 if (!resMesh && resOctree) {
164 std::cout <<
"distance mesh mesh: " << dres.
min_distance << std::endl;
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
void loadOBJFile(const char *filename, std::vector< Vec3f > &points, std::vector< Triangle > &triangles)
Load an obj mesh file.
void computeLocalAABB()
Compute the AABB for the BVH, used for broad-phase collision.
shared_ptr< OcTree > OcTreePtr_t
int beginModel(unsigned int num_tris=0, unsigned int num_vertices=0)
Begin a new BVH model.
hpp::fcl::OcTree makeOctree(const BVHModel< OBBRSS > &mesh, const FCL_REAL &resolution)
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.
AABB aabb_local
AABB in local coordinate, used for tight AABB when only translation transform.
shared_ptr< BVSplitter< BV > > bv_splitter
Split rule to split one BV node into two children.
int endModel()
End BVH model construction, will build the bounding volume hierarchy.
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,...
SplitMethodType
Three types of split algorithms are provided in FCL as default.
void makeMesh(const std::vector< Vec3f > &vertices, const std::vector< Triangle > &triangles, BVHModel< OBBRSS > &model)
void clear()
clear the results obtained
request to the collision algorithm
std::size_t getNbRun(const int &argc, char const *const *argv, std::size_t defaultValue)
Get the argument –nb-run from argv.
bool isCollision() const
return binary collision result
void generateRandomTransforms(FCL_REAL extents[6], std::vector< Transform3f > &transforms, std::size_t n)
Generate n random transforms whose translations are constrained by extents.
FCL_REAL min_distance
minimum distance between two objects. if two objects are in collision, min_distance <= 0.
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
request to the distance computation
A class describing the split rule that splits each BV node.
BOOST_AUTO_TEST_CASE(OCTREE)
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
Triangle with 3 indices for points.
int addSubModel(const std::vector< Vec3f > &ps, const std::vector< Triangle > &ts)
Add a set of triangles in the new BVH model.
Center at zero point, axis aligned box.
hpp-fcl
Author(s):
autogenerated on Fri Aug 2 2024 02:45:14