38 #include <gtest/gtest.h> 40 #include "fcl/config.h" 55 #include "fcl_resources/config.h" 61 void octomap_distance_test(S env_scale, std::size_t env_size,
bool use_mesh,
bool use_mesh_octomap,
double resolution = 0.1);
70 octomap_distance_test<S>(200, 100,
false,
false);
71 octomap_distance_test<S>(200, 1000,
false,
false);
73 octomap_distance_test<S>(200, 2,
false,
false, 1.0);
74 octomap_distance_test<S>(200, 10,
false,
false, 1.0);
81 test_octomap_distance<double>();
88 octomap_distance_test<S>(200, 100,
true,
true);
89 octomap_distance_test<S>(200, 1000,
true,
true);
91 octomap_distance_test<S>(200, 2,
true,
true, 1.0);
92 octomap_distance_test<S>(200, 5,
true,
true, 1.0);
99 test_octomap_distance_mesh<double>();
102 template <
typename S>
106 octomap_distance_test<S>(200, 100,
true,
false);
107 octomap_distance_test<S>(200, 1000,
true,
false);
109 octomap_distance_test<S>(200, 2,
true,
false, 1.0);
110 octomap_distance_test<S>(200, 5,
true,
false, 1.0);
117 test_octomap_distance_mesh_octomap_box<double>();
120 template <
typename S>
124 octomap_distance_test_BVH<RSS<S>>(5);
126 octomap_distance_test_BVH<RSS<S>>(5, 1.0);
133 test_octomap_bvh_rss_d_distance_rss<double>();
136 template <
typename S>
140 octomap_distance_test_BVH<OBBRSS<S>>(5);
142 octomap_distance_test_BVH<OBBRSS<S>>(5, 1.0);
149 test_octomap_bvh_obb_d_distance_obb<double>();
152 template <
typename S>
156 octomap_distance_test_BVH<kIOS<S>>(5);
158 octomap_distance_test_BVH<kIOS<S>>(5, 1.0);
165 test_octomap_bvh_kios_d_distance_kios<double>();
168 template<
typename BV>
171 using S =
typename BV::S;
173 std::vector<Vector3<S>> p1;
174 std::vector<Triangle> t1;
179 std::shared_ptr<CollisionGeometry<S>> m1_ptr(m1);
185 OcTree<S>* tree =
new OcTree<S>(
186 std::shared_ptr<octomap::OcTree>(test::generateOcTree(resolution)));
187 std::shared_ptr<CollisionGeometry<S>> tree_ptr(tree);
190 S
extents[] = {-5, -5, -5, 5, 5, 5};
194 for(std::size_t i = 0; i < n; ++i)
203 cdata.
request.enable_nearest_points =
true;
204 cdata1b.
request.enable_nearest_points =
true;
213 std::vector<CollisionObject<S>*> boxes;
214 test::generateBoxesFromOctomap(boxes, *tree);
215 for(std::size_t j = 0; j < boxes.size(); ++j)
216 boxes[j]->setTransform(tf2 * boxes[j]->getTransform());
225 S dist2 = cdata2.
result.min_distance;
227 for(std::size_t j = 0; j < boxes.size(); ++j)
238 cdata.
result.nearest_points[0] - cdata.
result.nearest_points[1];
244 EXPECT_NEAR(nearestPointDistance.norm(), dist1, 0.001);
249 template <
typename S>
250 void octomap_distance_test(S env_scale, std::size_t env_size,
bool use_mesh,
bool use_mesh_octomap,
double resolution)
253 std::vector<CollisionObject<S>*> env;
259 OcTree<S>* tree =
new OcTree<S>(std::shared_ptr<const octomap::OcTree>(test::generateOcTree(resolution)));
291 std::vector<CollisionObject<S>*> boxes;
293 test::generateBoxesFromOctomapMesh(boxes, *tree);
295 test::generateBoxesFromOctomap(boxes, *tree);
314 std::cout << cdata.
result.min_distance <<
" " << cdata3.
result.min_distance <<
" " << cdata2.
result.min_distance << std::endl;
316 if(cdata.
result.min_distance < 0)
317 EXPECT_LE(cdata2.
result.min_distance, 0);
323 for(
size_t i = 0; i < boxes.size(); ++i)
327 std::cout <<
"1) octomap overall time: " << t1.
overall_time << std::endl;
328 std::cout <<
"1') octomap overall time (as geometry): " << t3.
overall_time << std::endl;
329 std::cout <<
"2) boxes overall time: " << t2.
overall_time << std::endl;
330 std::cout <<
" a) to boxes: " << t2.
records[0] << std::endl;
331 std::cout <<
" b) structure init: " << t2.
records[1] << std::endl;
332 std::cout <<
" c) distance: " << t2.
records[2] << std::endl;
333 std::cout <<
"Note: octomap may need more collides when using mesh, because octomap collision uses box primitive inside" << std::endl;
337 int main(
int argc,
char* argv[])
339 ::testing::InitGoogleTest(&argc, argv);
340 return RUN_ALL_TESTS();
void test_octomap_distance_mesh()
void generateEnvironmentsMesh(std::vector< CollisionObject< S > *> &env, S env_scale, std::size_t n)
Generate environment with 3 * n objects, but all in meshes.
int beginModel(int num_tris=0, int num_vertices=0)
Begin a new BVH model.
std::array< S, 6 > & extents()
bool octree_as_geometry_collide
double getElapsedTime()
get elapsed time in milli-second
void test_octomap_distance_mesh_octomap_box()
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
std::vector< double > records
CollisionObject< S > * obj1
void stop()
stop the timer
bool DefaultDistanceFunction(CollisionObject< S > *o1, CollisionObject< S > *o2, void *data, S &dist)
Provides a simple callback for the distance query in the BroadPhaseCollisionManager. It assumes the data parameter is non-null and points to an instance of DefaultDistanceData. It simply invokes the distance() method on the culled pair of geometries and stores the results in the data's DistanceResult instance.
void test_octomap_bvh_rss_d_distance_rss()
#define EXPECT_NEAR(a, b, prec)
Eigen::Matrix< S, 3, 1 > Vector3
void test_octomap_distance()
bool octree_as_geometry_distance
int addSubModel(const std::vector< Vector3< S >> &ps, const std::vector< Triangle > &ts)
Add a set of triangles in the new BVH model.
The geometry for the object for collision or distance computation.
void test_octomap_bvh_obb_d_distance_obb()
void distance(CollisionObject< S > *obj, void *cdata, DistanceCallBack< S > callback) const
perform distance computation between one object and all the objects belonging to the manager ...
void setup()
initialize the manager, related with the specific type of manager
DistanceRequest< S > request
void generateEnvironments(std::vector< CollisionObject< S > *> &env, S env_scale, std::size_t n)
Generate environment with 3 * n objects: n boxes, n spheres and n cylinders.
Distance data for use with the DefaultDistanceFunction. It stores the distance request and the result...
void octomap_distance_test(S env_scale, std::size_t env_size, bool use_mesh, bool use_mesh_octomap, double resolution=0.1)
Octomap distance with an environment with 3 * env_size objects.
void test_octomap_bvh_kios_d_distance_kios()
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
int main(int argc, char *argv[])
the object for collision or distance computation, contains the geometry and the transform information...
void octomap_distance_test_BVH(std::size_t n, double resolution=0.1)
DistanceResult< S > result
CollisionObject< S > * obj2
void generateRandomTransforms(S extents[6], aligned_vector< Transform3< S >> &transforms, std::size_t n)
Generate n random transforms whose translations are constrained by extents.
int endModel()
End BVH model construction, will build the bounding volume hierarchy.
GTEST_TEST(FCL_OCTOMAP, test_octomap_distance)
void loadOBJFile(const char *filename, std::vector< Vector3< S >> &points, std::vector< Triangle > &triangles)
Load an obj mesh file.
void registerObjects(const std::vector< CollisionObject< S > *> &other_objs)
add objects to the manager
std::vector< _Tp, Eigen::aligned_allocator< _Tp > > aligned_vector