38 #include <gtest/gtest.h> 43 #include "fcl_resources/config.h" 65 const std::vector<
Vector3<S>>& vertices1,
const std::vector<Triangle>& triangles1,
68 template<
typename BV,
typename TraversalNode>
79 if(fabs(a[0] - b[0]) > DELTA<S>())
return false;
80 if(fabs(a[1] - b[1]) > DELTA<S>())
return false;
81 if(fabs(a[2] - b[2]) > DELTA<S>())
return false;
88 std::vector<Vector3<S>> p1, p2;
89 std::vector<Triangle> t1, t2;
95 S
extents[] = {-3000, -3000, 0, 3000, 3000, 3000};
108 for(std::size_t i = 0; i < transforms.size(); ++i)
124 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
125 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
129 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
130 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
134 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
135 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
139 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
140 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
144 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
145 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
149 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
150 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
154 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
155 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
159 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
160 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
164 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
165 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
169 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
170 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
174 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
175 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
179 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
180 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
184 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
185 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
189 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
190 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
194 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
195 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
199 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
200 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
204 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
205 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
211 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
212 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
216 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
217 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
221 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
222 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
226 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
227 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
231 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
232 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
236 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
237 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
241 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
242 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
246 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
247 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
251 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
252 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
256 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
257 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
261 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
262 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
266 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
267 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
272 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
273 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
277 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
278 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
282 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
283 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
287 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
288 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
292 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
293 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
297 EXPECT_TRUE(fabs(res.distance - res_now.distance) < DELTA<S>());
298 EXPECT_TRUE(fabs(res.distance) < DELTA<S>() || (res.distance > 0 &&
nearlyEqual(res.p1, res_now.p1) &&
nearlyEqual(res.p2, res_now.p2)));
302 std::cout <<
"distance timing: " << dis_time <<
" sec" << std::endl;
303 std::cout <<
"collision timing: " << col_time <<
" sec" << std::endl;
309 test_mesh_distance<double>();
312 template <
typename S>
326 std::shared_ptr<CollisionGeometry<S>> box_geometry_1(
327 new Box<S>(2.750000, 6.000000, 0.050000));
328 std::shared_ptr<CollisionGeometry<S>> box_geometry_2(
329 new Box<S>(0.424000, 0.150000, 0.168600));
343 Box<S>* box1 =
static_cast<Box<S>*
>(box_geometry_1.get());
344 Box<S>* box2 =
static_cast<Box<S>*
>(box_geometry_2.get());
363 S expected_dist{0.053516162824549};
366 const Vector3<S> expected_p_B1N1{-1.375, -0.098881502700918666,
367 -0.025000000000000022};
368 const Vector3<S> expected_p_B2N2{0.21199965773384655, 0.074999692703297122,
369 0.084299993303443954};
384 NearestPointFromDegenerateSimplex<double>();
387 template<
typename BV,
typename TraversalNode>
395 using S =
typename BV::S;
414 std::cout <<
"initialize error" << std::endl;
416 node.enable_statistics =
verbose;
426 distance_result.
p1 = p1;
427 distance_result.
p2 = p2;
431 std::cout <<
"distance " << local_result.
min_distance << std::endl;
433 std::cout << p1[0] <<
" " << p1[1] <<
" " << p1[2] << std::endl;
434 std::cout << p2[0] <<
" " << p2[1] <<
" " << p2[2] << std::endl;
435 std::cout << node.num_bv_tests <<
" " << node.num_leaf_tests << std::endl;
439 template<
typename BV>
447 using S =
typename BV::S;
469 if(!detail::initialize<BV>(node, m1, pose1, m2, pose2,
DistanceRequest<S>(
true), local_result))
470 std::cout <<
"initialize error" << std::endl;
482 std::cout <<
"distance " << local_result.
min_distance << std::endl;
490 template <
typename S>
492 const std::vector<
Vector3<S>>& vertices1,
const std::vector<Triangle>& triangles1,
512 std::cout <<
"initialize error" << std::endl;
525 int main(
int argc,
char* argv[])
527 ::testing::InitGoogleTest(&argc, argv);
528 return RUN_ALL_TESTS();
int beginModel(int num_tris=0, int num_vertices=0)
Begin a new BVH model.
size_t numContacts() const
number of contacts found
std::array< S, 6 > & extents()
const Transform3< S > & getTransform() const
get object's transform
bool enable_statistics
Whether stores statistics.
S min_distance
Minimum distance between two objects.
void distance_Test_Oriented(const Transform3< typename BV::S > &tf, const std::vector< Vector3< typename BV::S >> &vertices1, const std::vector< Triangle > &triangles1, const std::vector< Vector3< typename BV::S >> &vertices2, const std::vector< Triangle > &triangles2, detail::SplitMethodType split_method, int qsize, test::DistanceRes< typename BV::S > &distance_result, bool verbose=true)
::testing::AssertionResult CompareMatrices(const Eigen::MatrixBase< DerivedA > &m1, const Eigen::MatrixBase< DerivedB > &m2, double tolerance=0.0, MatrixCompareType compare_type=MatrixCompareType::absolute)
bool collide_Test_OBB(const Transform3< S > &tf, const std::vector< Vector3< S >> &vertices1, const std::vector< Triangle > &triangles1, const std::vector< Vector3< S >> &vertices2, const std::vector< Triangle > &triangles2, detail::SplitMethodType split_method, bool verbose)
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
int main(int argc, char *argv[])
GTEST_TEST(FCL_DISTANCE, mesh_distance)
void stop()
stop the timer
SplitMethodType
Three types of split algorithms are provided in FCL as default.
S distance(const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P, Vector3< S > *Q)
Approximate distance between two kIOS bounding volumes.
#define EXPECT_NEAR(a, b, prec)
Eigen::Matrix< S, 3, 1 > Vector3
int addSubModel(const std::vector< Vector3< S >> &ps, const std::vector< Triangle > &ts)
Add a set of triangles in the new BVH model.
bool nearlyEqual(const Vector3< S > &a, const Vector3< S > &b)
int num_bv_tests
statistical information
collision and distance solver based on libccd library.
template FCL_EXPORT std::size_t collide(const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result)
Parameters for performing collision request.
double getElapsedTimeInSec()
get elapsed time in second (same as getElapsedTime)
template bool initialize(MeshCollisionTraversalNodeOBB< double > &node, const BVHModel< OBB< double >> &model1, const Transform3< double > &tf1, const BVHModel< OBB< double >> &model2, const Transform3< double > &tf2, const CollisionRequest< double > &request, CollisionResult< double > &result)
Structure for minimum distance between two meshes and the corresponding nearest point pair...
Center at zero point, axis aligned box.
void distance_Test(const Transform3< typename BV::S > &tf, const std::vector< Vector3< typename BV::S >> &vertices1, const std::vector< Triangle > &triangles1, const std::vector< Vector3< typename BV::S >> &vertices2, const std::vector< Triangle > &triangles2, detail::SplitMethodType split_method, int qsize, test::DistanceRes< typename BV::S > &distance_result, bool verbose=true)
Quaternion< double > Quaterniond
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
the object for collision or distance computation, contains the geometry and the transform information...
template bool GJKDistance(void *obj1, ccd_support_fn supp1, void *obj2, ccd_support_fn supp2, unsigned int max_iterations, double tolerance, double *dist, Vector3d *p1, Vector3d *p2)
void NearestPointFromDegenerateSimplex()
A class describing the split rule that splits each BV node.
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.
S distance_tolerance
the threshold used in GJK algorithm to stop distance iteration
Vector3< S > nearest_points[2]
Nearest points in the world coordinates.
request to the distance computation
void loadOBJFile(const char *filename, std::vector< Vector3< S >> &points, std::vector< Triangle > &triangles)
Load an obj mesh file.
#define EXPECT_TRUE(args)
std::shared_ptr< detail::BVSplitterBase< BV > > bv_splitter
Split rule to split one BV node into two children.
std::vector< _Tp, Eigen::aligned_allocator< _Tp > > aligned_vector
bool enable_statistics
Whether stores statistics.
void test_mesh_distance()
Traversal node for collision between two meshes if their underlying BVH node is oriented node (OBB...
Traversal node for distance computation between two meshes.