flexible-collision-library / fcl

Flexible Collision Library
https://flexible-collision-library.github.io/
Other
1.35k stars 414 forks source link

running time of collision detection between mesh and box and the minimum distance #540

Open caozh502 opened 3 years ago

caozh502 commented 3 years ago

This Processing took 37 ms. My question is whether this running time of detection normal. And another problem is that the minimum distance data of the two detected objects shows abnormality. I don't know where the problem lies. The obj file is generated by the code of the pcl library and point cloud data. In the running result, there will be a line of warning Warning: distance function between node type 1 and node type 9 is not supported

// load sample 3D model
std::vector<Vector3f> vertices;
std::vector<Triangle> triangles;
fcl::test::loadOBJFile("../tree_mesh.obj", vertices, triangles);
//build bvh
typedef BVHModel<AABBf> Model;
std::shared_ptr<Model> geom = std::make_shared<Model>();
geom->beginModel();
geom->addSubModel(vertices,triangles);
geom->endModel();

std::cout<<geom->getNumBVs()<<std::endl;
std::cout<<geom->num_tris<<std::endl;
std::cout<<geom->num_vertices<<std::endl;

// set object transforms
Transform3f pose1 = Transform3f::Identity();
Transform3f pose2 = Transform3f::Identity();

// collision objects can be set
CollisionObjectf* obj1 = new CollisionObjectf(geom, pose1);
double length=14;
double width=2;
double height=2;
double m=5;

std::shared_ptr<fcl::CollisionGeometryf> box_geometry1(new fcl::Boxf(width,height,length));
CollisionObjectf* box1 = new CollisionObjectf (box_geometry1,pose2);
fcl::Vector3f trans1(0.,-height/2.-m,length/2.);
box1->setTranslation(trans1);

// set the collision request structure, here we just use the default setting
CollisionRequestf request;
CollisionResultf result;
DistanceRequestf D_request;
DistanceResultf D_result;
D_request.enable_nearest_points = true;
D_request.enable_signed_distance = true;
request.gjk_solver_type = fcl::GJKSolverType::GST_INDEP;
D_request.gjk_solver_type = fcl::GJKSolverType::GST_INDEP;

// perform collision test
collide(obj1, box1, request, result);
distance(obj1, box1, D_request, D_result);
std::cout<< result.numContacts() << std::endl;
std::cout << "The min distance is "<< D_result.min_distance << std::endl;
std::cout << D_result.nearest_points[0].transpose() << std::endl;
std::cout << D_result.nearest_points[1].transpose() << std::endl;

the number of bv in the BVH: 1657 Number of triangles: 829 Number of points: 527 min_distance: 3.40282e+38