fcl package from fcl_catkin repofcl |
|
Package Summary
Tags | No category tags. |
Version | 0.7.0 |
License | BSD |
Build type | CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/flexible-collision-library/fcl.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2023-12-04 |
Dev Status | MAINTAINED |
CI status | Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- TRI Geometry Team
Authors
FCL – The Flexible Collision Library
FCL is a library for performing three types of proximity queries on a pair of geometric models composed of triangles.
- Collision detection: detecting whether the two models overlap, and optionally, all of the triangles that overlap.
- Distance computation: computing the minimum distance between a pair of models, i.e., the distance between the closest pair of points.
- Tolerance verification: determining whether two models are closer or farther than a tolerance distance.
- Continuous collision detection: detecting whether the two moving models overlap during the movement, and optionally, the time of contact.
- Contact information: for collision detection and continuous collision detection, the contact information (including contact normals and contact points) can be returned optionally.
FCL has the following features
- C++ interface
- Compilable for either linux or win32 (both makefiles and Microsoft Visual projects can be generated using cmake)
- No special topological constraints or adjacency information required for input models – all that is necessary is a list of the model’s triangles
- Supported different object shapes:
- box
- sphere
- ellipsoid
- capsule
- cone
- cylinder
- convex
- half-space
- plane
- mesh
- octree (optional, octrees are represented using the octomap library http://octomap.github.com)
Installation
Before compiling FCL, please make sure Eigen and libccd (for collision checking between convex objects and is available here https://github.com/danfis/libccd) are installed. For libccd, make sure to compile from github version instead of the zip file from the webpage, because one bug fixing is not included in the zipped version.
Some optional libraries need to be installed for some optional capability of FCL. For octree collision, please install the octomap library from https://octomap.github.io/.
CMakeLists.txt is used to generate makefiles in Linux or Visual studio projects in windows. In command line, run
mkdir build
cd build
cmake ..
Next, in linux, use make to compile the code.
In windows, there will generate a visual studio project and then you can compile the code.
Interfaces
Before starting the proximity computation, we need first to set the geometry and transform for the objects involving in computation. The geometry of an object is represented as a mesh soup, which can be set as follows:
// set mesh triangles and vertice indices
std::vector<Vector3f> vertices;
std::vector<Triangle> triangles;
// code to set the vertices and triangles
...
// BVHModel is a template class for mesh geometry, for default OBBRSS template
// is used
typedef BVHModel<OBBRSSf> Model;
std::shared_ptr<Model> geom = std::make_shared<Model>();
// add the mesh data into the BVHModel structure
geom->beginModel();
geom->addSubModel(vertices, triangles);
geom->endModel();
The transform of an object includes the rotation and translation:
// R and T are the rotation matrix and translation vector
Matrix3f R;
Vector3f T;
// code for setting R and T
...
// transform is configured according to R and T
Transform3f pose = Transform3f::Identity();
pose.linear() = R;
pose.translation() = T;
Given the geometry and the transform, we can also combine them together to obtain a collision object instance and here is an example:
//geom and tf are the geometry and the transform of the object
std::shared_ptr<BVHModel<OBBRSSf>> geom = ...
Transform3f tf = ...
//Combine them together
CollisionObjectf* obj = new CollisionObjectf(geom, tf);
Once the objects are set, we can perform the proximity computation between them. All the proximity queries in FCL follow a common pipeline: first, set the query request data structure and then run the query function by using request as the input. The result is returned in a query result data structure. For example, for collision checking, we first set the CollisionRequest data structure, and then run the collision function:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// set the collision request structure, here we just use the default setting
CollisionRequest request;
// result will be returned via the collision result structure
CollisionResult result;
// perform collision test
collide(o1, o2, request, result);
By setting the collision request, the user can easily choose whether to return contact information (which is slower) or just return binary collision results (which is faster).
For distance computation, the pipeline is almost the same:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// set the distance request structure, here we just use the default setting
DistanceRequest request;
// result will be returned via the collision result structure
DistanceResult result;
// perform distance test
distance(o1, o2, request, result);
For continuous collision, FCL requires the goal transform to be provided (the initial transform is included in the collision object data structure). Beside that, the pipeline is almost the same as distance/collision:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// The goal transforms for o1 and o2
Transform3f tf_goal_o1 = ...
Transform3f tf_goal_o2 = ...
// set the continuous collision request structure, here we just use the default
// setting
ContinuousCollisionRequest request;
// result will be returned via the continuous collision result structure
ContinuousCollisionResult result;
// perform continuous collision test
continuousCollide(o1, tf_goal_o1, o2, tf_goal_o2, request, result);
FCL supports broadphase collision/distance between two groups of objects and can avoid the n square complexity. For collision, broadphase algorithm can return all the collision pairs. For distance, it can return the pair with the minimum distance. FCL uses a CollisionManager structure to manage all the objects involving the collision or distance operations.
// Initialize the collision manager for the first group of objects.
// FCL provides various different implementations of CollisionManager.
// Generally, the DynamicAABBTreeCollisionManager would provide the best
// performance.
BroadPhaseCollisionManagerf* manager1 = new DynamicAABBTreeCollisionManagerf();
// Initialize the collision manager for the second group of objects.
BroadPhaseCollisionManagerf* manager2 = new DynamicAABBTreeCollisionManagerf();
// To add objects into the collision manager, using
// BroadPhaseCollisionManager::registerObject() function to add one object
std::vector<CollisionObjectf*> objects1 = ...
for(std::size_t i = 0; i < objects1.size(); ++i)
manager1->registerObject(objects1[i]);
// Another choose is to use BroadPhaseCollisionManager::registerObjects()
// function to add a set of objects
std::vector<CollisionObjectf*> objects2 = ...
manager2->registerObjects(objects2);
// In order to collect the information during broadphase, CollisionManager
// requires two settings:
// a) a callback to collision or distance;
// b) an intermediate data to store the information generated during the
// broadphase computation.
// For convenience, FCL provides default callbacks to satisfy a) and a
// corresponding call back data to satisfy b) for both collision and distance
// queries. For collision use DefaultCollisionCallback and DefaultCollisionData
// and for distance use DefaultDistanceCallback and DefaultDistanceData.
// The default collision/distance data structs are simply containers which
// include the request and distance structures for each query type as mentioned
// above.
DefaultCollisionData collision_data;
DefaultDistanceData distance_data;
// Setup the managers, which is related with initializing the broadphase
// acceleration structure according to objects input
manager1->setup();
manager2->setup();
// Examples for various queries
// 1. Collision query between two object groups and get collision numbers
manager2->collide(manager1, &collision_data, DefaultCollisionFunction);
int n_contact_num = collision_data.result.numContacts();
// 2. Distance query between two object groups and get the minimum distance
manager2->distance(manager1, &distance_data, DefaultDistanceFunction);
double min_distance = distance_data.result.min_distance;
// 3. Self collision query for group 1
manager1->collide(&collision_data, DefaultCollisionFunction);
// 4. Self distance query for group 1
manager1->distance(&distance_data, DefaultDistanceFunction);
// 5. Collision query between one object in group 1 and the entire group 2
manager2->collide(objects1[0], &collision_data, DefaultCollisionFunction);
// 6. Distance query between one object in group 1 and the entire group 2
manager2->distance(objects1[0], &distance_data, DefaultDistanceFunction);
For more examples, please refer to the test folder:
- test_fcl_collision.cpp: provide examples for collision test
- test_fcl_distance.cpp: provide examples for distance test
- test_fcl_broadphase.cpp: provide examples for broadphase collision/distance test
- test_fcl_frontlist.cpp: provide examples for frontlist collision acceleration
- test_fcl_octomap.cpp: provide examples for collision/distance computation between octomap data and other data types.
FCL 0
FCL 0.7.0 (2021-09-09)
-
Breaking changes
-
Core/Common
-
Math
-
Geometry
- OcTree logic for determining free/occupied: #467
- Bugs in RSS distance queries fixed: #467
- Convex gets some validation and improved support for the GJK
supportVertex()
API: #488 - Fixed bug in collision function matrix that only allowed calculation of collision between ellipsoid and half space with that ordering. Now also supports half space and ellipsoid. #520
- Do not flush error messages on cerr: #542
-
Broadphase
-
Narrowphase
- Primitive convex-half space collision algorithm introduced: #469
- Contact and distance query results types changed to be compatible with OcTree: #472
- Documentation for OcTree no longer mistakenly excluded from doxygen: #472
- Another failure mode in the GJK/EPA signed distance query patched: #494
- Fix build when ccd_real_t == float: #498
- Remove accidental recursive include: #496
-
Build/Test/Misc
FCL 0.6.1 (2020-02-26)
-
Math
- Replace M_PI instance with constants::pi(): #450
-
Narrowphase
- Various corrections and clarifications of the GJK algorithm used for general convex distance: #446
-
Build/Test/Misc
- Clean up install config files and ensure find_dependency is called as appropriate: #452
FCL 0.6.0 (2020-02-10)
-
Core/Common
-
Math
-
Geometry
- BVH Model throws intelligent errors when it runs out of memory: #237
- Generate a BVH Model from multiple primitives: #308
- Clean up
Convex
class: #325, #338, #369 - Computation of
Capsule
moment of inertia corrected: #420 - Added tests on local AABB computation for
Capsule
: #423 - Fixed interpretation of capsule parameters in primitive capsule-capsule distance computation. #436
-
Broadphase
- Fixed redundant pair checking of
SpatialHashingCollisionManager
: #156 - Clean up of hierarchy tree code: #439
- Default callback functions for broadphase collision managers have been moved
out of
fcl::test
and intofcl
namespace (with a corresponding name change, e.g.,defaultDistanceFunction
–>DefaultDistanceFunction
). #438- This includes the removal of the stub function
defaultContinuousDistanceFunction()
.
- This includes the removal of the stub function
- Fixed redundant pair checking of
-
Narrowphase
- Added distance request option for computing exact negative distance: #172
- Adjust tolerance on cylinder-cone unit test to pass on MacOS: #198
- Unify computation of nearest point in convexity-based distance algorithms: #215
- Fixed bug in cylinder-half space collision query: #255, #267
- Errors in box-box collision function addressed – this changes the semantics of the old results: penetration depth is a positive value and the position of the penetration will not lie on the surface of one box, but lies at the midpoint between the two penetrating surfaces: #259
- Fixed bug in
meshConservativeAdvancementOrientedNodeCanStop
: #271 -
CollisionRequest
gets a “GJK tolerance”: #283 - Correct distance queries to report nearest point in world frame: #288
- Various corrections and clarifications of the GJK algorithm used for general convex distance: #290, #296, #324, #365, #367, #373
- Remove duplicated code between GJKDistance and GJKSignedDistance: #292
- Significant bug fixes in the EPA algorithm for computing signed distance on penetrating convex shapes: #305, #314, #336, #352, #388, #397, #417, #434, #435, #437
- Add custom sphere-box collision and distance algorithms for both solvers: #316
- Add custom sphere-cylinder collision and distance algorithms for both solvers: #321
- Octree-mesh distance query returns witness points: #427
-
Build/Test/Misc
- Ensure the locally generated config.h is used: #142
- Use major.minor version for ABI soversion: #143
- Added missing copyright headers: #149
- Enable Win32 builds on AppVeyor CI: #157
- Enabled build with SSE option by default: #159
- Show build status of master branch in README.md: #166
- Added CMake targets for generating API documentation: #174
- Clean up finding external dependencies and use imported targets where available: #181, #182, #196
- Added version check for Visual Studio in CMake (VS2015 or greater required): #189
- Add dedicated SSE CMake option: #191
- Remove unused references to TinyXML from build: #193
- Minor corrections to signed distance tests: #199
- Fix various compiler warnings and enable warnings as errors in CI: #197, #200, #204, #205
- Allow the CMake RPATH to be configured: #203
- Set SSE flags for the Apple compiler: #206
- Windows CI always uses double-valued libccd: #216
- Clean up of CMake install configuration: #230
- Formalize visibility of binary symbols: #233
- Remove tapping deprecated homebrew-science: #262
- Move travis CI to use xcode 9 instead of 7.3: #266
- Fix VS2017 incompatibility: #277
- Mention Visual Studio version requirement in INSTALL file: #284
- Correct CMake error message for the wrong version of libccd: #286
- Added test utility for performing equality between Eigen matrix-types
(
CompareMatrices
intest/eign_matrix_compare.h
): #316 - Toward enabling dashboards on CI: #328
- Add configuration files for various static analyzers: #332
- Update AppVeyor badge URL in README: #342
- CMake fixes and cleanup: #360
- Enable –output-on-failure for CI builds: #362
- Corrected test of the distance function to be compatible with libccd 2: #371
- Provides the
UnexpectedConfigurationException
so that when narrowphase operations encounter an error, they can throw this new exception which will trigger a logging of the types and poses of the geometries that led to the error: #381 - Provide catkin packaage.xml per ROS REP 136: #409
- Updated README.md to reflect FCL 0.6.0 syntax changes: #410
FCL 0.5.0 (2016-07-19)
- Added safe-guards to allow octree headers only if octomap enabled: #136
- Added CMake option to disable octomap in build: #135
- Added automatic coverage test reporting: #125, #98
- Added CMake exported targets: #116
- Fixed API to support Octomap 1.8: #129, #126
- Fixed continuousCollisionNaive() wasn’t resetting the returned result when no collision: #123
- Fixed uninitialized tf in TranslationMotion: #121
- Fixed fcl.pc populated incorrect installation paths: #118
- Fixed octree vs mesh CollisionResult now returns triangle id: #114
- Fixed minor typo: #113
- Fixed fallback finding of libccd: #112
- Fixed a nasty bug in propagate propagateBVHFrontListCollisionRecurse(): #110
- Fixed test_fcl_math failures on Windows 64 bit due to non-portable use of long: #108, #107
- Fixed compilation in Visual Studio 2015, and suppressed some warnings: #99
- Fixed build when libccd package config not found: #94
- Removing dependency on boost: #108, #105, #104, #103
Wiki Tutorials
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged fcl at Robotics Stack Exchange
fcl package from fcl_catkin repofcl |
|
Third-Party Package
This third-party package's source repository does not contain a package manifest. Instead, its package manifest is stored in its release repository. In order to build this package from source in a Catkin workspace, please download its package manifest.Package Summary
Tags | No category tags. |
Version | 0.3.3 |
License | BSD |
Build type | CATKIN |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/flexible-collision-library/fcl.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2023-12-04 |
Dev Status | MAINTAINED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Ioan Sucan
Authors
- Jia Pan
FCL – The Flexible Collision Library
FCL is a library for performing three types of proximity queries on a pair of geometric models composed of triangles.
- Collision detection: detecting whether the two models overlap, and optionally, all of the triangles that overlap.
- Distance computation: computing the minimum distance between a pair of models, i.e., the distance between the closest pair of points.
- Tolerance verification: determining whether two models are closer or farther than a tolerance distance.
- Continuous collision detection: detecting whether the two moving models overlap during the movement, and optionally, the time of contact.
- Contact information: for collision detection and continuous collision detection, the contact information (including contact normals and contact points) can be returned optionally.
FCL has the following features
- C++ interface
- Compilable for either linux or win32 (both makefiles and Microsoft Visual projects can be generated using cmake)
- No special topological constraints or adjacency information required for input models – all that is necessary is a list of the model’s triangles
- Supported different object shapes:
- box
- sphere
- ellipsoid
- capsule
- cone
- cylinder
- convex
- half-space
- plane
- mesh
- octree (optional, octrees are represented using the octomap library http://octomap.github.com)
Installation
Before compiling FCL, please make sure Eigen and libccd (for collision checking between convex objects and is available here https://github.com/danfis/libccd) are installed. For libccd, make sure to compile from github version instead of the zip file from the webpage, because one bug fixing is not included in the zipped version.
Some optional libraries need to be installed for some optional capability of FCL. For octree collision, please install the octomap library from https://octomap.github.io/.
CMakeLists.txt is used to generate makefiles in Linux or Visual studio projects in windows. In command line, run
mkdir build
cd build
cmake ..
Next, in linux, use make to compile the code.
In windows, there will generate a visual studio project and then you can compile the code.
Interfaces
Before starting the proximity computation, we need first to set the geometry and transform for the objects involving in computation. The geometry of an object is represented as a mesh soup, which can be set as follows:
// set mesh triangles and vertice indices
std::vector<Vector3f> vertices;
std::vector<Triangle> triangles;
// code to set the vertices and triangles
...
// BVHModel is a template class for mesh geometry, for default OBBRSS template
// is used
typedef BVHModel<OBBRSSf> Model;
std::shared_ptr<Model> geom = std::make_shared<Model>();
// add the mesh data into the BVHModel structure
geom->beginModel();
geom->addSubModel(vertices, triangles);
geom->endModel();
The transform of an object includes the rotation and translation:
// R and T are the rotation matrix and translation vector
Matrix3f R;
Vector3f T;
// code for setting R and T
...
// transform is configured according to R and T
Transform3f pose = Transform3f::Identity();
pose.linear() = R;
pose.translation() = T;
Given the geometry and the transform, we can also combine them together to obtain a collision object instance and here is an example:
//geom and tf are the geometry and the transform of the object
std::shared_ptr<BVHModel<OBBRSSf>> geom = ...
Transform3f tf = ...
//Combine them together
CollisionObjectf* obj = new CollisionObjectf(geom, tf);
Once the objects are set, we can perform the proximity computation between them. All the proximity queries in FCL follow a common pipeline: first, set the query request data structure and then run the query function by using request as the input. The result is returned in a query result data structure. For example, for collision checking, we first set the CollisionRequest data structure, and then run the collision function:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// set the collision request structure, here we just use the default setting
CollisionRequest request;
// result will be returned via the collision result structure
CollisionResult result;
// perform collision test
collide(o1, o2, request, result);
By setting the collision request, the user can easily choose whether to return contact information (which is slower) or just return binary collision results (which is faster).
For distance computation, the pipeline is almost the same:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// set the distance request structure, here we just use the default setting
DistanceRequest request;
// result will be returned via the collision result structure
DistanceResult result;
// perform distance test
distance(o1, o2, request, result);
For continuous collision, FCL requires the goal transform to be provided (the initial transform is included in the collision object data structure). Beside that, the pipeline is almost the same as distance/collision:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// The goal transforms for o1 and o2
Transform3f tf_goal_o1 = ...
Transform3f tf_goal_o2 = ...
// set the continuous collision request structure, here we just use the default
// setting
ContinuousCollisionRequest request;
// result will be returned via the continuous collision result structure
ContinuousCollisionResult result;
// perform continuous collision test
continuousCollide(o1, tf_goal_o1, o2, tf_goal_o2, request, result);
FCL supports broadphase collision/distance between two groups of objects and can avoid the n square complexity. For collision, broadphase algorithm can return all the collision pairs. For distance, it can return the pair with the minimum distance. FCL uses a CollisionManager structure to manage all the objects involving the collision or distance operations.
// Initialize the collision manager for the first group of objects.
// FCL provides various different implementations of CollisionManager.
// Generally, the DynamicAABBTreeCollisionManager would provide the best
// performance.
BroadPhaseCollisionManagerf* manager1 = new DynamicAABBTreeCollisionManagerf();
// Initialize the collision manager for the second group of objects.
BroadPhaseCollisionManagerf* manager2 = new DynamicAABBTreeCollisionManagerf();
// To add objects into the collision manager, using
// BroadPhaseCollisionManager::registerObject() function to add one object
std::vector<CollisionObjectf*> objects1 = ...
for(std::size_t i = 0; i < objects1.size(); ++i)
manager1->registerObject(objects1[i]);
// Another choose is to use BroadPhaseCollisionManager::registerObjects()
// function to add a set of objects
std::vector<CollisionObjectf*> objects2 = ...
manager2->registerObjects(objects2);
// In order to collect the information during broadphase, CollisionManager
// requires two settings:
// a) a callback to collision or distance;
// b) an intermediate data to store the information generated during the
// broadphase computation.
// For convenience, FCL provides default callbacks to satisfy a) and a
// corresponding call back data to satisfy b) for both collision and distance
// queries. For collision use DefaultCollisionCallback and DefaultCollisionData
// and for distance use DefaultDistanceCallback and DefaultDistanceData.
// The default collision/distance data structs are simply containers which
// include the request and distance structures for each query type as mentioned
// above.
DefaultCollisionData collision_data;
DefaultDistanceData distance_data;
// Setup the managers, which is related with initializing the broadphase
// acceleration structure according to objects input
manager1->setup();
manager2->setup();
// Examples for various queries
// 1. Collision query between two object groups and get collision numbers
manager2->collide(manager1, &collision_data, DefaultCollisionFunction);
int n_contact_num = collision_data.result.numContacts();
// 2. Distance query between two object groups and get the minimum distance
manager2->distance(manager1, &distance_data, DefaultDistanceFunction);
double min_distance = distance_data.result.min_distance;
// 3. Self collision query for group 1
manager1->collide(&collision_data, DefaultCollisionFunction);
// 4. Self distance query for group 1
manager1->distance(&distance_data, DefaultDistanceFunction);
// 5. Collision query between one object in group 1 and the entire group 2
manager2->collide(objects1[0], &collision_data, DefaultCollisionFunction);
// 6. Distance query between one object in group 1 and the entire group 2
manager2->distance(objects1[0], &distance_data, DefaultDistanceFunction);
For more examples, please refer to the test folder:
- test_fcl_collision.cpp: provide examples for collision test
- test_fcl_distance.cpp: provide examples for distance test
- test_fcl_broadphase.cpp: provide examples for broadphase collision/distance test
- test_fcl_frontlist.cpp: provide examples for frontlist collision acceleration
- test_fcl_octomap.cpp: provide examples for collision/distance computation between octomap data and other data types.
FCL 0
FCL 0.7.0 (2021-09-09)
-
Breaking changes
-
Core/Common
-
Math
-
Geometry
- OcTree logic for determining free/occupied: #467
- Bugs in RSS distance queries fixed: #467
- Convex gets some validation and improved support for the GJK
supportVertex()
API: #488 - Fixed bug in collision function matrix that only allowed calculation of collision between ellipsoid and half space with that ordering. Now also supports half space and ellipsoid. #520
- Do not flush error messages on cerr: #542
-
Broadphase
-
Narrowphase
- Primitive convex-half space collision algorithm introduced: #469
- Contact and distance query results types changed to be compatible with OcTree: #472
- Documentation for OcTree no longer mistakenly excluded from doxygen: #472
- Another failure mode in the GJK/EPA signed distance query patched: #494
- Fix build when ccd_real_t == float: #498
- Remove accidental recursive include: #496
-
Build/Test/Misc
FCL 0.6.1 (2020-02-26)
-
Math
- Replace M_PI instance with constants::pi(): #450
-
Narrowphase
- Various corrections and clarifications of the GJK algorithm used for general convex distance: #446
-
Build/Test/Misc
- Clean up install config files and ensure find_dependency is called as appropriate: #452
FCL 0.6.0 (2020-02-10)
-
Core/Common
-
Math
-
Geometry
- BVH Model throws intelligent errors when it runs out of memory: #237
- Generate a BVH Model from multiple primitives: #308
- Clean up
Convex
class: #325, #338, #369 - Computation of
Capsule
moment of inertia corrected: #420 - Added tests on local AABB computation for
Capsule
: #423 - Fixed interpretation of capsule parameters in primitive capsule-capsule distance computation. #436
-
Broadphase
- Fixed redundant pair checking of
SpatialHashingCollisionManager
: #156 - Clean up of hierarchy tree code: #439
- Default callback functions for broadphase collision managers have been moved
out of
fcl::test
and intofcl
namespace (with a corresponding name change, e.g.,defaultDistanceFunction
–>DefaultDistanceFunction
). #438- This includes the removal of the stub function
defaultContinuousDistanceFunction()
.
- This includes the removal of the stub function
- Fixed redundant pair checking of
-
Narrowphase
- Added distance request option for computing exact negative distance: #172
- Adjust tolerance on cylinder-cone unit test to pass on MacOS: #198
- Unify computation of nearest point in convexity-based distance algorithms: #215
- Fixed bug in cylinder-half space collision query: #255, #267
- Errors in box-box collision function addressed – this changes the semantics of the old results: penetration depth is a positive value and the position of the penetration will not lie on the surface of one box, but lies at the midpoint between the two penetrating surfaces: #259
- Fixed bug in
meshConservativeAdvancementOrientedNodeCanStop
: #271 -
CollisionRequest
gets a “GJK tolerance”: #283 - Correct distance queries to report nearest point in world frame: #288
- Various corrections and clarifications of the GJK algorithm used for general convex distance: #290, #296, #324, #365, #367, #373
- Remove duplicated code between GJKDistance and GJKSignedDistance: #292
- Significant bug fixes in the EPA algorithm for computing signed distance on penetrating convex shapes: #305, #314, #336, #352, #388, #397, #417, #434, #435, #437
- Add custom sphere-box collision and distance algorithms for both solvers: #316
- Add custom sphere-cylinder collision and distance algorithms for both solvers: #321
- Octree-mesh distance query returns witness points: #427
-
Build/Test/Misc
- Ensure the locally generated config.h is used: #142
- Use major.minor version for ABI soversion: #143
- Added missing copyright headers: #149
- Enable Win32 builds on AppVeyor CI: #157
- Enabled build with SSE option by default: #159
- Show build status of master branch in README.md: #166
- Added CMake targets for generating API documentation: #174
- Clean up finding external dependencies and use imported targets where available: #181, #182, #196
- Added version check for Visual Studio in CMake (VS2015 or greater required): #189
- Add dedicated SSE CMake option: #191
- Remove unused references to TinyXML from build: #193
- Minor corrections to signed distance tests: #199
- Fix various compiler warnings and enable warnings as errors in CI: #197, #200, #204, #205
- Allow the CMake RPATH to be configured: #203
- Set SSE flags for the Apple compiler: #206
- Windows CI always uses double-valued libccd: #216
- Clean up of CMake install configuration: #230
- Formalize visibility of binary symbols: #233
- Remove tapping deprecated homebrew-science: #262
- Move travis CI to use xcode 9 instead of 7.3: #266
- Fix VS2017 incompatibility: #277
- Mention Visual Studio version requirement in INSTALL file: #284
- Correct CMake error message for the wrong version of libccd: #286
- Added test utility for performing equality between Eigen matrix-types
(
CompareMatrices
intest/eign_matrix_compare.h
): #316 - Toward enabling dashboards on CI: #328
- Add configuration files for various static analyzers: #332
- Update AppVeyor badge URL in README: #342
- CMake fixes and cleanup: #360
- Enable –output-on-failure for CI builds: #362
- Corrected test of the distance function to be compatible with libccd 2: #371
- Provides the
UnexpectedConfigurationException
so that when narrowphase operations encounter an error, they can throw this new exception which will trigger a logging of the types and poses of the geometries that led to the error: #381 - Provide catkin packaage.xml per ROS REP 136: #409
- Updated README.md to reflect FCL 0.6.0 syntax changes: #410
FCL 0.5.0 (2016-07-19)
- Added safe-guards to allow octree headers only if octomap enabled: #136
- Added CMake option to disable octomap in build: #135
- Added automatic coverage test reporting: #125, #98
- Added CMake exported targets: #116
- Fixed API to support Octomap 1.8: #129, #126
- Fixed continuousCollisionNaive() wasn’t resetting the returned result when no collision: #123
- Fixed uninitialized tf in TranslationMotion: #121
- Fixed fcl.pc populated incorrect installation paths: #118
- Fixed octree vs mesh CollisionResult now returns triangle id: #114
- Fixed minor typo: #113
- Fixed fallback finding of libccd: #112
- Fixed a nasty bug in propagate propagateBVHFrontListCollisionRecurse(): #110
- Fixed test_fcl_math failures on Windows 64 bit due to non-portable use of long: #108, #107
- Fixed compilation in Visual Studio 2015, and suppressed some warnings: #99
- Fixed build when libccd package config not found: #94
- Removing dependency on boost: #108, #105, #104, #103
Wiki Tutorials
Dependant Packages
Name | Deps |
---|---|
moveit_core | |
moveit_experimental |
Launch files
Messages
Services
Plugins
Recent questions tagged fcl at Robotics Stack Exchange
fcl package from fcl_catkin repofcl |
|
Third-Party Package
This third-party package's source repository does not contain a package manifest. Instead, its package manifest is stored in its release repository. In order to build this package from source in a Catkin workspace, please download its package manifest.Package Summary
Tags | No category tags. |
Version | 0.3.4 |
License | BSD |
Build type | CATKIN |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/flexible-collision-library/fcl.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2023-12-04 |
Dev Status | MAINTAINED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Ioan Sucan
Authors
- Jia Pan
FCL – The Flexible Collision Library
FCL is a library for performing three types of proximity queries on a pair of geometric models composed of triangles.
- Collision detection: detecting whether the two models overlap, and optionally, all of the triangles that overlap.
- Distance computation: computing the minimum distance between a pair of models, i.e., the distance between the closest pair of points.
- Tolerance verification: determining whether two models are closer or farther than a tolerance distance.
- Continuous collision detection: detecting whether the two moving models overlap during the movement, and optionally, the time of contact.
- Contact information: for collision detection and continuous collision detection, the contact information (including contact normals and contact points) can be returned optionally.
FCL has the following features
- C++ interface
- Compilable for either linux or win32 (both makefiles and Microsoft Visual projects can be generated using cmake)
- No special topological constraints or adjacency information required for input models – all that is necessary is a list of the model’s triangles
- Supported different object shapes:
- box
- sphere
- ellipsoid
- capsule
- cone
- cylinder
- convex
- half-space
- plane
- mesh
- octree (optional, octrees are represented using the octomap library http://octomap.github.com)
Installation
Before compiling FCL, please make sure Eigen and libccd (for collision checking between convex objects and is available here https://github.com/danfis/libccd) are installed. For libccd, make sure to compile from github version instead of the zip file from the webpage, because one bug fixing is not included in the zipped version.
Some optional libraries need to be installed for some optional capability of FCL. For octree collision, please install the octomap library from https://octomap.github.io/.
CMakeLists.txt is used to generate makefiles in Linux or Visual studio projects in windows. In command line, run
mkdir build
cd build
cmake ..
Next, in linux, use make to compile the code.
In windows, there will generate a visual studio project and then you can compile the code.
Interfaces
Before starting the proximity computation, we need first to set the geometry and transform for the objects involving in computation. The geometry of an object is represented as a mesh soup, which can be set as follows:
// set mesh triangles and vertice indices
std::vector<Vector3f> vertices;
std::vector<Triangle> triangles;
// code to set the vertices and triangles
...
// BVHModel is a template class for mesh geometry, for default OBBRSS template
// is used
typedef BVHModel<OBBRSSf> Model;
std::shared_ptr<Model> geom = std::make_shared<Model>();
// add the mesh data into the BVHModel structure
geom->beginModel();
geom->addSubModel(vertices, triangles);
geom->endModel();
The transform of an object includes the rotation and translation:
// R and T are the rotation matrix and translation vector
Matrix3f R;
Vector3f T;
// code for setting R and T
...
// transform is configured according to R and T
Transform3f pose = Transform3f::Identity();
pose.linear() = R;
pose.translation() = T;
Given the geometry and the transform, we can also combine them together to obtain a collision object instance and here is an example:
//geom and tf are the geometry and the transform of the object
std::shared_ptr<BVHModel<OBBRSSf>> geom = ...
Transform3f tf = ...
//Combine them together
CollisionObjectf* obj = new CollisionObjectf(geom, tf);
Once the objects are set, we can perform the proximity computation between them. All the proximity queries in FCL follow a common pipeline: first, set the query request data structure and then run the query function by using request as the input. The result is returned in a query result data structure. For example, for collision checking, we first set the CollisionRequest data structure, and then run the collision function:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// set the collision request structure, here we just use the default setting
CollisionRequest request;
// result will be returned via the collision result structure
CollisionResult result;
// perform collision test
collide(o1, o2, request, result);
By setting the collision request, the user can easily choose whether to return contact information (which is slower) or just return binary collision results (which is faster).
For distance computation, the pipeline is almost the same:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// set the distance request structure, here we just use the default setting
DistanceRequest request;
// result will be returned via the collision result structure
DistanceResult result;
// perform distance test
distance(o1, o2, request, result);
For continuous collision, FCL requires the goal transform to be provided (the initial transform is included in the collision object data structure). Beside that, the pipeline is almost the same as distance/collision:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// The goal transforms for o1 and o2
Transform3f tf_goal_o1 = ...
Transform3f tf_goal_o2 = ...
// set the continuous collision request structure, here we just use the default
// setting
ContinuousCollisionRequest request;
// result will be returned via the continuous collision result structure
ContinuousCollisionResult result;
// perform continuous collision test
continuousCollide(o1, tf_goal_o1, o2, tf_goal_o2, request, result);
FCL supports broadphase collision/distance between two groups of objects and can avoid the n square complexity. For collision, broadphase algorithm can return all the collision pairs. For distance, it can return the pair with the minimum distance. FCL uses a CollisionManager structure to manage all the objects involving the collision or distance operations.
// Initialize the collision manager for the first group of objects.
// FCL provides various different implementations of CollisionManager.
// Generally, the DynamicAABBTreeCollisionManager would provide the best
// performance.
BroadPhaseCollisionManagerf* manager1 = new DynamicAABBTreeCollisionManagerf();
// Initialize the collision manager for the second group of objects.
BroadPhaseCollisionManagerf* manager2 = new DynamicAABBTreeCollisionManagerf();
// To add objects into the collision manager, using
// BroadPhaseCollisionManager::registerObject() function to add one object
std::vector<CollisionObjectf*> objects1 = ...
for(std::size_t i = 0; i < objects1.size(); ++i)
manager1->registerObject(objects1[i]);
// Another choose is to use BroadPhaseCollisionManager::registerObjects()
// function to add a set of objects
std::vector<CollisionObjectf*> objects2 = ...
manager2->registerObjects(objects2);
// In order to collect the information during broadphase, CollisionManager
// requires two settings:
// a) a callback to collision or distance;
// b) an intermediate data to store the information generated during the
// broadphase computation.
// For convenience, FCL provides default callbacks to satisfy a) and a
// corresponding call back data to satisfy b) for both collision and distance
// queries. For collision use DefaultCollisionCallback and DefaultCollisionData
// and for distance use DefaultDistanceCallback and DefaultDistanceData.
// The default collision/distance data structs are simply containers which
// include the request and distance structures for each query type as mentioned
// above.
DefaultCollisionData collision_data;
DefaultDistanceData distance_data;
// Setup the managers, which is related with initializing the broadphase
// acceleration structure according to objects input
manager1->setup();
manager2->setup();
// Examples for various queries
// 1. Collision query between two object groups and get collision numbers
manager2->collide(manager1, &collision_data, DefaultCollisionFunction);
int n_contact_num = collision_data.result.numContacts();
// 2. Distance query between two object groups and get the minimum distance
manager2->distance(manager1, &distance_data, DefaultDistanceFunction);
double min_distance = distance_data.result.min_distance;
// 3. Self collision query for group 1
manager1->collide(&collision_data, DefaultCollisionFunction);
// 4. Self distance query for group 1
manager1->distance(&distance_data, DefaultDistanceFunction);
// 5. Collision query between one object in group 1 and the entire group 2
manager2->collide(objects1[0], &collision_data, DefaultCollisionFunction);
// 6. Distance query between one object in group 1 and the entire group 2
manager2->distance(objects1[0], &distance_data, DefaultDistanceFunction);
For more examples, please refer to the test folder:
- test_fcl_collision.cpp: provide examples for collision test
- test_fcl_distance.cpp: provide examples for distance test
- test_fcl_broadphase.cpp: provide examples for broadphase collision/distance test
- test_fcl_frontlist.cpp: provide examples for frontlist collision acceleration
- test_fcl_octomap.cpp: provide examples for collision/distance computation between octomap data and other data types.
FCL 0
FCL 0.7.0 (2021-09-09)
-
Breaking changes
-
Core/Common
-
Math
-
Geometry
- OcTree logic for determining free/occupied: #467
- Bugs in RSS distance queries fixed: #467
- Convex gets some validation and improved support for the GJK
supportVertex()
API: #488 - Fixed bug in collision function matrix that only allowed calculation of collision between ellipsoid and half space with that ordering. Now also supports half space and ellipsoid. #520
- Do not flush error messages on cerr: #542
-
Broadphase
-
Narrowphase
- Primitive convex-half space collision algorithm introduced: #469
- Contact and distance query results types changed to be compatible with OcTree: #472
- Documentation for OcTree no longer mistakenly excluded from doxygen: #472
- Another failure mode in the GJK/EPA signed distance query patched: #494
- Fix build when ccd_real_t == float: #498
- Remove accidental recursive include: #496
-
Build/Test/Misc
FCL 0.6.1 (2020-02-26)
-
Math
- Replace M_PI instance with constants::pi(): #450
-
Narrowphase
- Various corrections and clarifications of the GJK algorithm used for general convex distance: #446
-
Build/Test/Misc
- Clean up install config files and ensure find_dependency is called as appropriate: #452
FCL 0.6.0 (2020-02-10)
-
Core/Common
-
Math
-
Geometry
- BVH Model throws intelligent errors when it runs out of memory: #237
- Generate a BVH Model from multiple primitives: #308
- Clean up
Convex
class: #325, #338, #369 - Computation of
Capsule
moment of inertia corrected: #420 - Added tests on local AABB computation for
Capsule
: #423 - Fixed interpretation of capsule parameters in primitive capsule-capsule distance computation. #436
-
Broadphase
- Fixed redundant pair checking of
SpatialHashingCollisionManager
: #156 - Clean up of hierarchy tree code: #439
- Default callback functions for broadphase collision managers have been moved
out of
fcl::test
and intofcl
namespace (with a corresponding name change, e.g.,defaultDistanceFunction
–>DefaultDistanceFunction
). #438- This includes the removal of the stub function
defaultContinuousDistanceFunction()
.
- This includes the removal of the stub function
- Fixed redundant pair checking of
-
Narrowphase
- Added distance request option for computing exact negative distance: #172
- Adjust tolerance on cylinder-cone unit test to pass on MacOS: #198
- Unify computation of nearest point in convexity-based distance algorithms: #215
- Fixed bug in cylinder-half space collision query: #255, #267
- Errors in box-box collision function addressed – this changes the semantics of the old results: penetration depth is a positive value and the position of the penetration will not lie on the surface of one box, but lies at the midpoint between the two penetrating surfaces: #259
- Fixed bug in
meshConservativeAdvancementOrientedNodeCanStop
: #271 -
CollisionRequest
gets a “GJK tolerance”: #283 - Correct distance queries to report nearest point in world frame: #288
- Various corrections and clarifications of the GJK algorithm used for general convex distance: #290, #296, #324, #365, #367, #373
- Remove duplicated code between GJKDistance and GJKSignedDistance: #292
- Significant bug fixes in the EPA algorithm for computing signed distance on penetrating convex shapes: #305, #314, #336, #352, #388, #397, #417, #434, #435, #437
- Add custom sphere-box collision and distance algorithms for both solvers: #316
- Add custom sphere-cylinder collision and distance algorithms for both solvers: #321
- Octree-mesh distance query returns witness points: #427
-
Build/Test/Misc
- Ensure the locally generated config.h is used: #142
- Use major.minor version for ABI soversion: #143
- Added missing copyright headers: #149
- Enable Win32 builds on AppVeyor CI: #157
- Enabled build with SSE option by default: #159
- Show build status of master branch in README.md: #166
- Added CMake targets for generating API documentation: #174
- Clean up finding external dependencies and use imported targets where available: #181, #182, #196
- Added version check for Visual Studio in CMake (VS2015 or greater required): #189
- Add dedicated SSE CMake option: #191
- Remove unused references to TinyXML from build: #193
- Minor corrections to signed distance tests: #199
- Fix various compiler warnings and enable warnings as errors in CI: #197, #200, #204, #205
- Allow the CMake RPATH to be configured: #203
- Set SSE flags for the Apple compiler: #206
- Windows CI always uses double-valued libccd: #216
- Clean up of CMake install configuration: #230
- Formalize visibility of binary symbols: #233
- Remove tapping deprecated homebrew-science: #262
- Move travis CI to use xcode 9 instead of 7.3: #266
- Fix VS2017 incompatibility: #277
- Mention Visual Studio version requirement in INSTALL file: #284
- Correct CMake error message for the wrong version of libccd: #286
- Added test utility for performing equality between Eigen matrix-types
(
CompareMatrices
intest/eign_matrix_compare.h
): #316 - Toward enabling dashboards on CI: #328
- Add configuration files for various static analyzers: #332
- Update AppVeyor badge URL in README: #342
- CMake fixes and cleanup: #360
- Enable –output-on-failure for CI builds: #362
- Corrected test of the distance function to be compatible with libccd 2: #371
- Provides the
UnexpectedConfigurationException
so that when narrowphase operations encounter an error, they can throw this new exception which will trigger a logging of the types and poses of the geometries that led to the error: #381 - Provide catkin packaage.xml per ROS REP 136: #409
- Updated README.md to reflect FCL 0.6.0 syntax changes: #410
FCL 0.5.0 (2016-07-19)
- Added safe-guards to allow octree headers only if octomap enabled: #136
- Added CMake option to disable octomap in build: #135
- Added automatic coverage test reporting: #125, #98
- Added CMake exported targets: #116
- Fixed API to support Octomap 1.8: #129, #126
- Fixed continuousCollisionNaive() wasn’t resetting the returned result when no collision: #123
- Fixed uninitialized tf in TranslationMotion: #121
- Fixed fcl.pc populated incorrect installation paths: #118
- Fixed octree vs mesh CollisionResult now returns triangle id: #114
- Fixed minor typo: #113
- Fixed fallback finding of libccd: #112
- Fixed a nasty bug in propagate propagateBVHFrontListCollisionRecurse(): #110
- Fixed test_fcl_math failures on Windows 64 bit due to non-portable use of long: #108, #107
- Fixed compilation in Visual Studio 2015, and suppressed some warnings: #99
- Fixed build when libccd package config not found: #94
- Removing dependency on boost: #108, #105, #104, #103
Wiki Tutorials
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged fcl at Robotics Stack Exchange
fcl package from fcl_catkin repofcl |
|
Third-Party Package
This third-party package's source repository does not contain a package manifest. Instead, its package manifest is stored in its release repository. In order to build this package from source in a Catkin workspace, please download its package manifest.Package Summary
Tags | No category tags. |
Version | 0.2.9 |
License | BSD |
Build type | CATKIN |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/flexible-collision-library/fcl.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2023-12-04 |
Dev Status | MAINTAINED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Ioan Sucan
Authors
- Jia Pan
FCL – The Flexible Collision Library
FCL is a library for performing three types of proximity queries on a pair of geometric models composed of triangles.
- Collision detection: detecting whether the two models overlap, and optionally, all of the triangles that overlap.
- Distance computation: computing the minimum distance between a pair of models, i.e., the distance between the closest pair of points.
- Tolerance verification: determining whether two models are closer or farther than a tolerance distance.
- Continuous collision detection: detecting whether the two moving models overlap during the movement, and optionally, the time of contact.
- Contact information: for collision detection and continuous collision detection, the contact information (including contact normals and contact points) can be returned optionally.
FCL has the following features
- C++ interface
- Compilable for either linux or win32 (both makefiles and Microsoft Visual projects can be generated using cmake)
- No special topological constraints or adjacency information required for input models – all that is necessary is a list of the model’s triangles
- Supported different object shapes:
- box
- sphere
- ellipsoid
- capsule
- cone
- cylinder
- convex
- half-space
- plane
- mesh
- octree (optional, octrees are represented using the octomap library http://octomap.github.com)
Installation
Before compiling FCL, please make sure Eigen and libccd (for collision checking between convex objects and is available here https://github.com/danfis/libccd) are installed. For libccd, make sure to compile from github version instead of the zip file from the webpage, because one bug fixing is not included in the zipped version.
Some optional libraries need to be installed for some optional capability of FCL. For octree collision, please install the octomap library from https://octomap.github.io/.
CMakeLists.txt is used to generate makefiles in Linux or Visual studio projects in windows. In command line, run
mkdir build
cd build
cmake ..
Next, in linux, use make to compile the code.
In windows, there will generate a visual studio project and then you can compile the code.
Interfaces
Before starting the proximity computation, we need first to set the geometry and transform for the objects involving in computation. The geometry of an object is represented as a mesh soup, which can be set as follows:
// set mesh triangles and vertice indices
std::vector<Vector3f> vertices;
std::vector<Triangle> triangles;
// code to set the vertices and triangles
...
// BVHModel is a template class for mesh geometry, for default OBBRSS template
// is used
typedef BVHModel<OBBRSSf> Model;
std::shared_ptr<Model> geom = std::make_shared<Model>();
// add the mesh data into the BVHModel structure
geom->beginModel();
geom->addSubModel(vertices, triangles);
geom->endModel();
The transform of an object includes the rotation and translation:
// R and T are the rotation matrix and translation vector
Matrix3f R;
Vector3f T;
// code for setting R and T
...
// transform is configured according to R and T
Transform3f pose = Transform3f::Identity();
pose.linear() = R;
pose.translation() = T;
Given the geometry and the transform, we can also combine them together to obtain a collision object instance and here is an example:
//geom and tf are the geometry and the transform of the object
std::shared_ptr<BVHModel<OBBRSSf>> geom = ...
Transform3f tf = ...
//Combine them together
CollisionObjectf* obj = new CollisionObjectf(geom, tf);
Once the objects are set, we can perform the proximity computation between them. All the proximity queries in FCL follow a common pipeline: first, set the query request data structure and then run the query function by using request as the input. The result is returned in a query result data structure. For example, for collision checking, we first set the CollisionRequest data structure, and then run the collision function:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// set the collision request structure, here we just use the default setting
CollisionRequest request;
// result will be returned via the collision result structure
CollisionResult result;
// perform collision test
collide(o1, o2, request, result);
By setting the collision request, the user can easily choose whether to return contact information (which is slower) or just return binary collision results (which is faster).
For distance computation, the pipeline is almost the same:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// set the distance request structure, here we just use the default setting
DistanceRequest request;
// result will be returned via the collision result structure
DistanceResult result;
// perform distance test
distance(o1, o2, request, result);
For continuous collision, FCL requires the goal transform to be provided (the initial transform is included in the collision object data structure). Beside that, the pipeline is almost the same as distance/collision:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// The goal transforms for o1 and o2
Transform3f tf_goal_o1 = ...
Transform3f tf_goal_o2 = ...
// set the continuous collision request structure, here we just use the default
// setting
ContinuousCollisionRequest request;
// result will be returned via the continuous collision result structure
ContinuousCollisionResult result;
// perform continuous collision test
continuousCollide(o1, tf_goal_o1, o2, tf_goal_o2, request, result);
FCL supports broadphase collision/distance between two groups of objects and can avoid the n square complexity. For collision, broadphase algorithm can return all the collision pairs. For distance, it can return the pair with the minimum distance. FCL uses a CollisionManager structure to manage all the objects involving the collision or distance operations.
// Initialize the collision manager for the first group of objects.
// FCL provides various different implementations of CollisionManager.
// Generally, the DynamicAABBTreeCollisionManager would provide the best
// performance.
BroadPhaseCollisionManagerf* manager1 = new DynamicAABBTreeCollisionManagerf();
// Initialize the collision manager for the second group of objects.
BroadPhaseCollisionManagerf* manager2 = new DynamicAABBTreeCollisionManagerf();
// To add objects into the collision manager, using
// BroadPhaseCollisionManager::registerObject() function to add one object
std::vector<CollisionObjectf*> objects1 = ...
for(std::size_t i = 0; i < objects1.size(); ++i)
manager1->registerObject(objects1[i]);
// Another choose is to use BroadPhaseCollisionManager::registerObjects()
// function to add a set of objects
std::vector<CollisionObjectf*> objects2 = ...
manager2->registerObjects(objects2);
// In order to collect the information during broadphase, CollisionManager
// requires two settings:
// a) a callback to collision or distance;
// b) an intermediate data to store the information generated during the
// broadphase computation.
// For convenience, FCL provides default callbacks to satisfy a) and a
// corresponding call back data to satisfy b) for both collision and distance
// queries. For collision use DefaultCollisionCallback and DefaultCollisionData
// and for distance use DefaultDistanceCallback and DefaultDistanceData.
// The default collision/distance data structs are simply containers which
// include the request and distance structures for each query type as mentioned
// above.
DefaultCollisionData collision_data;
DefaultDistanceData distance_data;
// Setup the managers, which is related with initializing the broadphase
// acceleration structure according to objects input
manager1->setup();
manager2->setup();
// Examples for various queries
// 1. Collision query between two object groups and get collision numbers
manager2->collide(manager1, &collision_data, DefaultCollisionFunction);
int n_contact_num = collision_data.result.numContacts();
// 2. Distance query between two object groups and get the minimum distance
manager2->distance(manager1, &distance_data, DefaultDistanceFunction);
double min_distance = distance_data.result.min_distance;
// 3. Self collision query for group 1
manager1->collide(&collision_data, DefaultCollisionFunction);
// 4. Self distance query for group 1
manager1->distance(&distance_data, DefaultDistanceFunction);
// 5. Collision query between one object in group 1 and the entire group 2
manager2->collide(objects1[0], &collision_data, DefaultCollisionFunction);
// 6. Distance query between one object in group 1 and the entire group 2
manager2->distance(objects1[0], &distance_data, DefaultDistanceFunction);
For more examples, please refer to the test folder:
- test_fcl_collision.cpp: provide examples for collision test
- test_fcl_distance.cpp: provide examples for distance test
- test_fcl_broadphase.cpp: provide examples for broadphase collision/distance test
- test_fcl_frontlist.cpp: provide examples for frontlist collision acceleration
- test_fcl_octomap.cpp: provide examples for collision/distance computation between octomap data and other data types.
FCL 0
FCL 0.7.0 (2021-09-09)
-
Breaking changes
-
Core/Common
-
Math
-
Geometry
- OcTree logic for determining free/occupied: #467
- Bugs in RSS distance queries fixed: #467
- Convex gets some validation and improved support for the GJK
supportVertex()
API: #488 - Fixed bug in collision function matrix that only allowed calculation of collision between ellipsoid and half space with that ordering. Now also supports half space and ellipsoid. #520
- Do not flush error messages on cerr: #542
-
Broadphase
-
Narrowphase
- Primitive convex-half space collision algorithm introduced: #469
- Contact and distance query results types changed to be compatible with OcTree: #472
- Documentation for OcTree no longer mistakenly excluded from doxygen: #472
- Another failure mode in the GJK/EPA signed distance query patched: #494
- Fix build when ccd_real_t == float: #498
- Remove accidental recursive include: #496
-
Build/Test/Misc
FCL 0.6.1 (2020-02-26)
-
Math
- Replace M_PI instance with constants::pi(): #450
-
Narrowphase
- Various corrections and clarifications of the GJK algorithm used for general convex distance: #446
-
Build/Test/Misc
- Clean up install config files and ensure find_dependency is called as appropriate: #452
FCL 0.6.0 (2020-02-10)
-
Core/Common
-
Math
-
Geometry
- BVH Model throws intelligent errors when it runs out of memory: #237
- Generate a BVH Model from multiple primitives: #308
- Clean up
Convex
class: #325, #338, #369 - Computation of
Capsule
moment of inertia corrected: #420 - Added tests on local AABB computation for
Capsule
: #423 - Fixed interpretation of capsule parameters in primitive capsule-capsule distance computation. #436
-
Broadphase
- Fixed redundant pair checking of
SpatialHashingCollisionManager
: #156 - Clean up of hierarchy tree code: #439
- Default callback functions for broadphase collision managers have been moved
out of
fcl::test
and intofcl
namespace (with a corresponding name change, e.g.,defaultDistanceFunction
–>DefaultDistanceFunction
). #438- This includes the removal of the stub function
defaultContinuousDistanceFunction()
.
- This includes the removal of the stub function
- Fixed redundant pair checking of
-
Narrowphase
- Added distance request option for computing exact negative distance: #172
- Adjust tolerance on cylinder-cone unit test to pass on MacOS: #198
- Unify computation of nearest point in convexity-based distance algorithms: #215
- Fixed bug in cylinder-half space collision query: #255, #267
- Errors in box-box collision function addressed – this changes the semantics of the old results: penetration depth is a positive value and the position of the penetration will not lie on the surface of one box, but lies at the midpoint between the two penetrating surfaces: #259
- Fixed bug in
meshConservativeAdvancementOrientedNodeCanStop
: #271 -
CollisionRequest
gets a “GJK tolerance”: #283 - Correct distance queries to report nearest point in world frame: #288
- Various corrections and clarifications of the GJK algorithm used for general convex distance: #290, #296, #324, #365, #367, #373
- Remove duplicated code between GJKDistance and GJKSignedDistance: #292
- Significant bug fixes in the EPA algorithm for computing signed distance on penetrating convex shapes: #305, #314, #336, #352, #388, #397, #417, #434, #435, #437
- Add custom sphere-box collision and distance algorithms for both solvers: #316
- Add custom sphere-cylinder collision and distance algorithms for both solvers: #321
- Octree-mesh distance query returns witness points: #427
-
Build/Test/Misc
- Ensure the locally generated config.h is used: #142
- Use major.minor version for ABI soversion: #143
- Added missing copyright headers: #149
- Enable Win32 builds on AppVeyor CI: #157
- Enabled build with SSE option by default: #159
- Show build status of master branch in README.md: #166
- Added CMake targets for generating API documentation: #174
- Clean up finding external dependencies and use imported targets where available: #181, #182, #196
- Added version check for Visual Studio in CMake (VS2015 or greater required): #189
- Add dedicated SSE CMake option: #191
- Remove unused references to TinyXML from build: #193
- Minor corrections to signed distance tests: #199
- Fix various compiler warnings and enable warnings as errors in CI: #197, #200, #204, #205
- Allow the CMake RPATH to be configured: #203
- Set SSE flags for the Apple compiler: #206
- Windows CI always uses double-valued libccd: #216
- Clean up of CMake install configuration: #230
- Formalize visibility of binary symbols: #233
- Remove tapping deprecated homebrew-science: #262
- Move travis CI to use xcode 9 instead of 7.3: #266
- Fix VS2017 incompatibility: #277
- Mention Visual Studio version requirement in INSTALL file: #284
- Correct CMake error message for the wrong version of libccd: #286
- Added test utility for performing equality between Eigen matrix-types
(
CompareMatrices
intest/eign_matrix_compare.h
): #316 - Toward enabling dashboards on CI: #328
- Add configuration files for various static analyzers: #332
- Update AppVeyor badge URL in README: #342
- CMake fixes and cleanup: #360
- Enable –output-on-failure for CI builds: #362
- Corrected test of the distance function to be compatible with libccd 2: #371
- Provides the
UnexpectedConfigurationException
so that when narrowphase operations encounter an error, they can throw this new exception which will trigger a logging of the types and poses of the geometries that led to the error: #381 - Provide catkin packaage.xml per ROS REP 136: #409
- Updated README.md to reflect FCL 0.6.0 syntax changes: #410
FCL 0.5.0 (2016-07-19)
- Added safe-guards to allow octree headers only if octomap enabled: #136
- Added CMake option to disable octomap in build: #135
- Added automatic coverage test reporting: #125, #98
- Added CMake exported targets: #116
- Fixed API to support Octomap 1.8: #129, #126
- Fixed continuousCollisionNaive() wasn’t resetting the returned result when no collision: #123
- Fixed uninitialized tf in TranslationMotion: #121
- Fixed fcl.pc populated incorrect installation paths: #118
- Fixed octree vs mesh CollisionResult now returns triangle id: #114
- Fixed minor typo: #113
- Fixed fallback finding of libccd: #112
- Fixed a nasty bug in propagate propagateBVHFrontListCollisionRecurse(): #110
- Fixed test_fcl_math failures on Windows 64 bit due to non-portable use of long: #108, #107
- Fixed compilation in Visual Studio 2015, and suppressed some warnings: #99
- Fixed build when libccd package config not found: #94
- Removing dependency on boost: #108, #105, #104, #103
Wiki Tutorials
Dependant Packages
Name | Deps |
---|---|
pr2_moveit_tests | |
moveit_core |
Launch files
Messages
Services
Plugins
Recent questions tagged fcl at Robotics Stack Exchange
fcl package from fcl_catkin repofcl |
|
Package Summary
Tags | No category tags. |
Version | 0.7.0 |
License | BSD |
Build type | CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/flexible-collision-library/fcl.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2023-12-04 |
Dev Status | MAINTAINED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- TRI Geometry Team
Authors
FCL – The Flexible Collision Library
FCL is a library for performing three types of proximity queries on a pair of geometric models composed of triangles.
- Collision detection: detecting whether the two models overlap, and optionally, all of the triangles that overlap.
- Distance computation: computing the minimum distance between a pair of models, i.e., the distance between the closest pair of points.
- Tolerance verification: determining whether two models are closer or farther than a tolerance distance.
- Continuous collision detection: detecting whether the two moving models overlap during the movement, and optionally, the time of contact.
- Contact information: for collision detection and continuous collision detection, the contact information (including contact normals and contact points) can be returned optionally.
FCL has the following features
- C++ interface
- Compilable for either linux or win32 (both makefiles and Microsoft Visual projects can be generated using cmake)
- No special topological constraints or adjacency information required for input models – all that is necessary is a list of the model’s triangles
- Supported different object shapes:
- box
- sphere
- ellipsoid
- capsule
- cone
- cylinder
- convex
- half-space
- plane
- mesh
- octree (optional, octrees are represented using the octomap library http://octomap.github.com)
Installation
Before compiling FCL, please make sure Eigen and libccd (for collision checking between convex objects and is available here https://github.com/danfis/libccd) are installed. For libccd, make sure to compile from github version instead of the zip file from the webpage, because one bug fixing is not included in the zipped version.
Some optional libraries need to be installed for some optional capability of FCL. For octree collision, please install the octomap library from https://octomap.github.io/.
CMakeLists.txt is used to generate makefiles in Linux or Visual studio projects in windows. In command line, run
mkdir build
cd build
cmake ..
Next, in linux, use make to compile the code.
In windows, there will generate a visual studio project and then you can compile the code.
Interfaces
Before starting the proximity computation, we need first to set the geometry and transform for the objects involving in computation. The geometry of an object is represented as a mesh soup, which can be set as follows:
// set mesh triangles and vertice indices
std::vector<Vector3f> vertices;
std::vector<Triangle> triangles;
// code to set the vertices and triangles
...
// BVHModel is a template class for mesh geometry, for default OBBRSS template
// is used
typedef BVHModel<OBBRSSf> Model;
std::shared_ptr<Model> geom = std::make_shared<Model>();
// add the mesh data into the BVHModel structure
geom->beginModel();
geom->addSubModel(vertices, triangles);
geom->endModel();
The transform of an object includes the rotation and translation:
// R and T are the rotation matrix and translation vector
Matrix3f R;
Vector3f T;
// code for setting R and T
...
// transform is configured according to R and T
Transform3f pose = Transform3f::Identity();
pose.linear() = R;
pose.translation() = T;
Given the geometry and the transform, we can also combine them together to obtain a collision object instance and here is an example:
//geom and tf are the geometry and the transform of the object
std::shared_ptr<BVHModel<OBBRSSf>> geom = ...
Transform3f tf = ...
//Combine them together
CollisionObjectf* obj = new CollisionObjectf(geom, tf);
Once the objects are set, we can perform the proximity computation between them. All the proximity queries in FCL follow a common pipeline: first, set the query request data structure and then run the query function by using request as the input. The result is returned in a query result data structure. For example, for collision checking, we first set the CollisionRequest data structure, and then run the collision function:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// set the collision request structure, here we just use the default setting
CollisionRequest request;
// result will be returned via the collision result structure
CollisionResult result;
// perform collision test
collide(o1, o2, request, result);
By setting the collision request, the user can easily choose whether to return contact information (which is slower) or just return binary collision results (which is faster).
For distance computation, the pipeline is almost the same:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// set the distance request structure, here we just use the default setting
DistanceRequest request;
// result will be returned via the collision result structure
DistanceResult result;
// perform distance test
distance(o1, o2, request, result);
For continuous collision, FCL requires the goal transform to be provided (the initial transform is included in the collision object data structure). Beside that, the pipeline is almost the same as distance/collision:
// Given two objects o1 and o2
CollisionObjectf* o1 = ...
CollisionObjectf* o2 = ...
// The goal transforms for o1 and o2
Transform3f tf_goal_o1 = ...
Transform3f tf_goal_o2 = ...
// set the continuous collision request structure, here we just use the default
// setting
ContinuousCollisionRequest request;
// result will be returned via the continuous collision result structure
ContinuousCollisionResult result;
// perform continuous collision test
continuousCollide(o1, tf_goal_o1, o2, tf_goal_o2, request, result);
FCL supports broadphase collision/distance between two groups of objects and can avoid the n square complexity. For collision, broadphase algorithm can return all the collision pairs. For distance, it can return the pair with the minimum distance. FCL uses a CollisionManager structure to manage all the objects involving the collision or distance operations.
// Initialize the collision manager for the first group of objects.
// FCL provides various different implementations of CollisionManager.
// Generally, the DynamicAABBTreeCollisionManager would provide the best
// performance.
BroadPhaseCollisionManagerf* manager1 = new DynamicAABBTreeCollisionManagerf();
// Initialize the collision manager for the second group of objects.
BroadPhaseCollisionManagerf* manager2 = new DynamicAABBTreeCollisionManagerf();
// To add objects into the collision manager, using
// BroadPhaseCollisionManager::registerObject() function to add one object
std::vector<CollisionObjectf*> objects1 = ...
for(std::size_t i = 0; i < objects1.size(); ++i)
manager1->registerObject(objects1[i]);
// Another choose is to use BroadPhaseCollisionManager::registerObjects()
// function to add a set of objects
std::vector<CollisionObjectf*> objects2 = ...
manager2->registerObjects(objects2);
// In order to collect the information during broadphase, CollisionManager
// requires two settings:
// a) a callback to collision or distance;
// b) an intermediate data to store the information generated during the
// broadphase computation.
// For convenience, FCL provides default callbacks to satisfy a) and a
// corresponding call back data to satisfy b) for both collision and distance
// queries. For collision use DefaultCollisionCallback and DefaultCollisionData
// and for distance use DefaultDistanceCallback and DefaultDistanceData.
// The default collision/distance data structs are simply containers which
// include the request and distance structures for each query type as mentioned
// above.
DefaultCollisionData collision_data;
DefaultDistanceData distance_data;
// Setup the managers, which is related with initializing the broadphase
// acceleration structure according to objects input
manager1->setup();
manager2->setup();
// Examples for various queries
// 1. Collision query between two object groups and get collision numbers
manager2->collide(manager1, &collision_data, DefaultCollisionFunction);
int n_contact_num = collision_data.result.numContacts();
// 2. Distance query between two object groups and get the minimum distance
manager2->distance(manager1, &distance_data, DefaultDistanceFunction);
double min_distance = distance_data.result.min_distance;
// 3. Self collision query for group 1
manager1->collide(&collision_data, DefaultCollisionFunction);
// 4. Self distance query for group 1
manager1->distance(&distance_data, DefaultDistanceFunction);
// 5. Collision query between one object in group 1 and the entire group 2
manager2->collide(objects1[0], &collision_data, DefaultCollisionFunction);
// 6. Distance query between one object in group 1 and the entire group 2
manager2->distance(objects1[0], &distance_data, DefaultDistanceFunction);
For more examples, please refer to the test folder:
- test_fcl_collision.cpp: provide examples for collision test
- test_fcl_distance.cpp: provide examples for distance test
- test_fcl_broadphase.cpp: provide examples for broadphase collision/distance test
- test_fcl_frontlist.cpp: provide examples for frontlist collision acceleration
- test_fcl_octomap.cpp: provide examples for collision/distance computation between octomap data and other data types.
FCL 0
FCL 0.7.0 (2021-09-09)
-
Breaking changes
-
Core/Common
-
Math
-
Geometry
- OcTree logic for determining free/occupied: #467
- Bugs in RSS distance queries fixed: #467
- Convex gets some validation and improved support for the GJK
supportVertex()
API: #488 - Fixed bug in collision function matrix that only allowed calculation of collision between ellipsoid and half space with that ordering. Now also supports half space and ellipsoid. #520
- Do not flush error messages on cerr: #542
-
Broadphase
-
Narrowphase
- Primitive convex-half space collision algorithm introduced: #469
- Contact and distance query results types changed to be compatible with OcTree: #472
- Documentation for OcTree no longer mistakenly excluded from doxygen: #472
- Another failure mode in the GJK/EPA signed distance query patched: #494
- Fix build when ccd_real_t == float: #498
- Remove accidental recursive include: #496
-
Build/Test/Misc
FCL 0.6.1 (2020-02-26)
-
Math
- Replace M_PI instance with constants::pi(): #450
-
Narrowphase
- Various corrections and clarifications of the GJK algorithm used for general convex distance: #446
-
Build/Test/Misc
- Clean up install config files and ensure find_dependency is called as appropriate: #452
FCL 0.6.0 (2020-02-10)
-
Core/Common
-
Math
-
Geometry
- BVH Model throws intelligent errors when it runs out of memory: #237
- Generate a BVH Model from multiple primitives: #308
- Clean up
Convex
class: #325, #338, #369 - Computation of
Capsule
moment of inertia corrected: #420 - Added tests on local AABB computation for
Capsule
: #423 - Fixed interpretation of capsule parameters in primitive capsule-capsule distance computation. #436
-
Broadphase
- Fixed redundant pair checking of
SpatialHashingCollisionManager
: #156 - Clean up of hierarchy tree code: #439
- Default callback functions for broadphase collision managers have been moved
out of
fcl::test
and intofcl
namespace (with a corresponding name change, e.g.,defaultDistanceFunction
–>DefaultDistanceFunction
). #438- This includes the removal of the stub function
defaultContinuousDistanceFunction()
.
- This includes the removal of the stub function
- Fixed redundant pair checking of
-
Narrowphase
- Added distance request option for computing exact negative distance: #172
- Adjust tolerance on cylinder-cone unit test to pass on MacOS: #198
- Unify computation of nearest point in convexity-based distance algorithms: #215
- Fixed bug in cylinder-half space collision query: #255, #267
- Errors in box-box collision function addressed – this changes the semantics of the old results: penetration depth is a positive value and the position of the penetration will not lie on the surface of one box, but lies at the midpoint between the two penetrating surfaces: #259
- Fixed bug in
meshConservativeAdvancementOrientedNodeCanStop
: #271 -
CollisionRequest
gets a “GJK tolerance”: #283 - Correct distance queries to report nearest point in world frame: #288
- Various corrections and clarifications of the GJK algorithm used for general convex distance: #290, #296, #324, #365, #367, #373
- Remove duplicated code between GJKDistance and GJKSignedDistance: #292
- Significant bug fixes in the EPA algorithm for computing signed distance on penetrating convex shapes: #305, #314, #336, #352, #388, #397, #417, #434, #435, #437
- Add custom sphere-box collision and distance algorithms for both solvers: #316
- Add custom sphere-cylinder collision and distance algorithms for both solvers: #321
- Octree-mesh distance query returns witness points: #427
-
Build/Test/Misc
- Ensure the locally generated config.h is used: #142
- Use major.minor version for ABI soversion: #143
- Added missing copyright headers: #149
- Enable Win32 builds on AppVeyor CI: #157
- Enabled build with SSE option by default: #159
- Show build status of master branch in README.md: #166
- Added CMake targets for generating API documentation: #174
- Clean up finding external dependencies and use imported targets where available: #181, #182, #196
- Added version check for Visual Studio in CMake (VS2015 or greater required): #189
- Add dedicated SSE CMake option: #191
- Remove unused references to TinyXML from build: #193
- Minor corrections to signed distance tests: #199
- Fix various compiler warnings and enable warnings as errors in CI: #197, #200, #204, #205
- Allow the CMake RPATH to be configured: #203
- Set SSE flags for the Apple compiler: #206
- Windows CI always uses double-valued libccd: #216
- Clean up of CMake install configuration: #230
- Formalize visibility of binary symbols: #233
- Remove tapping deprecated homebrew-science: #262
- Move travis CI to use xcode 9 instead of 7.3: #266
- Fix VS2017 incompatibility: #277
- Mention Visual Studio version requirement in INSTALL file: #284
- Correct CMake error message for the wrong version of libccd: #286
- Added test utility for performing equality between Eigen matrix-types
(
CompareMatrices
intest/eign_matrix_compare.h
): #316 - Toward enabling dashboards on CI: #328
- Add configuration files for various static analyzers: #332
- Update AppVeyor badge URL in README: #342
- CMake fixes and cleanup: #360
- Enable –output-on-failure for CI builds: #362
- Corrected test of the distance function to be compatible with libccd 2: #371
- Provides the
UnexpectedConfigurationException
so that when narrowphase operations encounter an error, they can throw this new exception which will trigger a logging of the types and poses of the geometries that led to the error: #381 - Provide catkin packaage.xml per ROS REP 136: #409
- Updated README.md to reflect FCL 0.6.0 syntax changes: #410
FCL 0.5.0 (2016-07-19)
- Added safe-guards to allow octree headers only if octomap enabled: #136
- Added CMake option to disable octomap in build: #135
- Added automatic coverage test reporting: #125, #98
- Added CMake exported targets: #116
- Fixed API to support Octomap 1.8: #129, #126
- Fixed continuousCollisionNaive() wasn’t resetting the returned result when no collision: #123
- Fixed uninitialized tf in TranslationMotion: #121
- Fixed fcl.pc populated incorrect installation paths: #118
- Fixed octree vs mesh CollisionResult now returns triangle id: #114
- Fixed minor typo: #113
- Fixed fallback finding of libccd: #112
- Fixed a nasty bug in propagate propagateBVHFrontListCollisionRecurse(): #110
- Fixed test_fcl_math failures on Windows 64 bit due to non-portable use of long: #108, #107
- Fixed compilation in Visual Studio 2015, and suppressed some warnings: #99
- Fixed build when libccd package config not found: #94
- Removing dependency on boost: #108, #105, #104, #103