Showing preview only (4,606K chars total). Download the full file or copy to clipboard to get everything.
Repository: coal-library/coal
Branch: devel
Commit: 60b3e498ca40
Files: 500
Total size: 4.3 MB
Directory structure:
gitextract_n08c_ker/
├── .clang-format
├── .gersemirc
├── .git-blame-ignore-revs
├── .gitattributes
├── .github/
│ ├── dependabot.yml
│ └── workflows/
│ ├── check-changelog.yml
│ ├── dockgen.yml
│ ├── macos-linux-pip.yml
│ ├── macos-linux-windows-pixi.yml
│ ├── nix.yml
│ ├── ros_ci.yml
│ ├── update-flake-lock.yml
│ └── update_pixi_lockfile.yml
├── .gitignore
├── .gitlab-ci.yml
├── .gitmodules
├── .pre-commit-config.yaml
├── CHANGELOG.md
├── CITATION.bib
├── CITATION.cff
├── CMakeLists.txt
├── LICENSE
├── README.md
├── colcon.pkg
├── development/
│ ├── build.md
│ ├── release.md
│ └── scripts/
│ └── pixi/
│ ├── activation.bat
│ └── activation.sh
├── doc/
│ ├── CMakeLists.txt
│ ├── Doxyfile.extra.in
│ ├── generate_distance_plot.py
│ ├── gjk.py
│ ├── mesh-mesh-collision-call.dot
│ ├── notes
│ ├── python/
│ │ ├── doxygen-boost.hh
│ │ ├── doxygen.hh
│ │ ├── doxygen_xml_parser.py
│ │ └── xml_docstring.py
│ ├── shape-mesh-collision-call.dot
│ └── shape-shape-collision-call.dot
├── dockgen.toml
├── flake.nix
├── hpp-fclConfig.cmake
├── include/
│ ├── coal/
│ │ ├── BV/
│ │ │ ├── AABB.h
│ │ │ ├── BV.h
│ │ │ ├── BV_node.h
│ │ │ ├── OBB.h
│ │ │ ├── OBBRSS.h
│ │ │ ├── RSS.h
│ │ │ ├── kDOP.h
│ │ │ └── kIOS.h
│ │ ├── BVH/
│ │ │ ├── BVH_front.h
│ │ │ ├── BVH_internal.h
│ │ │ ├── BVH_model.h
│ │ │ └── BVH_utility.h
│ │ ├── alloca.h
│ │ ├── broadphase/
│ │ │ ├── broadphase.h
│ │ │ ├── broadphase_SSaP.h
│ │ │ ├── broadphase_SaP.h
│ │ │ ├── broadphase_bruteforce.h
│ │ │ ├── broadphase_callbacks.h
│ │ │ ├── broadphase_collision_manager.h
│ │ │ ├── broadphase_continuous_collision_manager-inl.h
│ │ │ ├── broadphase_continuous_collision_manager.h
│ │ │ ├── broadphase_dynamic_AABB_tree-inl.h
│ │ │ ├── broadphase_dynamic_AABB_tree.h
│ │ │ ├── broadphase_dynamic_AABB_tree_array-inl.h
│ │ │ ├── broadphase_dynamic_AABB_tree_array.h
│ │ │ ├── broadphase_interval_tree.h
│ │ │ ├── broadphase_spatialhash-inl.h
│ │ │ ├── broadphase_spatialhash.h
│ │ │ ├── default_broadphase_callbacks.h
│ │ │ └── detail/
│ │ │ ├── hierarchy_tree-inl.h
│ │ │ ├── hierarchy_tree.h
│ │ │ ├── hierarchy_tree_array-inl.h
│ │ │ ├── hierarchy_tree_array.h
│ │ │ ├── interval_tree.h
│ │ │ ├── interval_tree_node-inl.h
│ │ │ ├── interval_tree_node.h
│ │ │ ├── morton-inl.h
│ │ │ ├── morton.h
│ │ │ ├── node_base-inl.h
│ │ │ ├── node_base.h
│ │ │ ├── node_base_array-inl.h
│ │ │ ├── node_base_array.h
│ │ │ ├── simple_hash_table-inl.h
│ │ │ ├── simple_hash_table.h
│ │ │ ├── simple_interval-inl.h
│ │ │ ├── simple_interval.h
│ │ │ ├── sparse_hash_table-inl.h
│ │ │ ├── sparse_hash_table.h
│ │ │ ├── spatial_hash-inl.h
│ │ │ └── spatial_hash.h
│ │ ├── collision.h
│ │ ├── collision_data.h
│ │ ├── collision_func_matrix.h
│ │ ├── collision_object.h
│ │ ├── collision_utility.h
│ │ ├── contact_patch/
│ │ │ ├── contact_patch_simplifier.h
│ │ │ ├── contact_patch_solver.h
│ │ │ ├── contact_patch_solver.hxx
│ │ │ └── polygon_convex_hull.h
│ │ ├── contact_patch.h
│ │ ├── contact_patch_func_matrix.h
│ │ ├── data_types.h
│ │ ├── distance.h
│ │ ├── distance_func_matrix.h
│ │ ├── doc.hh
│ │ ├── fwd.hh
│ │ ├── hfield.h
│ │ ├── internal/
│ │ │ ├── BV_fitter.h
│ │ │ ├── BV_splitter.h
│ │ │ ├── intersect.h
│ │ │ ├── intersect.hxx
│ │ │ ├── shape_shape_contact_patch_func.h
│ │ │ ├── shape_shape_func.h
│ │ │ ├── tools.h
│ │ │ ├── traversal.h
│ │ │ ├── traversal_node_base.h
│ │ │ ├── traversal_node_bvh_hfield.h
│ │ │ ├── traversal_node_bvh_shape.h
│ │ │ ├── traversal_node_bvhs.h
│ │ │ ├── traversal_node_hfield_shape.h
│ │ │ ├── traversal_node_octree.h
│ │ │ ├── traversal_node_setup.h
│ │ │ ├── traversal_node_shapes.h
│ │ │ └── traversal_recurse.h
│ │ ├── logging.h
│ │ ├── math/
│ │ │ ├── matrix_3f.h
│ │ │ ├── transform.h
│ │ │ ├── types.h
│ │ │ └── vec_3f.h
│ │ ├── mesh_loader/
│ │ │ ├── assimp.h
│ │ │ └── loader.h
│ │ ├── narrowphase/
│ │ │ ├── gjk.h
│ │ │ ├── minkowski_difference.h
│ │ │ ├── narrowphase.h
│ │ │ ├── narrowphase_defaults.h
│ │ │ ├── support_data.h
│ │ │ └── support_functions.h
│ │ ├── octree.h
│ │ ├── serialization/
│ │ │ ├── AABB.h
│ │ │ ├── BVH_model.h
│ │ │ ├── BV_node.h
│ │ │ ├── BV_splitter.h
│ │ │ ├── OBB.h
│ │ │ ├── OBBRSS.h
│ │ │ ├── RSS.h
│ │ │ ├── archive.h
│ │ │ ├── collision_data.h
│ │ │ ├── collision_object.h
│ │ │ ├── contact_patch.h
│ │ │ ├── convex.h
│ │ │ ├── eigen.h
│ │ │ ├── fwd.h
│ │ │ ├── geometric_shapes.h
│ │ │ ├── hfield.h
│ │ │ ├── kDOP.h
│ │ │ ├── kIOS.h
│ │ │ ├── memory.h
│ │ │ ├── octree.h
│ │ │ ├── quadrilateral.h
│ │ │ ├── serializer.h
│ │ │ ├── transform.h
│ │ │ └── triangle.h
│ │ ├── shape/
│ │ │ ├── convex.h
│ │ │ ├── convex.hxx
│ │ │ ├── geometric_shape_to_BVH_model.h
│ │ │ ├── geometric_shapes.h
│ │ │ ├── geometric_shapes.hxx
│ │ │ ├── geometric_shapes_traits.h
│ │ │ └── geometric_shapes_utility.h
│ │ ├── shared_ptr_comparison.h
│ │ ├── third_party/
│ │ │ └── boost/
│ │ │ └── core/
│ │ │ ├── data.hpp
│ │ │ ├── detail/
│ │ │ │ └── assert.hpp
│ │ │ ├── make_span.hpp
│ │ │ └── span.hpp
│ │ └── timings.h
│ └── hpp/
│ └── fcl/
│ ├── BV/
│ │ ├── AABB.h
│ │ ├── BV.h
│ │ ├── BV_node.h
│ │ ├── OBB.h
│ │ ├── OBBRSS.h
│ │ ├── RSS.h
│ │ ├── kDOP.h
│ │ └── kIOS.h
│ ├── BVH/
│ │ ├── BVH_front.h
│ │ ├── BVH_internal.h
│ │ ├── BVH_model.h
│ │ └── BVH_utility.h
│ ├── broadphase/
│ │ ├── broadphase.h
│ │ ├── broadphase_SSaP.h
│ │ ├── broadphase_SaP.h
│ │ ├── broadphase_bruteforce.h
│ │ ├── broadphase_callbacks.h
│ │ ├── broadphase_collision_manager.h
│ │ ├── broadphase_continuous_collision_manager-inl.h
│ │ ├── broadphase_continuous_collision_manager.h
│ │ ├── broadphase_dynamic_AABB_tree-inl.h
│ │ ├── broadphase_dynamic_AABB_tree.h
│ │ ├── broadphase_dynamic_AABB_tree_array-inl.h
│ │ ├── broadphase_dynamic_AABB_tree_array.h
│ │ ├── broadphase_interval_tree.h
│ │ ├── broadphase_spatialhash-inl.h
│ │ ├── broadphase_spatialhash.h
│ │ ├── default_broadphase_callbacks.h
│ │ └── detail/
│ │ ├── hierarchy_tree-inl.h
│ │ ├── hierarchy_tree.h
│ │ ├── hierarchy_tree_array-inl.h
│ │ ├── hierarchy_tree_array.h
│ │ ├── interval_tree.h
│ │ ├── interval_tree_node.h
│ │ ├── morton-inl.h
│ │ ├── morton.h
│ │ ├── node_base-inl.h
│ │ ├── node_base.h
│ │ ├── node_base_array-inl.h
│ │ ├── node_base_array.h
│ │ ├── simple_hash_table-inl.h
│ │ ├── simple_hash_table.h
│ │ ├── simple_interval-inl.h
│ │ ├── simple_interval.h
│ │ ├── sparse_hash_table-inl.h
│ │ ├── sparse_hash_table.h
│ │ ├── spatial_hash-inl.h
│ │ └── spatial_hash.h
│ ├── coal.hpp
│ ├── collision.h
│ ├── collision_data.h
│ ├── collision_func_matrix.h
│ ├── collision_object.h
│ ├── collision_utility.h
│ ├── config.hh
│ ├── contact_patch/
│ │ ├── contact_patch_solver.h
│ │ └── contact_patch_solver.hxx
│ ├── contact_patch.h
│ ├── contact_patch_func_matrix.h
│ ├── data_types.h
│ ├── deprecated.hh
│ ├── distance.h
│ ├── distance_func_matrix.h
│ ├── fwd.hh
│ ├── hfield.h
│ ├── internal/
│ │ ├── BV_fitter.h
│ │ ├── BV_splitter.h
│ │ ├── intersect.h
│ │ ├── shape_shape_contact_patch_func.h
│ │ ├── shape_shape_func.h
│ │ ├── tools.h
│ │ ├── traversal.h
│ │ ├── traversal_node_base.h
│ │ ├── traversal_node_bvh_shape.h
│ │ ├── traversal_node_bvhs.h
│ │ ├── traversal_node_hfield_shape.h
│ │ ├── traversal_node_octree.h
│ │ ├── traversal_node_setup.h
│ │ ├── traversal_node_shapes.h
│ │ └── traversal_recurse.h
│ ├── logging.h
│ ├── math/
│ │ ├── matrix_3f.h
│ │ ├── transform.h
│ │ ├── types.h
│ │ └── vec_3f.h
│ ├── mesh_loader/
│ │ ├── assimp.h
│ │ └── loader.h
│ ├── narrowphase/
│ │ ├── gjk.h
│ │ ├── minkowski_difference.h
│ │ ├── narrowphase.h
│ │ ├── narrowphase_defaults.h
│ │ ├── support_data.h
│ │ ├── support_functions.h
│ │ └── support_functions.hxx
│ ├── octree.h
│ ├── serialization/
│ │ ├── AABB.h
│ │ ├── BVH_model.h
│ │ ├── BV_node.h
│ │ ├── BV_splitter.h
│ │ ├── OBB.h
│ │ ├── OBBRSS.h
│ │ ├── RSS.h
│ │ ├── archive.h
│ │ ├── collision_data.h
│ │ ├── collision_object.h
│ │ ├── contact_patch.h
│ │ ├── convex.h
│ │ ├── eigen.h
│ │ ├── fwd.h
│ │ ├── geometric_shapes.h
│ │ ├── hfield.h
│ │ ├── kDOP.h
│ │ ├── kIOS.h
│ │ ├── memory.h
│ │ ├── octree.h
│ │ ├── quadrilateral.h
│ │ ├── serializer.h
│ │ ├── transform.h
│ │ └── triangle.h
│ ├── shape/
│ │ ├── convex.h
│ │ ├── convex.hxx
│ │ ├── geometric_shape_to_BVH_model.h
│ │ ├── geometric_shapes.h
│ │ ├── geometric_shapes.hxx
│ │ ├── geometric_shapes_traits.h
│ │ └── geometric_shapes_utility.h
│ ├── timings.h
│ └── warning.hh
├── package.xml
├── pixi.toml
├── python/
│ ├── CMakeLists.txt
│ ├── broadphase/
│ │ ├── broadphase.cc
│ │ ├── broadphase_callbacks.hh
│ │ ├── broadphase_collision_manager.hh
│ │ └── fwd.hh
│ ├── coal/
│ │ ├── __init__.py
│ │ ├── viewer.py
│ │ └── windows_dll_manager.py
│ ├── coal.cc
│ ├── coal.hh
│ ├── collision-geometries.cc
│ ├── collision.cc
│ ├── contact_patch.cc
│ ├── deprecation.hh
│ ├── distance.cc
│ ├── fwd.hh
│ ├── gjk.cc
│ ├── hppfcl/
│ │ ├── __init__.py
│ │ └── viewer.py
│ ├── math.cc
│ ├── octree.cc
│ ├── pickle.hh
│ ├── printable.hh
│ ├── serializable.hh
│ ├── utils/
│ │ └── std-pair.hh
│ └── version.cc
├── python-nb/
│ ├── CMakeLists.txt
│ ├── aabb.cc
│ ├── broadphase/
│ │ ├── broadphase.cc
│ │ └── broadphase_callbacks_collision_manager.hh
│ ├── bvh.cc
│ ├── coal/
│ │ ├── __init__.py
│ │ └── windows_dll_manager.py
│ ├── collision-geometries.cc
│ ├── collision.cc
│ ├── contact_patch.cc
│ ├── distance.cc
│ ├── fwd.h
│ ├── gjk.cc
│ ├── height_field.cc
│ ├── math.cc
│ ├── memory-footprint.cc
│ ├── module.cc
│ ├── octree.cc
│ ├── pickle.hh
│ ├── serializable.hh
│ └── shapes.cc
├── src/
│ ├── BV/
│ │ ├── AABB.cpp
│ │ ├── OBB.cpp
│ │ ├── OBB.h
│ │ ├── OBBRSS.cpp
│ │ ├── RSS.cpp
│ │ ├── kDOP.cpp
│ │ └── kIOS.cpp
│ ├── BVH/
│ │ ├── BVH_model.cpp
│ │ ├── BVH_utility.cpp
│ │ ├── BV_fitter.cpp
│ │ └── BV_splitter.cpp
│ ├── CMakeLists.txt
│ ├── broadphase/
│ │ ├── broadphase_SSaP.cpp
│ │ ├── broadphase_SaP.cpp
│ │ ├── broadphase_bruteforce.cpp
│ │ ├── broadphase_collision_manager.cpp
│ │ ├── broadphase_dynamic_AABB_tree.cpp
│ │ ├── broadphase_dynamic_AABB_tree_array.cpp
│ │ ├── broadphase_interval_tree.cpp
│ │ ├── default_broadphase_callbacks.cpp
│ │ └── detail/
│ │ ├── interval_tree.cpp
│ │ ├── interval_tree_node.cpp
│ │ ├── morton-inl.h
│ │ ├── morton.cpp
│ │ ├── simple_interval.cpp
│ │ └── spatial_hash.cpp
│ ├── collision.cpp
│ ├── collision_data.cpp
│ ├── collision_func_matrix.cpp
│ ├── collision_node.cpp
│ ├── collision_node.h
│ ├── collision_object.cpp
│ ├── collision_utility.cpp
│ ├── contact_patch/
│ │ ├── contact_patch_simplifier.cpp
│ │ ├── contact_patch_solver.cpp
│ │ └── polygon_convex_hull.cpp
│ ├── contact_patch.cpp
│ ├── contact_patch_func_matrix.cpp
│ ├── distance/
│ │ ├── box_halfspace.cpp
│ │ ├── box_plane.cpp
│ │ ├── box_sphere.cpp
│ │ ├── capsule_capsule.cpp
│ │ ├── capsule_halfspace.cpp
│ │ ├── capsule_plane.cpp
│ │ ├── cone_halfspace.cpp
│ │ ├── cone_plane.cpp
│ │ ├── convex_halfspace.cpp
│ │ ├── convex_plane.cpp
│ │ ├── cylinder_halfspace.cpp
│ │ ├── cylinder_plane.cpp
│ │ ├── ellipsoid_halfspace.cpp
│ │ ├── ellipsoid_plane.cpp
│ │ ├── halfspace_halfspace.cpp
│ │ ├── halfspace_plane.cpp
│ │ ├── plane_plane.cpp
│ │ ├── sphere_capsule.cpp
│ │ ├── sphere_cylinder.cpp
│ │ ├── sphere_halfspace.cpp
│ │ ├── sphere_plane.cpp
│ │ ├── sphere_sphere.cpp
│ │ ├── triangle_halfspace.cpp
│ │ ├── triangle_plane.cpp
│ │ ├── triangle_sphere.cpp
│ │ └── triangle_triangle.cpp
│ ├── distance.cpp
│ ├── distance_func_matrix.cpp
│ ├── hfield.cpp
│ ├── intersect.cpp
│ ├── math/
│ │ └── transform.cpp
│ ├── mesh_loader/
│ │ ├── assimp.cpp
│ │ └── loader.cpp
│ ├── narrowphase/
│ │ ├── details.h
│ │ ├── gjk.cpp
│ │ ├── minkowski_difference.cpp
│ │ └── support_functions.cpp
│ ├── octree.cpp
│ ├── serialization/
│ │ └── serialization.cpp
│ ├── shape/
│ │ ├── geometric_shapes.cpp
│ │ └── geometric_shapes_utility.cpp
│ ├── traits_traversal.h
│ └── traversal/
│ └── traversal_recurse.cpp
└── test/
├── CMakeLists.txt
├── accelerated_gjk.cpp
├── alloca.cpp
├── benchmark/
│ └── test_fcl_gjk.output
├── benchmark.cpp
├── box_box_collision.cpp
├── box_box_distance.cpp
├── broadphase.cpp
├── broadphase_collision_1.cpp
├── broadphase_collision_2.cpp
├── broadphase_dynamic_AABB_tree.cpp
├── bvh_models.cpp
├── capsule_box_1.cpp
├── capsule_box_2.cpp
├── capsule_capsule.cpp
├── collision.cpp
├── collision_node_asserts.cpp
├── contact_patch.cpp
├── convex.cpp
├── distance.cpp
├── distance_lower_bound.cpp
├── fcl_resources/
│ ├── config.h.in
│ ├── env.obj
│ ├── env.octree
│ ├── illformated_mesh.dae
│ ├── rob.obj
│ └── staircases_koroibot_hr.dae
├── frontlist.cpp
├── geometric_shapes.cpp
├── gjk-geometric-tools-benchmark
├── gjk.cpp
├── gjk_asserts.cpp
├── gjk_convergence_criterion.cpp
├── hfields.cpp
├── math.cpp
├── normal_and_nearest_points.cpp
├── obb.cpp
├── octree.cpp
├── patch_simplifier.cpp
├── pixi_build/
│ └── CMakeLists.txt
├── polygon_convex_hull.cpp
├── profiling.cpp
├── python_unit/
│ ├── CMakeLists.txt
│ ├── api.py
│ ├── collision.py
│ ├── collision_manager.py
│ ├── geometric_shapes.py
│ ├── pickling.py
│ └── test_case.py
├── scripts/
│ ├── collision-bench.py
│ ├── collision.py
│ ├── distance_lower_bound.py
│ ├── geometric_shapes.py
│ ├── gjk.py
│ ├── obb.py
│ └── octree.py
├── security_margin.cpp
├── serialization.cpp
├── shape_inflation.cpp
├── shape_mesh_consistency.cpp
├── simple.cpp
├── swept_sphere_radius.cpp
├── utility.cpp
└── utility.h
================================================
FILE CONTENTS
================================================
================================================
FILE: .clang-format
================================================
BasedOnStyle: Google
SortIncludes: false
================================================
FILE: .gersemirc
================================================
definitions: [./CMakeLists.txt,./cmake,./python,./src,./test]
line_length: 80
indent: 2
warn_about_unknown_commands: false
================================================
FILE: .git-blame-ignore-revs
================================================
0067c8aa66aac548601e2a3fd029aa264cc59f2a
76b68f785df31b00e153290b45ec290a9c5f7963
# ruff --fix . (Guilhem Saurel, 2023-10-25)
02cef56abfacee590c8444fd379c8837bf007fa1
# black . (Guilhem Saurel, 2023-10-25)
febfbcbe9c98cdb4e0c7bbf4554a6925b391834b
# ruff --fix . (Guilhem Saurel, 2023-10-24)
58dee5ae90eded5125825a2da0fe76a5031f3334
# black . (Guilhem Saurel, 2023-10-24)
889ff8d1ca00b9e317e1da4136e233bb49a049df
# pre-commit run -all (ManifoldFR, 2025-02-12)
3c3494086db02747bf858142bc3be5cbc244385f
================================================
FILE: .gitattributes
================================================
# SCM syntax highlighting
pixi.lock linguist-language=YAML linguist-generated=true
================================================
FILE: .github/dependabot.yml
================================================
version: 2
updates:
- package-ecosystem: github-actions
directory: /
target-branch: devel
schedule:
interval: monthly
================================================
FILE: .github/workflows/check-changelog.yml
================================================
name: Check-changelog
on:
pull_request:
types: [assigned, opened, synchronize, reopened, labeled, unlabeled]
branches:
- devel
jobs:
check-changelog:
name: Check changelog action
runs-on: ubuntu-latest
steps:
- uses: tarides/changelog-check-action@v3
with:
changelog: CHANGELOG.md
================================================
FILE: .github/workflows/dockgen.yml
================================================
name: "Publish docker image"
on:
push:
branches:
- devel
tags:
- "v*"
jobs:
dockgen:
runs-on: "ubuntu-latest"
permissions:
contents: read
packages: write
attestations: write
id-token: write
steps:
- uses: actions/checkout@v6
- uses: astral-sh/setup-uv@v7
- run: uvx dockgen
- run: cat Dockerfile
# https://docs.github.com/en/packages/managing-github-packages-using-github-actions-workflows/publishing-and-installing-a-package-with-github-actions
- name: Log in to the Container registry
uses: docker/login-action@v4
with:
registry: ghcr.io
username: ${{ github.actor }}
password: ${{ secrets.GITHUB_TOKEN }}
- name: Extract metadata (tags, labels) for Docker
id: meta
uses: docker/metadata-action@v6
with:
images: ghcr.io/${{ github.repository }}
- name: Build and push Docker image
id: push
uses: docker/build-push-action@v7
with:
context: .
push: true
tags: ${{ steps.meta.outputs.tags }}
labels: ${{ steps.meta.outputs.labels }}
- name: Generate artifact attestation
uses: actions/attest-build-provenance@v4
with:
subject-name: ghcr.io/${{ github.repository }}
subject-digest: ${{ steps.push.outputs.digest }}
push-to-registry: true
================================================
FILE: .github/workflows/macos-linux-pip.yml
================================================
name: CI - MacOS/Linux via pip
on:
push:
branches:
- devel
paths-ignore:
- .gitlab-ci.yml
- .gitignore
- '**.md'
- CITATION.*
- LICENSE
- colcon.pkg
- .pre-commit-config.yaml
pull_request:
paths-ignore:
- .gitlab-ci.yml
- .gitignore
- '**.md'
- CITATION.*
- LICENSE
- colcon.pkg
- .pre-commit-config.yaml
concurrency:
group: ${{ github.workflow }}-${{ github.ref }}
cancel-in-progress: true
env:
CTEST_OUTPUT_ON_FAILURE: 1
CTEST_PARALLEL_LEVEL: 4
jobs:
coal-pip:
name: "CI on ${{ matrix.os }} / py ${{ matrix.python-version }} with pip"
runs-on: "${{ matrix.os }}-latest"
strategy:
fail-fast: false
matrix:
os: ["ubuntu", "macos"]
python-version: ["3.8", "3.9", "3.10", "3.11", "3.12", "3.13"]
exclude:
- os: "macos"
python-version: "3.8" # Not available on arm64
steps:
- uses: actions/checkout@v6
with:
submodules: 'true'
- uses: actions/setup-python@v6
with:
python-version: ${{ matrix.python-version }}
- run: python -m pip install -U pip
- run: python -m pip install cmeel-assimp cmeel-octomap cmeel-qhull eigenpy[build]
- run: echo "CMAKE_PREFIX_PATH=$(cmeel cmake)" >> $GITHUB_ENV
- run: cmake -B build -S . -DPython_EXECUTABLE=$(which python) -DCOAL_HAS_QHULL=ON -DCOAL_PYTHON_NANOBIND=OFF
- run: cmake --build build -j 4
- run: cmake --build build -t test
================================================
FILE: .github/workflows/macos-linux-windows-pixi.yml
================================================
name: CI - MacOS/Linux/Windows via Pixi
on:
push:
branches:
- devel
paths-ignore:
- .gitlab-ci.yml
- .gitignore
- '**.md'
- CITATION.*
- LICENSE
- colcon.pkg
- .pre-commit-config.yaml
pull_request:
paths-ignore:
- .gitlab-ci.yml
- .gitignore
- '**.md'
- CITATION.*
- LICENSE
- colcon.pkg
- .pre-commit-config.yaml
concurrency:
group: ${{ github.workflow }}-${{ github.ref }}
cancel-in-progress: true
jobs:
coal-pixi:
name: Standard - ${{ matrix.os }} - Env ${{ matrix.environment }} ${{ matrix.build_type }} ${{ matrix.cxx_options }}
runs-on: ${{ matrix.os }}
env:
CCACHE_BASEDIR: "${GITHUB_WORKSPACE}"
CCACHE_DIR: "${GITHUB_WORKSPACE}/.ccache"
CCACHE_COMPRESS: true
CCACHE_COMPRESSLEVEL: 6
# Since pixi will install a compiler, the compiler mtime will be changed.
# This can invalidate the cache (https://ccache.dev/manual/latest.html#config_compiler_check)
CCACHE_COMPILERCHECK: content
strategy:
fail-fast: false
matrix:
os: [ubuntu-latest, macos-latest, macos-15-intel]
environment: [all, all-python-oldest, all-boost-python]
build_type: [Release, Debug]
cxx_options: ['', '-mavx2']
exclude:
- os: macos-latest
cxx_options: '-mavx2'
- os: macos-15-intel
cxx_options: '-mavx2'
include:
- os: windows-latest
environment: all
cxx_options: ''
build_type: Release
- os: windows-latest
environment: all-boost-python
cxx_options: ''
build_type: Release
- os: windows-latest
environment: all-clang-cl
cxx_options: ''
build_type: Release
- os: windows-latest
environment: default
cxx_options: ''
build_type: Debug
steps:
- uses: actions/checkout@v6
with:
submodules: recursive
- uses: actions/cache@v5
with:
path: .ccache
key: ccache-macos-linux-windows-pixi-${{ matrix.os }}-${{ matrix.build_type }}-${{ matrix.cxx_options }}-${{ matrix.environment }}-${{ github.sha }}
restore-keys: ccache-macos-linux-windows-pixi-${{ matrix.os }}-${{ matrix.build_type }}-${{ matrix.cxx_options }}-${{ matrix.environment }}-
- uses: prefix-dev/setup-pixi@v0.9.5
with:
cache: true
environments: ${{ matrix.environment }}
- name: Clear ccache statistics [MacOS/Linux/Windows]
run: |
pixi run -e ${{ matrix.environment }} ccache -z
- name: Build Coal [MacOS/Linux/Windows]
env:
CMAKE_BUILD_PARALLEL_LEVEL: 2
COAL_BUILD_TYPE: ${{ matrix.build_type }}
COAL_CXX_FLAGS: ${{ matrix.cxx_options }}
run: |
pixi run -e ${{ matrix.environment }} build
- name: Test Coal [MacOS/Linux/Windows]
if: ${{ ! (contains(matrix.os, 'windows') && matrix.build_type == 'Debug') }}
run: |
pixi run -e ${{ matrix.environment }} ctest --test-dir build --output-on-failure
- name: Show ccache statistics [MacOS/Linux/Windows]
run: |
pixi run -e ${{ matrix.environment }} ccache -sv
coal-python-standalone-pixi:
name: Python standalone - ${{ matrix.os }} - Env ${{ matrix.environment }}
runs-on: ${{ matrix.os }}
env:
CCACHE_BASEDIR: "${GITHUB_WORKSPACE}"
CCACHE_DIR: "${GITHUB_WORKSPACE}/.ccache"
CCACHE_COMPRESS: true
CCACHE_COMPRESSLEVEL: 6
# Since pixi will install a compiler, the compiler mtime will be changed.
# This can invalidate the cache (https://ccache.dev/manual/latest.html#config_compiler_check)
CCACHE_COMPILERCHECK: content
strategy:
fail-fast: false
matrix:
os: [ubuntu-latest, macos-latest, macos-15-intel, windows-latest]
environment: [all, all-boost-python]
steps:
- uses: actions/checkout@v6
with:
submodules: recursive
- uses: actions/cache@v5
with:
path: .ccache
key: ccache-python-standalone-macos-linux-windows-pixi-${{ matrix.os }}-${{ matrix.environment }}-${{ github.sha }}
restore-keys: ccache-python-standalone-macos-linux-windows-pixi-${{ matrix.os }}-${{ matrix.environment }}-
- uses: prefix-dev/setup-pixi@v0.9.5
with:
cache: true
environments: ${{ matrix.environment }}
- name: Clear ccache statistics [MacOS/Linux/Windows]
run: |
pixi run -e ${{ matrix.environment }} ccache -z
- name: Build Coal cpp [MacOS/Linux/Windows]
env:
CMAKE_BUILD_PARALLEL_LEVEL: 2
shell: bash -el {0}
run: |
pixi run -e ${{ matrix.environment }} configure \
-DBUILD_PYTHON_INTERFACE=OFF \
-B build_cpp
pixi run -e ${{ matrix.environment }} cmake --build build_cpp --target all
pixi run -e ${{ matrix.environment }} cmake --install build_cpp
- name: Build Coal standalone python [MacOS/Linux/Windows]
env:
CMAKE_BUILD_PARALLEL_LEVEL: 2
shell: bash -el {0}
run: |
pixi run -e ${{ matrix.environment }} configure \
-DBUILD_PYTHON_INTERFACE=ON \
-DBUILD_STANDALONE_PYTHON_INTERFACE=ON \
-B build_python
pixi run -e ${{ matrix.environment }} cmake --build build_python --target all
pixi run -e ${{ matrix.environment }} cmake --install build_python
pixi run -e ${{ matrix.environment }} python -c "import coal"
- name: Show ccache statistics [MacOS/Linux/Windows]
run: |
pixi run -e ${{ matrix.environment }} ccache -sv
# coal-pixi-build:
# name: Pixi build - ${{ matrix.os }}
# runs-on: ${{ matrix.os }}
# strategy:
# fail-fast: false
# matrix:
# os: [ubuntu-latest, macos-latest, macos-15-intel, windows-latest]
# steps:
# - uses: actions/checkout@v6
# with:
# submodules: recursive
# - uses: prefix-dev/setup-pixi@v0.9.5
# env:
# CMAKE_BUILD_PARALLEL_LEVEL: 2
# with:
# cache: true
# environments: test-pixi-build
# - name: Test package [MacOS/Linux/Windows]
# run: |
# pixi run -e test-pixi-build test
check:
if: always()
name: check-macos-linux-windows-pixi
needs:
- coal-pixi
- coal-python-standalone-pixi
# - coal-pixi-build
runs-on: Ubuntu-latest
steps:
- name: Decide whether the needed jobs succeeded or failed
uses: re-actors/alls-green@release/v1
with:
jobs: ${{ toJSON(needs) }}
================================================
FILE: .github/workflows/nix.yml
================================================
name: "CI - Nix"
on:
push:
branches:
- devel
pull_request:
concurrency:
group: ${{ github.workflow }}-${{ github.ref }}
cancel-in-progress: true
jobs:
nix:
runs-on: "${{ matrix.os }}-latest"
strategy:
matrix:
os: [ubuntu, macos]
extends: ["", "pkgs-eigen5", "pkgs-full", "pkgs-nanobind"]
steps:
- uses: actions/checkout@v6
- uses: cachix/install-nix-action@v31
- uses: cachix/cachix-action@v17
with:
name: gepetto
authToken: '${{ secrets.CACHIX_AUTH_TOKEN }}'
- run: nix flake check -L
- run: nix build -L ".#${{ matrix.extends }}"
check:
if: always()
name: check-macos-linux-nix
runs-on: ubuntu-latest
needs:
- nix
steps:
- uses: re-actors/alls-green@release/v1
with:
jobs: ${{ toJSON(needs) }}
================================================
FILE: .github/workflows/ros_ci.yml
================================================
# This config uses industrial_ci (https://github.com/ros-industrial/industrial_ci.git).
# For troubleshooting, see readme (https://github.com/ros-industrial/industrial_ci/blob/master/README.rst)
name: ROS-CI
# This determines when this workflow is run
on:
push:
branches:
- devel
paths-ignore:
- .gitlab-ci.yml
- .gitignore
- '**.md'
- CITATION.*
- LICENSE
- .pre-commit-config.yaml
pull_request:
paths-ignore:
- .gitlab-ci.yml
- .gitignore
- '**.md'
- CITATION.*
- LICENSE
- .pre-commit-config.yaml
concurrency:
group: ${{ github.workflow }}-${{ github.ref }}
cancel-in-progress: true
jobs:
ros:
name: ROS ${{ matrix.ROS_DISTRO }} - ${{ matrix.os }}
strategy:
fail-fast: false
matrix:
include:
# ROS2 Humble Hawksbill (May 2022 - May 2027)
- ROS_DISTRO: humble
os: Ubuntu 22.04 (Jammy)
# ROS2 Jazzy Jalisco (May 2024 - May 2029)
- ROS_DISTRO: jazzy
os: Ubuntu 24.04 (Noble)
# ROS2 Kilted Kayu (May 2025 - December 2026)
- ROS_DISTRO: kilted
os: Ubuntu 24.04 (Noble)
# ROS2 Rolling Ridley
- ROS_DISTRO: rolling
os: Ubuntu 24.04 (Noble)
env:
CMAKE_ARGS: -DBUILD_PYTHON_INTERFACE=ON -DCOAL_BUILD_TESTS=ON -DCOAL_BUILD_BENCHMARKS=ON
VERBOSE_OUTPUT: true
VERBOSE_TESTS: true
ROS_DISTRO: ${{ matrix.ROS_DISTRO }}
CCACHE_DIR: ${{ github.workspace }}/.ccache
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v6
- uses: actions/cache@v5
with:
path: ${{ env.CCACHE_DIR }}
key: ccache-${{ matrix.ROS_DISTRO }}-${{github.run_id}}
restore-keys: ccache-${{ matrix.ROS_DISTRO }}-
- uses: ros-industrial/industrial_ci@f3c2dc8b4a9e6215f9c00f83e86ca0692970f81d
check:
if: always()
name: check-ros-ci
needs:
- ros
runs-on: ubuntu-latest
steps:
- name: Decide whether the needed jobs succeeded or failed
uses: re-actors/alls-green@release/v1
with:
jobs: ${{ toJSON(needs) }}
================================================
FILE: .github/workflows/update-flake-lock.yml
================================================
name: update-flake-lock
on:
workflow_dispatch:
schedule:
- cron: '0 11 12 * *'
jobs:
update-flake-inputs:
runs-on: ubuntu-slim
permissions:
contents: write
pull-requests: write
steps:
- name: Generate GitHub App Token
id: app-token
uses: actions/create-github-app-token@v3
with:
app-id: ${{ secrets.GEPETTO_NIX_APP_ID }}
private-key: ${{ secrets.GEPETTO_NIX_APP_PRIVATE_KEY }}
- name: Checkout repository
uses: actions/checkout@v6
with:
token: ${{ steps.app-token.outputs.token }}
- name: Setup Nix
uses: cachix/install-nix-action@v31
- name: Update flake inputs
uses: mic92/update-flake-inputs@v1
with:
github-token: ${{ steps.app-token.outputs.token }}
pr-labels: 'no-changelog'
git-author-name: 'hrp2-14'
git-author-email: '40568249+hrp2-14@users.noreply.github.com'
================================================
FILE: .github/workflows/update_pixi_lockfile.yml
================================================
name: CI - Update Pixi lockfile
permissions:
contents: write
pull-requests: write
on:
workflow_dispatch:
schedule:
- cron: 0 5 1 * *
jobs:
pixi-update:
runs-on: ubuntu-latest
steps:
- uses: actions/create-github-app-token@v3
id: generate-token
with:
app-id: ${{ secrets.APP_ID }}
private-key: ${{ secrets.APP_PRIVATE_KEY }}
- uses: actions/checkout@v6
with:
token: ${{ steps.generate-token.outputs.token }}
ref: devel
# Make sure the value of GITHUB_TOKEN will not be persisted in repo's config
persist-credentials: false
- name: Set up pixi
uses: prefix-dev/setup-pixi@v0.9.5
with:
run-install: false
- name: Update lockfile
run: |
set -o pipefail
pixi update --json | pixi exec pixi-diff-to-markdown >> diff.md
- name: Create pull request
uses: peter-evans/create-pull-request@v8
with:
token: ${{ steps.generate-token.outputs.token }}
commit-message: 'pixi: Update pixi lockfile'
title: Update pixi lockfile
body-path: diff.md
branch: topic/update-pixi
base: devel
labels: |
pixi
no changelog
delete-branch: true
add-paths: pixi.lock
================================================
FILE: .gitignore
================================================
build*/
Xcode/*
*~
*.pyc
.cache/
__pycache__/
# pixi environments
.pixi
*.egg-info
================================================
FILE: .gitlab-ci.yml
================================================
include: https://rainboard.laas.fr/project/coal/.gitlab-ci.yml
================================================
FILE: .gitmodules
================================================
[submodule "cmake"]
branch = master
path = cmake
url = https://github.com/jrl-umi3218/jrl-cmakemodules.git
================================================
FILE: .pre-commit-config.yaml
================================================
ci:
autoupdate_branch: devel
autofix_prs: false
autoupdate_schedule: quarterly
submodules: true
repos:
- repo: https://github.com/astral-sh/ruff-pre-commit
rev: v0.15.9
hooks:
- id: ruff
args:
- --fix
- --exit-non-zero-on-fix
- id: ruff-format
- repo: https://github.com/pre-commit/mirrors-clang-format
rev: v22.1.2
hooks:
- id: clang-format
- repo: https://github.com/pre-commit/pre-commit-hooks
rev: v6.0.0
hooks:
- id: trailing-whitespace
- repo: https://github.com/BlankSpruce/gersemi
rev: 0.26.1
hooks:
- id: gersemi
================================================
FILE: CHANGELOG.md
================================================
# Changelog
All notable changes to this project will be documented in this file.
The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/).
## [Unreleased]
### Added
- broadphase: add functional API for collision and distance callbacks ([#724](https://github.com/coal-library/coal/pull/724))
- Added a second set of Python bindings based on nanobind ([#659](https://github.com/coal-library/coal/pull/659))
- ROS: jrl_cmakemodules dependency + kilted CI ([#769](https://github.com/coal-library/coal/pull/769))
- Added `SUFFIX_SO_VERSION` CMake option, default `OFF` ([#770](https://github.com/coal-library/coal/pull/770))
- Add pixi-build support ([#774](https://github.com/coal-library/coal/pull/774))
- contact patches: add helpers to reduce the size of a contact patch by keeping points that minimize the difference between the area of the original patch and the area of the new patch
- handle the specific cases of n_desired = 1 or 2 ([805](https://github.com/coal-library/coal/pull/805))
- improve efficiency of ContactPatchSimplifierMaxArea and improve testing of patch simplifiers ([813](https://github.com/coal-library/coal/pull/813))
- timings: + and += operators ([805](https://github.com/coal-library/coal/pull/805))
- Add print methods for collision data (`Contact`, `CollisionRequest`, `CollisionResult`, `DistanceRequest`, `DistanceResult`, `ContactPatch`, `ContactPatchRequest` and `ContactPatchResult`) ([854](https://github.com/coal-library/coal/pull/854)).
- One can now do `std::cout << contact` for example.
- Added the `PrintableVisitor` in python bindings so that `print(contact)` works in python as well
- Added `resolveReferences` method to `Contact` and `DistanceResult` to remap the `o1/o2` pointers (typically after serialization/deserialization) ([855](https://github.com/coal-library/coal/pull/855)).
- Added copy constructors to `Contact::Contact(const Contact& other, const CollisionGeometry* new_o1, const CollisionGeometry* new_o2)` and `DistanceResult::DistanceResult(const DistanceResult& other, const CollisionGeometry* new_o1, const CollisionGeometry* new_o2)` to allow copying a `Contact` or `DistanceResult` while remapping the `o1/o2` pointers to new geometries. This is typically useful in the context of deep-copying ([#856](https://github.com/coal-library/coal/pull/820)).
- Added the `COAL_EQUAL_OPERATOR_CHECK` macro. This macro can be overridden at compile time, extremely practial for debugging serialization for example. ([#859](https://github.com/coal-library/coal/pull/859))
### Removed
- Remove direct dependency to ([#744](https://github.com/coal-library/coal/pull/744)):
- Boost::system
- Boost::chrono
- Boost::date_time
- Boost::thread
### Fixed
- Fix doc parsing via doxygen scripts ([#678](https://github.com/coal-library/coal/pull/678) [#699](https://github.com/coal-library/coal/pull/699))
- Correctly calculate AABB for pruned octrees ([#741](https://github.com/coal-library/coal/pull/741))
- Fix contact counting in octree collision detection with ShapeShapeCollide ([#746](https://github.com/coal-library/coal/pull/746))
- Fix sqrDistLowerBound in octree traversal with height field ([#753](https://github.com/coal-library/coal/pull/753))
- Fix contact patch computation by enforcing CCW construction of support sets ([#772](https://github.com/coal-library/coal/pull/772))
- Remove pixi 0.57 warnings ([#774](https://github.com/coal-library/coal/pull/774))
- Fix nanobind bindings' stub file ([#781](https://github.com/coal-library/coal/pull/781#event-20983199417))
- Remove Windows warnings when building benchmakrs ([789](https://github.com/coal-library/coal/pull/789))
- convex: a point can have more than 256 neighbors now. In fact, a point can have `std::numeric_limits<IndexType>::max()` number of neighbors, where IndexType is typically int16 or int32 ([805](https://github.com/coal-library/coal/pull/805))
- Fix octree against octree collision check ([#811](https://github.com/coal-library/coal/pull/811))
- Fix condition for negative bounding volume check ([#816](https://github.com/coal-library/coal/pull/816))
- Add missing calls to computeLocalAABB for internal objects ([#819](https://github.com/coal-library/coal/pull/819))
- Add missing override specifiers ([#820](https://github.com/coal-library/coal/pull/820))
- Fix Python error when accessing `geometry.convex` on BVH geometris ([#833](https://github.com/coal-library/coal/pull/833))
- Fix `Contact`, `CollisionResult` and `DistanceResult` operator== ([#856](https://github.com/coal-library/coal/pull/820)):
- If the `o1/o2` pointers are different, we check whether or not the underlying geometries are the same. This is typically important in the context of serialization.
- Fix using NaN to initialize collision data (`Contact`, `CollisionResult`, `DistanceResult`). This prevents the absurd `Contact contact; contact == contact; // false` problem.
- Fix NaNs coming from GJK/EPA when the algorithms (correctly) early stopped. NaNs indicate failure. In the case that GJK/EPA early stopped but ran fine, we set non-computed data to inf instead of NaN.
### Changed
- Float precision ([#665](https://github.com/coal-library/coal/pull/665))
- Rename `CoalScalar` to `Scalar`
- Add option to switch between (default) double precision and float precision
- Changed all the uses of `double` to `Scalar` in Coal
- Fixed all the compilation warnings when compiling the library using float precision
- Tracy profiling ([#668](https://github.com/coal-library/coal/pull/668))
- added cmake option `COAL_BUILD_WITH_TRACY`
- put tracy scoped zones in broadphase and primitive shapes collision/distance queries
- Use double precision for GJK/EPA when coal is compiled in float ([#674](https://github.com/coal-library/coal/pull/674))
- Everything is in float in coal (including the support functions), except the computations inside GJK/EPA
- Allows GJK/EPA to avoid limitation of float precision
- Renamed PyPI package from coal-library to coal ([#675](https://github.com/coal-library/coal/pull/675))
- Fixed malloc in COAL_ASSERT ([#687](https://github.com/coal-library/coal/pull/687))
- Introducing `Convex16` and `Convex32` to store neighbors and polygons indices as `uint16` or `uint32` ([#682](https://github.com/coal-library/coal/pull/682), [#716](https://github.com/coal-library/coal/pull/716)).
- Along with #665, this allows to divide by two the memory footprint of `Convex`.
- Fixed a bug in DynamicAABBTree broadphase that missed aabb overlaps when multiple planes/halfspaces are used in a scene.
- Python version update ([#774](https://github.com/coal-library/coal/pull/774)):
- Project is now tested with Python 3.10 and 3.14
- Python 3.10 is the minimal supported Python version
- Nix: switch to flakoboros ([#852](https://github.com/coal-library/coal/pull/852))
## [3.0.3] - 2026-05-05
- Backport removal of Boost::system
## [3.0.2] - 2025-09-29
### Added
- CMake: add COAL_DISABLE_HPP_FCL_WARNINGS option ([#709](https://github.com/coal-library/coal/pull/709))
- CMake: add support for BUILD_STANDALONE_PYTHON_INTERFACE ([#658](https://github.com/coal-library/coal/pull/658))
- Docker images `ghcr.io/coal-library/coal` ([#737](https://github.com/coal-library/coal/pull/737))
### Removed
- Remove constraints on supported doxygen version to generate the python documentation ([#681](https://github.com/coal-library/coal/pull/681))
- Remove useless COAL_WITH_CXX11_SUPPORT guard ([#688](https://github.com/coal-library/coal/pull/688))
- Remove qhull submodule, as ubuntu 20.04 is EoL ([#704](https://github.com/coal-library/coal/pull/704))
- Removed support for octomap < 1.8 ([#727](https://github.com/coal-library/coal/pull/727))
### Changed
- Formatted all CMake listfiles using gersemi, add gersemi to pre-commit configuration ([#657](https://github.com/coal-library/coal/pull/657/files))
## [3.0.1] - 2025-02-12
### Fixed
- Remove CMake CMP0167 warnings ([#630](https://github.com/coal-library/coal/pull/630))
- Allow to run test in the build directory on Windows ([#630](https://github.com/coal-library/coal/pull/630))
- Updated nix flake from `hpp-fcl` to `coal` ([#632](https://github.com/coal-library/coal/pull/632)
- Fix hpp-fclConfig.cmake on Windows ([#633](https://github.com/coal-library/coal/pull/633))
- Fix install version ([#651](https://github.com/coal-library/coal/pull/651))
### Added
- Add Pixi support ([#629](https://github.com/coal-library/coal/pull/629))
### Changed
- Set NOMINMAX as a public definitions on Windows ([#640](https://github.com/coal-library/coal/pull/640))
## [3.0.0] - 2024-11-20
### Added
- Renaming the library from `hpp-fcl` to `coal`. Created a `COAL_BACKWARD_COMPATIBILITY_WITH_HPP_FCL` CMake option for retro compatibility. This allows to still do `find_package(hpp-fcl)` and `#include <hpp/fcl/...>` in C++ and it allows to still do `import hppfcl` in python ([#596](https://github.com/coal-library/coal/pull/596)).
- Added `Transform3f::Random` and `Transform3f::setRandom` ([#584](https://github.com/coal-library/coal/pull/584))
- New feature: computation of contact surfaces for any pair of primitive shapes (triangle, sphere, ellipsoid, plane, halfspace, cone, capsule, cylinder, convex) ([#574](https://github.com/coal-library/coal/pull/574)).
- Enhance Broadphase DynamicAABBTree to better handle planes and halfspace ([#570](https://github.com/coal-library/coal/pull/570))
- [#558](https://github.com/coal-library/coal/pull/558):
- [internal] Removed dead code in `narrowphase/details.h` ([#558](https://github.com/coal-library/coal/pull/558))
- [internal] Removed specializations of methods of `GJKSolver`. Now the specializations are all handled by `ShapeShapeDistance` in `shape_shape_func.h`.
- [new feature] Added support for Swept-Sphere primitives (sphere, box, capsule, cone, ellipsoid, triangle, halfspace, plane, convex mesh).
- [API change] Renamed default convergence criterion from `VDB` to `Default` ([#556](https://github.com/coal-library/coal/pull/556))
- Fixed EPA returning nans on cases where it could return an estimate of the normal and penetration depth. ([#556](https://github.com/coal-library/coal/pull/556))
- Fixed too low tolerance in GJK/EPA asserts ([#554](https://github.com/coal-library/coal/pull/554))
- Fixed `normal_and_nearest_points` test (no need to have Eigen 3.4) ([#553](https://github.com/coal-library/coal/pull/553))
- [#549](https://github.com/coal-library/coal/pull/549)
- Optimize EPA: ignore useless faces in EPA's polytope; warm-start support computation for `Convex`; fix edge-cases witness points computation.
- Add `Serializable` trait to transform, collision data, collision geometries, bounding volumes, bvh models, hfields. Collision problems can now be serialized from C++ and sent to python and vice versa.
- CMake: allow use of installed jrl-cmakemodules ([#564](https://github.com/coal-library/coal/pull/564))
- CMake: Add compatibility with jrl-cmakemodules workspace ([#610](https://github.com/coal-library/coal/pull/610))
- Python: add id() support for geometries ([#618](https://github.com/coal-library/coal/pull/618)).
### Fixed
- Fix Fix serialization unit test when running without Qhull support ([#611](https://github.com/coal-library/coal/pull/611))
- Compiler warnings ([#601](https://github.com/coal-library/coal/pull/601), [#605](https://github.com/coal-library/coal/pull/605))
- CMake: fix assimp finder
- Don't define GCC7 Boost serialization hack when `HPP_FCL_SKIP_EIGEN_BOOST_SERIALIZATION` is defined ([#530](https://github.com/coal-library/coal/pull/530))
- Default parameters for narrowphase algorithms (GJK and EPA); fixed assertion checks that were sometimes failing in GJK simplex projection and BVH `collide` ([#531](https://github.com/coal-library/coal/pull/531)).
- Created a new macro `HPP_FCL_ASSERT` which behaves as an assert by default. When the option `HPP_FCL_TURN_ASSERT_INTO_EXCEPTION` is turned on, it replaces the macro by an exception ([#533](https://github.com/coal-library/coal/pull/533)). Also fixed an EPA assert in `GJKSolver`.
- Simplify internals of hpp-fcl ([#535](https://github.com/coal-library/coal/pull/535)):
- Computing distance between 2 primitives shapes does not use a traversal node anymore.
- Removed successive mallocs in GJK/EPA when using an instance of `GJKSolver` multiple times.
- `GJKSolver` now deals with **all** statuses of GJK/EPA. Some of these statuses represent a bad behavior of GJK/EPA and now trigger an assertion in Debug mode. Usefull for debugging these algos.
- Logging was added with macros like `HPP_FCL_LOG_(INFO/DEBUG/WARNING/ERROR)`; hpp-fcl can now log usefull info when the preprocessor option `HPP_FCL_ENABLE_LOGGING` is enabled.
- Deprecated `enable_distance_lower_bound` in `CollisionRequest`; a lower bound on distance is always computed.
- Deprecated `enable_nearest_points` in `DistanceRequest`; they are always computed and are the points of the shapes that achieve a distance of `DistanceResult::min_distance`.
- Added `enable_signed_distance` flag in `DistanceRequest` (default `true`). Turn this of for better performance if only the distance when objects are disjoint is needed.
- The internal collision and distance functions of hpp-fcl now use `CollisionRequest::enable_contact` and `DistanceRequest::enable_signed_distance` to control whether or not penetration information should be computed. There are many scenarios where we don't need the penetration information and only want to know if objects are colliding and compute their distance only if they are disjoint. These flags allow the user to control the trade-off between performance vs. information of the library.
- Fix convergence criterion of EPA; made GJK and EPA convergence criterion absolute + relative to scale to the shapes' dimensions; remove max face/vertices fields from EPA (these can be deduced from the max number of iterations)
- Account for lateral borders in Height Fields model.
- Fix compilation error on recent APPLE compilers ([#539](https://github.com/coal-library/coal/pull/539)).
- Fix printing of deprecated message ([#540](https://github.com/coal-library/coal/pull/540)).
- Fix compilation with earlier Eigen version
- Fix compilation warning message
- Fix issue in Octomap.computeLocalAABB
- Fix unsupported function for contact_patch_matrix
- Fix Octomap dependency on ROS
## [2.4.5] - 2024-07-28
### Fixed
- Fix Octomap dependency on ROS
## [2.4.4] - 2024-03-06
## [2.4.3] - 2024-03-06
### Fixed
- updated cmake module to fix documentation generation
- test documentation in conda ci
## [2.4.2] - 2024-03-06
### Fixed
- Fix CMAKE_INSTALL_{} path for installation ([#543](https://github.com/coal-library/coal/pull/543))
## [2.4.1] - 2024-01-23
### Fixed
- CachedMeshLoader checks file last modification time.
- Fix call to clear methods for {Collision,Distance}Data inside init function ([#509](https://github.com/coal-library/coal/pull/509))
- CMake: fix submodule use in bindings in ([#512](https://github.com/coal-library/coal/pull/512))
- Fix bug in DynamicAABBTreeCollisionManager (see [#514](https://github.com/coal-library/coal/issues/514)) in ([#515](https://github.com/coal-library/coal/pull/515))
### Added
- In struct Contact
- Documentation of the members,
- initialization of normal, closest points and contact point in constructors
- method getDistanceToCollision
- New variant of GJK (PolyakAcceleration).
- Specialization of distance computation between
- Sphere and Capsule,
- Ellipsoid and Halfspace,
- Ellipsoid and Plane.
- Collision computation between Octree and HeightField.
### Changed
- Matrixx3f and Matrixx3i become row major.
- Use shared pointers to vectors instead of arrays for vertices and triangles in class BVHModelBase.
### Removed
- members related epa in class QueryRequest
## [2.4.0] - 2023-11-27
### Added
- Add method to `CollisionObject` to get `CollisionGeometry` raw pointer
### Fixed
- Fix RPATH computation on OSX
- Fix Python stubs generation on Windows
## [2.3.7] - 2023-11-15
### What's Changed
- Add Python 3.12 support by [@jorisv](https://github.com/jorisv) ([#471](https://github.com/coal-library/coal/pull/471))
- Enable ruff linting by [@nim65s](https://github.com/nim65s) ([#464](https://github.com/coal-library/coal/pull/464))
## [2.3.6] - 2023-09-30
### What's Changed
- Update ROS_DISTRO by [@jcarpent](https://github.com/jcarpent) ([#442](https://github.com/coal-library/coal/pull/442))
- Add citations by [@jcarpent](https://github.com/jcarpent) ([#449](https://github.com/coal-library/coal/pull/449))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#444](https://github.com/coal-library/coal/pull/444))
- [WIP] Debug by [@jcarpent](https://github.com/jcarpent) ([#455](https://github.com/coal-library/coal/pull/455))
- CMake: require >= 3.10 by [@nim65s](https://github.com/nim65s) ([#453](https://github.com/coal-library/coal/pull/453))
- core: fix SaPCollisionManager::empty() by [@rujialiu](https://github.com/rujialiu) ([#454](https://github.com/coal-library/coal/pull/454))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#452](https://github.com/coal-library/coal/pull/452))
### New Contributors
- [@rujialiu](https://github.com/rujialiu) made their first contribution ([#454](https://github.com/coal-library/coal/pull/454))
## [2.3.5] - 2023-07-11
### What's Changed
- Fix compilation warning by [@jcarpent](https://github.com/jcarpent) ([#434](https://github.com/coal-library/coal/pull/434))
- Fix parsing of doxygen doc by [@jcarpent](https://github.com/jcarpent) ([#439](https://github.com/coal-library/coal/pull/439))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#438](https://github.com/coal-library/coal/pull/438))
## [2.3.4] - 2023-06-01
### What's Changed
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#414](https://github.com/coal-library/coal/pull/414))
- Fix conversion warning by [@wxmerkt](https://github.com/wxmerkt) ([#417](https://github.com/coal-library/coal/pull/417))
- Add missing boost include by [@nim65s](https://github.com/nim65s) ([#418](https://github.com/coal-library/coal/pull/418))
- ci: update macos-linux-pip by [@nim65s](https://github.com/nim65s) ([#419](https://github.com/coal-library/coal/pull/419))
- Modernize Cmake use by [@nim65s](https://github.com/nim65s) ([#420](https://github.com/coal-library/coal/pull/420))
- tests: use boost::filesystem by [@nim65s](https://github.com/nim65s) ([#424](https://github.com/coal-library/coal/pull/424))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#425](https://github.com/coal-library/coal/pull/425))
- Update minimal Python version by [@jcarpent](https://github.com/jcarpent) ([#427](https://github.com/coal-library/coal/pull/427))
- Sync submodule cmake by [@jcarpent](https://github.com/jcarpent) ([#430](https://github.com/coal-library/coal/pull/430))
- Sync submodule CMake by [@jcarpent](https://github.com/jcarpent) ([#431](https://github.com/coal-library/coal/pull/431))
## [2.3.3] - 2023-05-09
### What's Changed
- update default C++ to 14 by [@nim65s](https://github.com/nim65s) ([#410](https://github.com/coal-library/coal/pull/410))
- Sync submodule cmake by [@jcarpent](https://github.com/jcarpent) ([#413](https://github.com/coal-library/coal/pull/413))
## [2.3.2] - 2023-04-27
### What's Changed
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#391](https://github.com/coal-library/coal/pull/391))
- Sync submodule cmake by [@jcarpent](https://github.com/jcarpent) ([#393](https://github.com/coal-library/coal/pull/393))
- Topic/rpath by [@nim65s](https://github.com/nim65s) ([#394](https://github.com/coal-library/coal/pull/394))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#396](https://github.com/coal-library/coal/pull/396))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#399](https://github.com/coal-library/coal/pull/399))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#402](https://github.com/coal-library/coal/pull/402))
- Sync submodule cmake by [@jcarpent](https://github.com/jcarpent) ([#406](https://github.com/coal-library/coal/pull/406))
## [2.3.1] - 2023-03-25
### What's Changed
- Remove useless call to /proc/cpuinfo by [@jcarpent](https://github.com/jcarpent) ([#385](https://github.com/coal-library/coal/pull/385))
- Add pip CI by [@nim65s](https://github.com/nim65s) ([#386](https://github.com/coal-library/coal/pull/386))
- [GJKSolver] Fix missing switch case in result status of GJK by [@lmontaut](https://github.com/lmontaut) ([#387](https://github.com/coal-library/coal/pull/387))
- Sync submodule cmake by [@jcarpent](https://github.com/jcarpent) ([#388](https://github.com/coal-library/coal/pull/388))
## [2.3.0] - 2023-03-17
### What's Changed
- [CI] Remove EOL Galactic by [@wxmerkt](https://github.com/wxmerkt) ([#366](https://github.com/coal-library/coal/pull/366))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#367](https://github.com/coal-library/coal/pull/367))
- Sync submodule cmake by [@jcarpent](https://github.com/jcarpent) ([#368](https://github.com/coal-library/coal/pull/368))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#369](https://github.com/coal-library/coal/pull/369))
- Adding EarlyStopped flag in GJK by [@lmontaut](https://github.com/lmontaut) ([#371](https://github.com/coal-library/coal/pull/371))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#373](https://github.com/coal-library/coal/pull/373))
- Update CI by [@jcarpent](https://github.com/jcarpent) ([#374](https://github.com/coal-library/coal/pull/374))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#375](https://github.com/coal-library/coal/pull/375))
- Skip test if BUILD_TESTING is OFF by [@jcarpent](https://github.com/jcarpent) ([#378](https://github.com/coal-library/coal/pull/378))
## [2.2.0] - 2022-12-12
### What's Changed
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#358](https://github.com/coal-library/coal/pull/358))
- Extract checks if AABB overlap by [@jmirabel](https://github.com/jmirabel) ([#360](https://github.com/coal-library/coal/pull/360))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#361](https://github.com/coal-library/coal/pull/361))
- Sync submodule CMake by [@jcarpent](https://github.com/jcarpent) ([#362](https://github.com/coal-library/coal/pull/362))
- Add support of Pickling by [@jcarpent](https://github.com/jcarpent) ([#363](https://github.com/coal-library/coal/pull/363))
## [2.1.4] - 2022-10-24
### What's Changed
- Sync submodule CMake by [@jcarpent](https://github.com/jcarpent) ([#352](https://github.com/coal-library/coal/pull/352))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#353](https://github.com/coal-library/coal/pull/353))
## [2.1.3] - 2022-09-13
### What's Changed
- Minor boost cleanup by [@pantor](https://github.com/pantor) ([#331](https://github.com/coal-library/coal/pull/331))
- [CI] Activate ROS2 configurations by [@wxmerkt](https://github.com/wxmerkt) ([#332](https://github.com/coal-library/coal/pull/332))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#337](https://github.com/coal-library/coal/pull/337))
- Sync submodule cmake by [@jcarpent](https://github.com/jcarpent) ([#341](https://github.com/coal-library/coal/pull/341))
- Fix shapeIntersect when for EPA FallBack by [@jcarpent](https://github.com/jcarpent) ([#342](https://github.com/coal-library/coal/pull/342))
- Fix findAssimp on Windows by [@jcarpent](https://github.com/jcarpent) ([#345](https://github.com/coal-library/coal/pull/345))
- Sync submodule cmake by [@jcarpent](https://github.com/jcarpent) ([#347](https://github.com/coal-library/coal/pull/347))
### New Contributors
- [@pantor](https://github.com/pantor) made their first contribution ([#331](https://github.com/coal-library/coal/pull/331))
## [2.1.2] - 2022-08-01
### What's Changed
- core: add EPA::FallBack condition to shapeDistance computation by [@lmontaut](https://github.com/lmontaut) ([#325](https://github.com/coal-library/coal/pull/325))
- CMake: update to eigenpy 2.7.10 by [@nim65s](https://github.com/nim65s) ([#327](https://github.com/coal-library/coal/pull/327))
## [2.1.1] - 2022-07-25
### What's Changed
- cmake: relocatable package for recent CMake versions by [@nim65s](https://github.com/nim65s) ([#319](https://github.com/coal-library/coal/pull/319))
- ROS2/Colcon integration by [@wxmerkt](https://github.com/wxmerkt) ([#321](https://github.com/coal-library/coal/pull/321))
## [2.1.0] - 2022-07-13
### What's Changed
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#288](https://github.com/coal-library/coal/pull/288))
- Add enum helpers by [@jcarpent](https://github.com/jcarpent) ([#290](https://github.com/coal-library/coal/pull/290))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#294](https://github.com/coal-library/coal/pull/294))
- Ellipsoids in collision & distance matrices by [@lmontaut](https://github.com/lmontaut) ([#295](https://github.com/coal-library/coal/pull/295))
- doc: simplex projection in GJK class. by [@lmontaut](https://github.com/lmontaut) ([#296](https://github.com/coal-library/coal/pull/296))
- Feature: Nesterov acceleration for GJK by [@lmontaut](https://github.com/lmontaut) ([#289](https://github.com/coal-library/coal/pull/289))
- Add more testing to broadphase by [@jcarpent](https://github.com/jcarpent) ([#298](https://github.com/coal-library/coal/pull/298))
- Feature: adding convergence criterions for GJK algorithm by [@lmontaut](https://github.com/lmontaut) ([#299](https://github.com/coal-library/coal/pull/299))
- Sync submodule cmake by [@jcarpent](https://github.com/jcarpent) ([#300](https://github.com/coal-library/coal/pull/300))
- Reorder triangles when computing convex hulls by [@lmontaut](https://github.com/lmontaut) ([#301](https://github.com/coal-library/coal/pull/301))
- Exposing gjk utils by [@lmontaut](https://github.com/lmontaut) ([#302](https://github.com/coal-library/coal/pull/302))
- Fix assert precision in GJK by [@jcarpent](https://github.com/jcarpent) ([#304](https://github.com/coal-library/coal/pull/304))
- Simplify GJKSolver settings by [@jcarpent](https://github.com/jcarpent) ([#305](https://github.com/coal-library/coal/pull/305))
- Add CollisionResult::nearest_points by [@jcarpent](https://github.com/jcarpent) ([#303](https://github.com/coal-library/coal/pull/303))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#306](https://github.com/coal-library/coal/pull/306))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#309](https://github.com/coal-library/coal/pull/309))
- Fix minimal value for GJK::distance_upper_bound by [@jcarpent](https://github.com/jcarpent) ([#310](https://github.com/coal-library/coal/pull/310))
- Fix incoherent overlap by [@jcarpent](https://github.com/jcarpent) ([#311](https://github.com/coal-library/coal/pull/311))
- Expose shared_ptr<OcTree> by [@Jiayuan-Gu](https://github.com/Jiayuan-Gu) ([#314](https://github.com/coal-library/coal/pull/314))
- test/gjk_convergence_criterion: Add check on GJK::Status by [@wxmerkt](https://github.com/wxmerkt) ([#315](https://github.com/coal-library/coal/pull/315))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#316](https://github.com/coal-library/coal/pull/316))
- Handle negative security margin by [@jcarpent](https://github.com/jcarpent) ([#312](https://github.com/coal-library/coal/pull/312))
### New Contributors
- [@Jiayuan-Gu](https://github.com/Jiayuan-Gu) made their first contribution ([#314](https://github.com/coal-library/coal/pull/314))
## [2.0.1] - 2022-04-15
This PR mainly fixes packaging issues and removes compilation warnings.
### What's Changed
- Zero warnings by [@wxmerkt](https://github.com/wxmerkt) ([#282](https://github.com/coal-library/coal/pull/282))
- Sync submodule cmake by [@jcarpent](https://github.com/jcarpent) ([#283](https://github.com/coal-library/coal/pull/283))
- [pre-commit.ci] pre-commit autoupdate by [@pre-commit-ci](https://github.com/pre-commit-ci) ([#284](https://github.com/coal-library/coal/pull/284))
- Activate python3-pylatexenc dependency by [@wxmerkt](https://github.com/wxmerkt) ([#286](https://github.com/coal-library/coal/pull/286))
- Comment pylatexenc again since it's not available on the buildfarm by [@wxmerkt](https://github.com/wxmerkt) ([#287](https://github.com/coal-library/coal/pull/287))
### New Contributors
- [@pre-commit-ci](https://github.com/pre-commit-ci) made their first contribution ([#284](https://github.com/coal-library/coal/pull/284))
## [2.0.0] - 2022-04-06
This new release reintroduces the full support of Broad phase within hpp-fcl while also enforcing C++11 as minimal standard.
### What's Changed
- Add Ellipsoid by [@jcarpent](https://github.com/jcarpent) ([#259](https://github.com/coal-library/coal/pull/259))
- Removing comment about inflation. by [@lmontaut](https://github.com/lmontaut) ([#261](https://github.com/coal-library/coal/pull/261))
- Reintroduce broadphase by [@jcarpent](https://github.com/jcarpent) ([#260](https://github.com/coal-library/coal/pull/260))
- Simplify CollisionObject by removing cgeom_const by [@jcarpent](https://github.com/jcarpent) ([#263](https://github.com/coal-library/coal/pull/263))
- Address some warnings by [@wxmerkt](https://github.com/wxmerkt) ([#262](https://github.com/coal-library/coal/pull/262))
- Fix missing copy of aabb_local in CollisionGeometry by [@jcarpent](https://github.com/jcarpent) ([#264](https://github.com/coal-library/coal/pull/264))
- use std::shared_ptr, fix #218 by [@nim65s](https://github.com/nim65s) ([#266](https://github.com/coal-library/coal/pull/266))
- Fix broadphase warnings for clang (some conversion remain for g++) by [@wxmerkt](https://github.com/wxmerkt) ([#268](https://github.com/coal-library/coal/pull/268))
- [ComputeCollision] Return no collision if security_margin is set to -inf by [@florent-lamiraux](https://github.com/florent-lamiraux) ([#271](https://github.com/coal-library/coal/pull/271))
- tests: remove link to boost unit test framework by [@nim65s](https://github.com/nim65s) ([#270](https://github.com/coal-library/coal/pull/270))
- Fix computation of aabb_center by [@jcarpent](https://github.com/jcarpent) ([#273](https://github.com/coal-library/coal/pull/273))
- Add operator== and operator!= to CollisionGeometry by [@jcarpent](https://github.com/jcarpent) ([#274](https://github.com/coal-library/coal/pull/274))
- Merge pull request #276 from humanoid-path-planner/patch-release-1.8.1 by [@jcarpent](https://github.com/jcarpent) ([#277](https://github.com/coal-library/coal/pull/277))
- Fix some missing features in base classes by [@jcarpent](https://github.com/jcarpent) ([#275](https://github.com/coal-library/coal/pull/275))
- Add operator{==,!=} to CollisionObject by [@jcarpent](https://github.com/jcarpent) ([#278](https://github.com/coal-library/coal/pull/278))
- Configure and apply pre-commit by [@jcarpent](https://github.com/jcarpent) ([#280](https://github.com/coal-library/coal/pull/280))
- Fix DistanceCallBackBaseWrapper by [@jcarpent](https://github.com/jcarpent) ([#281](https://github.com/coal-library/coal/pull/281))
### New Contributors
- [@lmontaut](https://github.com/lmontaut) made their first contribution ([#261](https://github.com/coal-library/coal/pull/261))
## [1.8.1] - 2022-03-20
### What's Changed
- Preparing for ROS1 and ROS2 release by [@wxmerkt](https://github.com/wxmerkt) ([#255](https://github.com/coal-library/coal/pull/255))
- Patch release 1.8.1 by [@wxmerkt](https://github.com/wxmerkt) ([#276](https://github.com/coal-library/coal/pull/276))
## [1.8.0] - 2022-02-08
### What's Changed
- [CMake] Qhull is a private dependency by [@nim65s](https://github.com/nim65s) ([#247](https://github.com/coal-library/coal/pull/247))
- Remove useless warnings by [@jcarpent](https://github.com/jcarpent) ([#248](https://github.com/coal-library/coal/pull/248))
- fix submodule url by [@nim65s](https://github.com/nim65s) ([#246](https://github.com/coal-library/coal/pull/246))
- Remove warnings and add missing noalias by [@jcarpent](https://github.com/jcarpent) ([#249](https://github.com/coal-library/coal/pull/249))
- Function makeOctree returns a shared pointer by [@florent-lamiraux](https://github.com/florent-lamiraux) ([#254](https://github.com/coal-library/coal/pull/254))
- Add support of HeightField by [@jcarpent](https://github.com/jcarpent) ([#251](https://github.com/coal-library/coal/pull/251))
- [OcTree] Add method to save octree in obj file. by [@florent-lamiraux](https://github.com/florent-lamiraux) ([#256](https://github.com/coal-library/coal/pull/256))
- Fix C++98 compatibility by [@jcarpent](https://github.com/jcarpent) ([#258](https://github.com/coal-library/coal/pull/258))
## [1.7.8] - 2021-10-30
### What's Changed
- Fix conversion by [@jcarpent](https://github.com/jcarpent) ([#242](https://github.com/coal-library/coal/pull/242))
- Fix exposition of vertices by [@jcarpent](https://github.com/jcarpent) ([#243](https://github.com/coal-library/coal/pull/243))
- Enhance Convex exposition by [@jcarpent](https://github.com/jcarpent) ([#244](https://github.com/coal-library/coal/pull/244))
- Sync submodule cmake by [@jcarpent](https://github.com/jcarpent) ([#245](https://github.com/coal-library/coal/pull/245))
## [1.7.7] - 2021-09-13
This new release fixes several bugs within the framework.
## [1.7.6] - 2021-09-08
This new release improves the packaging of the project and integrates the Stub generation of Python bindings.
## [1.7.5] - 2021-07-30
This new release provides extended API exposition in Python, removes some code related to CDD while also trying to rely on the QHULL version present on the system.
## [1.7.4] - 2021-06-11
This release fixes several bugs:
- correct update of the distance lower bound
- fix memory footprint computation
while also removing the support of Travis CI.
## [1.7.3] - 2021-05-26
This new release provides:
- fixes of LINE and POINTS when loading meshes with assimp
- removing of various warnings
- computation of memory footprint for geometries
## [1.7.2] - 2021-04-19
This new release improves the loading of meshes using Assimp by automatically removing degenerated LINES and POINTS.
## [1.7.1] - 2021-04-02
This new release reduces the impact of timers on the computations.
This should be used with care and can be enabled by setting the correct flag to true in the QueryRequest.
## [1.7.0] - 2021-03-31
This new release provides:
- extended support for serialization
- timing of the collision/distance computations
- helpers to build octree
- various bug fixes and interface improvements
## [1.6.0] - 2020-10-06
This new release provides:
- functors for evaluating Collision and Distances (faster call)
- extended support of v142 compiler
- support of collision check between HalfSpace and Convex shapes
- improvement of GJK solver
- fixes on Python bindings
## [1.5.4] - 2020-09-22
In this new release, the support of collision checking between Convex objects and HalfSpace have been enhanced and some minor fixes have been provided.
## [1.5.3] - 2020-08-31
This new release provides better CMake packaging and improved GJK algorithms.
## [1.5.2] - 2020-08-15
This release improves the packaging of the project and provides fixes for the GJK solver.
## [1.5.1] - 2020-08-06
This new release fixes packaging issues with precedent release 1.5.0. It also provides additional fixes in main collision/distance algorithms.
## [1.4.6] - 2020-06-10
This new release enhances the packaging of the project and allows the compilation of FCL on Windows systems.
## [1.4.5] - 2020-06-03
Changes in v1.4.5:
- Fix Python 3 doc generation
- Fix packaging of the project
- Compilation on Windows.
- [CMake] Install missing header.
- Add collide and distance prototype that update the GJK guess.
- Add support function cached guess in queries and merge query attribute.
- Add function to generate the convex hull.
- Add hint to the support function + Fix usage of GJK guess.
- [Python] Add constructor for class Convex.
- [Python] Bind functions to create BVHModel.
## [1.4.4] - 2020-04-29
Changes in 1.4.4:
- add MeshLoader::loadOctree
- fix generation of XML documentation
- fix generation of Doxygen documentation
## [1.4.3] - 2020-04-08
This new release fixes some packagings issues for OS X systems.
## [1.4.2] - 2020-04-04
Changes in v1.4.2:
- don't require linking to eigenpy in .pc file.
## [1.4.1] - 2020-04-03
Changes in v1.4.1:
- Bug fix + prepare optimization of collision using GJK / EPA
- Add missing constructor for Transform3f
## [1.4.0] - 2020-04-03
Changes since v1.3.0:
- Improve code efficiency + use shared memory between Numpy and Eigen
- [Python] Doc and minor update + [C++] bugfix
- [Python] Fix bindings of CollisionResult.
- FIX: throw when no contact is available
- Minor fix and computational improvments
- [GJK/EPA] Fix bugs + Treat sphere as point and capsule as line segment.
- Fix boxSphereDistance
- Provide documentation for the Python bindings.
- Generate Python documentation from doxygen documentation.
- Fix issue when Python_EXECUTABLE is not defined
- update CMake packaging
## [1.3.0] - 2020-01-28
This new release comes with:
- the removing of the GJK solver
- the Python bindings build by default
- an improved documentation
- additional Python bindings
## [1.2.2] - 2019-12-17
This new Release improves the Python bindings and fixes an important bug when checking the collision between two Capsules.
Thanks to [@rstrudel](https://github.com/rstrudel) for this fix.
## [1.2.1] - 2019-12-09
This new release improves both the packaging of the project, which seems to be totally compatible with the new CMake linkage style. In addition, the bindings are now fully compatible with Pinocchio.
## [1.2.0] - 2019-11-22
Changes since v1.1.3:
- Add python bindings
- Update CMake
- Add version support
- New folder Internal for internal header
- Travis: update CI & change policy to only perform build in DEBUG mode on Bionic
- assimp: fix issue with recent version of assimp
- [bindings] [CMakeLists] Use .so for Mac and .pyd for Windows, fix #86
- Organize documentation
- [CMake] fix octomap detection
- [Minor] update CMake module + fix visibility of some methods.
- Enable Convex / Convex queries + Add Python bindings.
- Fix unit-tests and compilation
- [GJK] Fix GJK::encloseOrigin (fixes unit-tests)
- Improve GJK implementation + OBB overlap test + bug fixes
- Clean include BV/BVH/math/mesh_loader
## [1.1.3] - 2019-08-07
This new release enhances the compatibility of hpp-fcl with C++14 and more.
This feature is requested for integration in Anaconda.
## [1.1.2] - 2019-08-05
This new release provides a fix in the parallelization of the computations and improves the packaging of the whole project.
## [1.0.2] - 2019-04-24
Changes since v1.0.1:
- obb: fix compatibility with Eigen 3.0.5
- [CI] octomap for osx
## [1.0.1] - 2019-02-20
- Fix CI on OSX
- Declare CachedMeshLoader::Key::operator<
- minor details
## [0.7.0] - 2019-01-31
This release is mainly here to allow the packaging of HPP-RBPRM.
Another release will follow with more news.
## [0.6.0] - 2018-10-22
- Fix bug when OCTOMAP is not found
- move buildTrianglePlane and clipTriangle method from private to public
- Fix bug with "\" symbols
- [CMake] Add flags related to Octomap in pkg-config file and remove FCL_HAVE_EIGEN
## [0.5.1] - 2017-10-02
Now Eigen is at the heart of linear algebra computations.
## [0.5] - 2017-03-17
First release
[Unreleased]: https://github.com/coal-library/coal/compare/v3.0.3...HEAD
[3.0.3]: https://github.com/coal-library/coal/compare/v3.0.2...v3.0.3
[3.0.2]: https://github.com/coal-library/coal/compare/v3.0.1...v3.0.2
[3.0.1]: https://github.com/coal-library/coal/compare/v3.0.0...v3.0.1
[3.0.0]: https://github.com/coal-library/coal/compare/v2.4.5...v3.0.0
[2.4.5]: https://github.com/coal-library/coal/compare/v2.4.4...v2.4.5
[2.4.4]: https://github.com/coal-library/coal/compare/v2.4.3...v2.4.4
[2.4.3]: https://github.com/coal-library/coal/compare/v2.4.2...v2.4.3
[2.4.2]: https://github.com/coal-library/coal/compare/v2.4.1...v2.4.2
[2.4.1]: https://github.com/coal-library/coal/compare/v2.4.0...v2.4.1
[2.4.0]: https://github.com/coal-library/coal/compare/v2.3.7...v2.4.0
[2.3.7]: https://github.com/coal-library/coal/compare/2.3.6...v2.3.7
[2.3.6]: https://github.com/coal-library/coal/compare/v2.3.5...v2.3.6
[2.3.5]: https://github.com/coal-library/coal/compare/v2.3.4...v2.3.5
[2.3.4]: https://github.com/coal-library/coal/compare/v2.3.3...v2.3.4
[2.3.3]: https://github.com/coal-library/coal/compare/v2.3.2...v2.3.3
[2.3.2]: https://github.com/coal-library/coal/compare/v2.3.1...v2.3.2
[2.3.1]: https://github.com/coal-library/coal/compare/v2.3.0...v2.3.1
[2.3.0]: https://github.com/coal-library/coal/compare/v2.2.0...v2.3.0
[2.2.0]: https://github.com/coal-library/coal/compare/v2.1.4...v2.2.0
[2.1.4]: https://github.com/coal-library/coal/compare/v2.1.3...v2.1.4
[2.1.3]: https://github.com/coal-library/coal/compare/v2.1.2...v2.1.3
[2.1.2]: https://github.com/coal-library/coal/compare/v2.1.1...v2.1.2
[2.1.1]: https://github.com/coal-library/coal/compare/v2.1.0...v2.1.1
[2.1.0]: https://github.com/coal-library/coal/compare/v2.0.1...v2.1.0
[2.0.1]: https://github.com/coal-library/coal/compare/v2.0.0...v2.0.1
[2.0.0]: https://github.com/coal-library/coal/compare/v1.8.1...v2.0.0
[1.8.1]: https://github.com/coal-library/coal/compare/v1.8.0...v1.8.1
[1.8.0]: https://github.com/coal-library/coal/compare/v1.7.8...v1.8.0
[1.7.8]: https://github.com/coal-library/coal/compare/v1.7.7...v1.7.8
[1.7.7]: https://github.com/coal-library/coal/compare/v1.7.6...v1.7.7
[1.7.6]: https://github.com/coal-library/coal/compare/v1.7.5...v1.7.6
[1.7.5]: https://github.com/coal-library/coal/compare/v1.7.4...v1.7.5
[1.7.4]: https://github.com/coal-library/coal/compare/v1.7.3...v1.7.4
[1.7.3]: https://github.com/coal-library/coal/compare/v1.7.2...v1.7.3
[1.7.2]: https://github.com/coal-library/coal/compare/v1.7.1...v1.7.2
[1.7.1]: https://github.com/coal-library/coal/compare/v1.7.0...v1.7.1
[1.7.0]: https://github.com/coal-library/coal/compare/v1.6.0...v1.7.0
[1.6.0]: https://github.com/coal-library/coal/compare/v1.5.4...v1.6.0
[1.5.4]: https://github.com/coal-library/coal/compare/v1.5.3...v1.5.4
[1.5.3]: https://github.com/coal-library/coal/compare/v1.5.2...v1.5.3
[1.5.2]: https://github.com/coal-library/coal/compare/v1.5.1...v1.5.2
[1.5.1]: https://github.com/coal-library/coal/compare/v1.4.6...v1.5.1
[1.4.6]: https://github.com/coal-library/coal/compare/v1.4.5...v1.4.6
[1.4.5]: https://github.com/coal-library/coal/compare/v1.4.4...v1.4.5
[1.4.4]: https://github.com/coal-library/coal/compare/v1.4.3...v1.4.4
[1.4.3]: https://github.com/coal-library/coal/compare/v1.4.2...v1.4.3
[1.4.2]: https://github.com/coal-library/coal/compare/v1.4.1...v1.4.2
[1.4.1]: https://github.com/coal-library/coal/compare/v1.4.0...v1.4.1
[1.4.0]: https://github.com/coal-library/coal/compare/v1.3.0...v1.4.0
[1.3.0]: https://github.com/coal-library/coal/compare/v1.2.2...v1.3.0
[1.2.2]: https://github.com/coal-library/coal/compare/v1.2.1...v1.2.2
[1.2.1]: https://github.com/coal-library/coal/compare/v1.2.0...v1.2.1
[1.2.0]: https://github.com/coal-library/coal/compare/v1.1.3...v1.2.0
[1.1.3]: https://github.com/coal-library/coal/compare/v1.1.2...v1.1.3
[1.1.2]: https://github.com/coal-library/coal/compare/v1.0.2...v1.1.2
[1.0.2]: https://github.com/coal-library/coal/compare/v1.0.1...v1.0.2
[1.0.1]: https://github.com/coal-library/coal/compare/v0.7.0...v1.0.1
[0.7.0]: https://github.com/coal-library/coal/compare/v0.6.0...v0.7.0
[0.6.0]: https://github.com/coal-library/coal/compare/v0.5.1...v0.6.0
[0.5.1]: https://github.com/coal-library/coal/compare/v0.5...v0.5.1
[0.5]: https://github.com/coal-library/coal/releases/tag/v0.5
================================================
FILE: CITATION.bib
================================================
@misc{coalweb,
author = {Jia Pan and Sachin Chitta and Dinesh Manocha and Florent Lamiraux and Joseph Mirabel and Justin Carpentier and Louis Montaut and others},
title = {Coal: an extension of the Flexible Collision Library},
howpublished = {https://github.com/coal-library/coal},
year = {2015--2024}
}
================================================
FILE: CITATION.cff
================================================
cff-version: 1.2.0
message: "Thanks for using Coal. Please use the following metadata to cite us in your documents."
authors:
- family-names: Pan
given-names: Jia
- family-names: Chitta
given-names: Sachin
- family-names: Manocha
given-names: Dinesh
- family-names: Mirabel
given-names: Joseph
- family-names: Carpentier
given-names: Justin
orcid: "https://orcid.org/0000-0001-6585-2894"
- family-names: Montaut
given-names: Louis
title: "Coal - An extension of the Flexible Collision Library"
abstract: "An extension of the Flexible Collision Library"
version: 3.0.3
date-released: "2026-05-05"
license: BSD-2-Clause
url: "https://github.com/coal-library/coal"
================================================
FILE: CMakeLists.txt
================================================
#
# Software License Agreement (BSD License)
#
# Copyright (c) 2014-2025 CNRS-LAAS, INRIA Author: Florent Lamiraux, Joseph
# Mirabel All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# * Redistributions of source code must retain the above copyright notice, this
# list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above copyright notice,
# this list of conditions and the following disclaimer in the documentation
# and/or other materials provided with the distribution.
# * Neither the name of CNRS-LAAS. nor the names of its contributors may be used
# to endorse or promote products derived from this software without specific
# prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
# DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
# FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
# DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
# SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
# OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
cmake_minimum_required(VERSION 3.22)
set(CXX_DISABLE_WERROR TRUE)
set(PROJECT_NAME coal)
set(PROJECT_ORG "coal-library")
set(
PROJECT_DESCRIPTION
"Coal, The Collision Detection Library. Previously known as HPP-FCL, fork of FCL -- The Flexible Collision Library"
)
set(PROJECT_URL "https://github.com/coal-library/coal")
if(NOT BUILD_STANDALONE_PYTHON_INTERFACE)
set(PROJECT_USE_CMAKE_EXPORT TRUE)
endif()
set(PROJECT_COMPATIBILITY_VERSION AnyNewerVersion)
# To enable jrl-cmakemodules compatibility with workspace we must define the two
# following lines
set(PROJECT_AUTO_RUN_FINALIZE FALSE)
set(PROJECT_SOURCE_DIR ${CMAKE_CURRENT_LIST_DIR})
set(PROJECT_USE_KEYWORD_LINK_LIBRARIES TRUE)
set(DOXYGEN_USE_TEMPLATE_CSS TRUE)
# ----------------------------------------------------
# --- OPTIONS ---------------------------------------
# Need to be set before including base.cmake
# ----------------------------------------------------
option(INSTALL_DOCUMENTATION "Generate and install the documentation" OFF)
option(SUFFIX_SO_VERSION "Suffix library name with its version" OFF)
option(
COAL_TURN_ASSERT_INTO_EXCEPTION
"Turn some critical Coal asserts to exception."
FALSE
)
option(
COAL_ENABLE_LOGGING
"Activate logging for warnings or error messages. Turned on by default in Debug."
FALSE
)
option(
COAL_BACKWARD_COMPATIBILITY_WITH_HPP_FCL
"Make Coal retro-compatible with HPP-FCL."
FALSE
)
option(
COAL_USE_FLOAT_PRECISION
"Use float precision (32-bit) instead of the default double precision (64-bit)"
FALSE
)
option(
COAL_BUILD_WITH_TRACY
"Build with tracy profiler for performance analysis"
FALSE
)
# Check if the submodule cmake have been initialized
set(JRL_CMAKE_MODULES "${CMAKE_CURRENT_LIST_DIR}/cmake")
if(EXISTS "${JRL_CMAKE_MODULES}/base.cmake")
message(STATUS "JRL cmakemodules found in 'cmake/' git submodule")
else()
find_package(jrl-cmakemodules QUIET CONFIG)
if(jrl-cmakemodules_FOUND)
get_property(
JRL_CMAKE_MODULES
TARGET jrl-cmakemodules::jrl-cmakemodules
PROPERTY INTERFACE_INCLUDE_DIRECTORIES
)
message(STATUS "JRL cmakemodules found on system at ${JRL_CMAKE_MODULES}")
else()
message(STATUS "JRL cmakemodules not found. Let's fetch it.")
include(FetchContent)
FetchContent_Declare(
"jrl-cmakemodules"
GIT_REPOSITORY "https://github.com/jrl-umi3218/jrl-cmakemodules.git"
)
FetchContent_MakeAvailable("jrl-cmakemodules")
FetchContent_GetProperties("jrl-cmakemodules" SOURCE_DIR JRL_CMAKE_MODULES)
endif()
endif()
# Use BoostConfig module distributed by boost library instead of using FindBoost
# module distributed by CMake. There is one unresolved issue with FindBoost and
# clang-cl so we deactivate it in this case.
if(NOT WIN32 OR NOT ${CMAKE_CXX_COMPILER_ID} MATCHES "Clang")
if(POLICY CMP0167)
cmake_policy(SET CMP0167 NEW)
# Set a default value to this policy to avoid issue with find_dependency
# macro redefinition with different policy in some modules.
set(CMAKE_POLICY_DEFAULT_CMP0167 NEW)
endif()
endif()
include("${JRL_CMAKE_MODULES}/base.cmake")
COMPUTE_PROJECT_ARGS(PROJECT_ARGS LANGUAGES CXX)
project(${PROJECT_NAME} ${PROJECT_ARGS})
include("${JRL_CMAKE_MODULES}/boost.cmake")
include("${JRL_CMAKE_MODULES}/python.cmake")
include("${JRL_CMAKE_MODULES}/apple.cmake")
include("${JRL_CMAKE_MODULES}/ide.cmake")
include("${JRL_CMAKE_MODULES}/tracy.cmake")
include(CMakeDependentOption)
set(
CMAKE_MODULE_PATH
${JRL_CMAKE_MODULES}/find-external/assimp/
${CMAKE_MODULE_PATH}
)
function(set_standard_output_directory target)
set_target_properties(
${target}
PROPERTIES
RUNTIME_OUTPUT_DIRECTORY ${PROJECT_BINARY_DIR}/bin
LIBRARY_OUTPUT_DIRECTORY ${PROJECT_BINARY_DIR}/lib
ARCHIVE_OUTPUT_DIRECTORY ${PROJECT_BINARY_DIR}/lib
)
endfunction()
SET_DEFAULT_CMAKE_BUILD_TYPE("RelWithDebInfo")
# If needed, fix CMake policy for APPLE systems
APPLY_DEFAULT_APPLE_CONFIGURATION()
cmake_dependent_option(
COAL_PYTHON_NANOBIND
"Build the nanobind-based bindings."
OFF
BUILD_PYTHON_INTERFACE
OFF
)
# Stubs only optional for legacy Boost.Python bindings
if(NOT COAL_PYTHON_NANOBIND)
cmake_dependent_option(
GENERATE_PYTHON_STUBS
"Generate the Python stubs for the Python bindings (only for legacy Boost.Python bindings)"
OFF
BUILD_PYTHON_INTERFACE
OFF
)
endif()
ADD_PROJECT_DEPENDENCY(Eigen3 REQUIRED PKG_CONFIG_REQUIRES "eigen3 >= 3.0.0")
# -- tracy profiling (optional)
if(COAL_BUILD_WITH_TRACY)
# assume it is installed somewhere
ADD_PROJECT_DEPENDENCY(Tracy REQUIRED)
set_target_properties(
Tracy::TracyClient
PROPERTIES POSITION_INDEPENDENT_CODE True
)
endif(COAL_BUILD_WITH_TRACY)
# Required dependencies
SET_BOOST_DEFAULT_OPTIONS()
EXPORT_BOOST_DEFAULT_OPTIONS()
ADD_PROJECT_DEPENDENCY(Boost REQUIRED serialization filesystem)
if(COAL_ENABLE_LOGGING)
ADD_PROJECT_DEPENDENCY(Boost REQUIRED log)
endif()
if(Boost_VERSION_STRING VERSION_LESS 1.81)
# Default C++ version should be C++11
CHECK_MINIMAL_CXX_STANDARD(11 ENFORCE)
else()
# Boost.Math will be C++14 starting in July 2023 (Boost 1.82 release)
CHECK_MINIMAL_CXX_STANDARD(14 ENFORCE)
endif()
# Optional dependencies
ADD_PROJECT_DEPENDENCY(octomap 1.8.0 PKG_CONFIG_REQUIRES "octomap >= 1.8")
if(octomap_FOUND)
set(COAL_HAS_OCTOMAP TRUE)
string(REPLACE "." ";" VERSION_LIST ${octomap_VERSION})
list(GET VERSION_LIST 0 OCTOMAP_MAJOR_VERSION)
list(GET VERSION_LIST 1 OCTOMAP_MINOR_VERSION)
list(GET VERSION_LIST 2 OCTOMAP_PATCH_VERSION)
message(STATUS "COAL uses Octomap")
else()
set(COAL_HAS_OCTOMAP FALSE)
message(STATUS "COAL does not use Octomap")
endif()
option(COAL_HAS_QHULL "use qhull library to compute convex hulls." FALSE)
if(COAL_HAS_QHULL)
find_package(Qhull REQUIRED COMPONENTS qhull_r qhullcpp)
endif()
find_package(assimp REQUIRED)
set(
${PROJECT_NAME}_HEADERS
include/coal/alloca.h
include/coal/collision_data.h
include/coal/BV/kIOS.h
include/coal/BV/BV.h
include/coal/BV/RSS.h
include/coal/BV/OBBRSS.h
include/coal/BV/BV_node.h
include/coal/BV/AABB.h
include/coal/BV/OBB.h
include/coal/BV/kDOP.h
include/coal/broadphase/broadphase.h
include/coal/broadphase/broadphase_SSaP.h
include/coal/broadphase/broadphase_SaP.h
include/coal/broadphase/broadphase_bruteforce.h
include/coal/broadphase/broadphase_collision_manager.h
include/coal/broadphase/broadphase_continuous_collision_manager-inl.h
include/coal/broadphase/broadphase_continuous_collision_manager.h
include/coal/broadphase/broadphase_dynamic_AABB_tree-inl.h
include/coal/broadphase/broadphase_dynamic_AABB_tree.h
include/coal/broadphase/broadphase_dynamic_AABB_tree_array-inl.h
include/coal/broadphase/broadphase_dynamic_AABB_tree_array.h
include/coal/broadphase/broadphase_interval_tree.h
include/coal/broadphase/broadphase_spatialhash-inl.h
include/coal/broadphase/broadphase_spatialhash.h
include/coal/broadphase/broadphase_callbacks.h
include/coal/broadphase/default_broadphase_callbacks.h
include/coal/broadphase/detail/hierarchy_tree-inl.h
include/coal/broadphase/detail/hierarchy_tree.h
include/coal/broadphase/detail/hierarchy_tree_array-inl.h
include/coal/broadphase/detail/hierarchy_tree_array.h
include/coal/broadphase/detail/interval_tree.h
include/coal/broadphase/detail/interval_tree_node.h
include/coal/broadphase/detail/morton-inl.h
include/coal/broadphase/detail/morton.h
include/coal/broadphase/detail/node_base-inl.h
include/coal/broadphase/detail/node_base.h
include/coal/broadphase/detail/node_base_array-inl.h
include/coal/broadphase/detail/node_base_array.h
include/coal/broadphase/detail/simple_hash_table-inl.h
include/coal/broadphase/detail/simple_hash_table.h
include/coal/broadphase/detail/simple_interval-inl.h
include/coal/broadphase/detail/simple_interval.h
include/coal/broadphase/detail/sparse_hash_table-inl.h
include/coal/broadphase/detail/sparse_hash_table.h
include/coal/broadphase/detail/spatial_hash-inl.h
include/coal/broadphase/detail/spatial_hash.h
include/coal/narrowphase/narrowphase.h
include/coal/narrowphase/gjk.h
include/coal/narrowphase/narrowphase_defaults.h
include/coal/narrowphase/minkowski_difference.h
include/coal/narrowphase/support_data.h
include/coal/narrowphase/support_functions.h
include/coal/shape/convex.h
include/coal/shape/convex.hxx
include/coal/shape/geometric_shape_to_BVH_model.h
include/coal/shape/geometric_shapes.h
include/coal/shape/geometric_shapes.hxx
include/coal/shape/geometric_shapes_traits.h
include/coal/shape/geometric_shapes_utility.h
include/coal/distance_func_matrix.h
include/coal/collision.h
include/coal/collision_func_matrix.h
include/coal/contact_patch.h
include/coal/contact_patch_func_matrix.h
include/coal/contact_patch/contact_patch_solver.h
include/coal/contact_patch/contact_patch_solver.hxx
include/coal/contact_patch/contact_patch_simplifier.h
include/coal/contact_patch/polygon_convex_hull.h
include/coal/distance.h
include/coal/math/matrix_3f.h
include/coal/math/vec_3f.h
include/coal/math/types.h
include/coal/math/transform.h
include/coal/data_types.h
include/coal/BVH/BVH_internal.h
include/coal/BVH/BVH_model.h
include/coal/BVH/BVH_front.h
include/coal/BVH/BVH_utility.h
include/coal/collision_object.h
include/coal/collision_utility.h
include/coal/hfield.h
include/coal/fwd.hh
include/coal/logging.h
include/coal/mesh_loader/assimp.h
include/coal/mesh_loader/loader.h
include/coal/internal/BV_fitter.h
include/coal/internal/BV_splitter.h
include/coal/internal/shape_shape_func.h
include/coal/internal/shape_shape_contact_patch_func.h
include/coal/internal/intersect.h
include/coal/internal/intersect.hxx
include/coal/internal/tools.h
include/coal/internal/traversal_node_base.h
include/coal/internal/traversal_node_bvh_shape.h
include/coal/internal/traversal_node_bvhs.h
include/coal/internal/traversal_node_hfield_shape.h
include/coal/internal/traversal_node_setup.h
include/coal/internal/traversal_node_shapes.h
include/coal/internal/traversal_recurse.h
include/coal/internal/traversal.h
include/coal/serialization/fwd.h
include/coal/serialization/serializer.h
include/coal/serialization/archive.h
include/coal/serialization/transform.h
include/coal/serialization/AABB.h
include/coal/serialization/BV_node.h
include/coal/serialization/BV_splitter.h
include/coal/serialization/BVH_model.h
include/coal/serialization/collision_data.h
include/coal/serialization/contact_patch.h
include/coal/serialization/collision_object.h
include/coal/serialization/convex.h
include/coal/serialization/eigen.h
include/coal/serialization/geometric_shapes.h
include/coal/serialization/memory.h
include/coal/serialization/OBB.h
include/coal/serialization/RSS.h
include/coal/serialization/OBBRSS.h
include/coal/serialization/kIOS.h
include/coal/serialization/kDOP.h
include/coal/serialization/hfield.h
include/coal/serialization/quadrilateral.h
include/coal/serialization/triangle.h
include/coal/timings.h
include/coal/shared_ptr_comparison.h
)
# boost::span requires Boost >= 1.78.0.
# On Ubuntu 22.04 the system Boost is 1.74 and is too old.
# We must install boost/core/span headers.
if(Boost_VERSION VERSION_LESS 1.78)
message(INFO "Boost <= 1.78 detected: boost::span headers will be installed")
list(
APPEND ${PROJECT_NAME}_HEADERS
include/coal/third_party/boost/core/data.hpp
include/coal/third_party/boost/core/detail/assert.hpp
include/coal/third_party/boost/core/make_span.hpp
include/coal/third_party/boost/core/span.hpp
)
endif()
if(
COAL_BACKWARD_COMPATIBILITY_WITH_HPP_FCL
AND NOT BUILD_STANDALONE_PYTHON_INTERFACE
)
set(
HPP_FCL_BACKWARD_COMPATIBILITY_HEADERS
include/hpp/fcl/broadphase/broadphase_bruteforce.h
include/hpp/fcl/broadphase/broadphase_callbacks.h
include/hpp/fcl/broadphase/broadphase_collision_manager.h
include/hpp/fcl/broadphase/broadphase_continuous_collision_manager.h
include/hpp/fcl/broadphase/broadphase_continuous_collision_manager-inl.h
include/hpp/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h
include/hpp/fcl/broadphase/broadphase_dynamic_AABB_tree_array-inl.h
include/hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h
include/hpp/fcl/broadphase/broadphase_dynamic_AABB_tree-inl.h
include/hpp/fcl/broadphase/broadphase.h
include/hpp/fcl/broadphase/broadphase_interval_tree.h
include/hpp/fcl/broadphase/broadphase_SaP.h
include/hpp/fcl/broadphase/broadphase_spatialhash.h
include/hpp/fcl/broadphase/broadphase_spatialhash-inl.h
include/hpp/fcl/broadphase/broadphase_SSaP.h
include/hpp/fcl/broadphase/default_broadphase_callbacks.h
include/hpp/fcl/broadphase/detail/hierarchy_tree_array.h
include/hpp/fcl/broadphase/detail/hierarchy_tree_array-inl.h
include/hpp/fcl/broadphase/detail/hierarchy_tree.h
include/hpp/fcl/broadphase/detail/hierarchy_tree-inl.h
include/hpp/fcl/broadphase/detail/interval_tree.h
include/hpp/fcl/broadphase/detail/interval_tree_node.h
include/hpp/fcl/broadphase/detail/morton.h
include/hpp/fcl/broadphase/detail/morton-inl.h
include/hpp/fcl/broadphase/detail/node_base_array.h
include/hpp/fcl/broadphase/detail/node_base_array-inl.h
include/hpp/fcl/broadphase/detail/node_base.h
include/hpp/fcl/broadphase/detail/node_base-inl.h
include/hpp/fcl/broadphase/detail/simple_hash_table.h
include/hpp/fcl/broadphase/detail/simple_hash_table-inl.h
include/hpp/fcl/broadphase/detail/simple_interval.h
include/hpp/fcl/broadphase/detail/simple_interval-inl.h
include/hpp/fcl/broadphase/detail/sparse_hash_table.h
include/hpp/fcl/broadphase/detail/sparse_hash_table-inl.h
include/hpp/fcl/broadphase/detail/spatial_hash.h
include/hpp/fcl/broadphase/detail/spatial_hash-inl.h
include/hpp/fcl/BV/AABB.h
include/hpp/fcl/BV/BV.h
include/hpp/fcl/BV/BV_node.h
include/hpp/fcl/BVH/BVH_front.h
include/hpp/fcl/BVH/BVH_internal.h
include/hpp/fcl/BVH/BVH_model.h
include/hpp/fcl/BVH/BVH_utility.h
include/hpp/fcl/BV/kDOP.h
include/hpp/fcl/BV/kIOS.h
include/hpp/fcl/BV/OBB.h
include/hpp/fcl/BV/OBBRSS.h
include/hpp/fcl/BV/RSS.h
include/hpp/fcl/coal.hpp
include/hpp/fcl/collision_data.h
include/hpp/fcl/collision_func_matrix.h
include/hpp/fcl/collision.h
include/hpp/fcl/collision_object.h
include/hpp/fcl/collision_utility.h
include/hpp/fcl/config.hh
include/hpp/fcl/contact_patch/contact_patch_solver.h
include/hpp/fcl/contact_patch/contact_patch_solver.hxx
include/hpp/fcl/contact_patch_func_matrix.h
include/hpp/fcl/contact_patch.h
include/hpp/fcl/data_types.h
include/hpp/fcl/deprecated.hh
include/hpp/fcl/distance_func_matrix.h
include/hpp/fcl/distance.h
include/hpp/fcl/fwd.hh
include/hpp/fcl/hfield.h
include/hpp/fcl/internal/BV_fitter.h
include/hpp/fcl/internal/BV_splitter.h
include/hpp/fcl/internal/intersect.h
include/hpp/fcl/internal/shape_shape_contact_patch_func.h
include/hpp/fcl/internal/shape_shape_func.h
include/hpp/fcl/internal/tools.h
include/hpp/fcl/internal/traversal.h
include/hpp/fcl/internal/traversal_node_base.h
include/hpp/fcl/internal/traversal_node_bvhs.h
include/hpp/fcl/internal/traversal_node_bvh_shape.h
include/hpp/fcl/internal/traversal_node_hfield_shape.h
include/hpp/fcl/internal/traversal_node_setup.h
include/hpp/fcl/internal/traversal_node_shapes.h
include/hpp/fcl/internal/traversal_recurse.h
include/hpp/fcl/internal/traversal_node_octree.h
include/hpp/fcl/logging.h
include/hpp/fcl/math/matrix_3f.h
include/hpp/fcl/math/transform.h
include/hpp/fcl/math/types.h
include/hpp/fcl/math/vec_3f.h
include/hpp/fcl/mesh_loader/assimp.h
include/hpp/fcl/mesh_loader/loader.h
include/hpp/fcl/narrowphase/gjk.h
include/hpp/fcl/narrowphase/minkowski_difference.h
include/hpp/fcl/narrowphase/narrowphase_defaults.h
include/hpp/fcl/narrowphase/narrowphase.h
include/hpp/fcl/narrowphase/support_data.h
include/hpp/fcl/narrowphase/support_functions.h
include/hpp/fcl/narrowphase/support_functions.hxx
include/hpp/fcl/octree.h
include/hpp/fcl/serialization/AABB.h
include/hpp/fcl/serialization/archive.h
include/hpp/fcl/serialization/BVH_model.h
include/hpp/fcl/serialization/BV_node.h
include/hpp/fcl/serialization/BV_splitter.h
include/hpp/fcl/serialization/collision_data.h
include/hpp/fcl/serialization/collision_object.h
include/hpp/fcl/serialization/contact_patch.h
include/hpp/fcl/serialization/convex.h
include/hpp/fcl/serialization/eigen.h
include/hpp/fcl/serialization/fwd.h
include/hpp/fcl/serialization/geometric_shapes.h
include/hpp/fcl/serialization/hfield.h
include/hpp/fcl/serialization/kDOP.h
include/hpp/fcl/serialization/kIOS.h
include/hpp/fcl/serialization/memory.h
include/hpp/fcl/serialization/OBB.h
include/hpp/fcl/serialization/OBBRSS.h
include/hpp/fcl/serialization/octree.h
include/hpp/fcl/serialization/quadrilateral.h
include/hpp/fcl/serialization/RSS.h
include/hpp/fcl/serialization/serializer.h
include/hpp/fcl/serialization/transform.h
include/hpp/fcl/serialization/triangle.h
include/hpp/fcl/shape/convex.h
include/hpp/fcl/shape/convex.hxx
include/hpp/fcl/shape/geometric_shapes.h
include/hpp/fcl/shape/geometric_shapes.hxx
include/hpp/fcl/shape/geometric_shapes_traits.h
include/hpp/fcl/shape/geometric_shapes_utility.h
include/hpp/fcl/shape/geometric_shape_to_BVH_model.h
include/hpp/fcl/timings.h
include/hpp/fcl/warning.hh
)
list(APPEND ${PROJECT_NAME}_HEADERS ${HPP_FCL_BACKWARD_COMPATIBILITY_HEADERS})
if(NOT BUILD_STANDALONE_PYTHON_INTERFACE)
HEADER_INSTALL(
COMPONENT hpp-fcl-compatibility
${HPP_FCL_BACKWARD_COMPATIBILITY_HEADERS}
)
endif()
endif()
if(COAL_HAS_OCTOMAP)
list(
APPEND ${PROJECT_NAME}_HEADERS
include/coal/octree.h
include/coal/serialization/octree.h
include/coal/internal/traversal_node_octree.h
)
endif(COAL_HAS_OCTOMAP)
add_subdirectory(doc)
if(NOT BUILD_STANDALONE_PYTHON_INTERFACE)
add_subdirectory(src)
endif()
if(BUILD_PYTHON_INTERFACE)
if(BUILD_STANDALONE_PYTHON_INTERFACE)
ADD_PROJECT_DEPENDENCY(${PROJECT_NAME} REQUIRED CONFIG)
endif()
add_custom_target(${PROJECT_NAME}_python)
set_target_properties(
${PROJECT_NAME}_python
PROPERTIES EXCLUDE_FROM_DEFAULT_BUILD True
)
if(COAL_PYTHON_NANOBIND)
find_package(Python REQUIRED COMPONENTS Interpreter Development.Module)
# jrl-cmakemodules use PYTHON_EXECUTABLE defined in FINDPYTHON macro.
# Since we doesn't call it in this branch, we must redefine it.
set(PYTHON_EXECUTABLE ${Python_EXECUTABLE})
add_subdirectory(python-nb)
else()
set(PYTHON_COMPONENTS Interpreter Development NumPy)
FINDPYTHON(REQUIRED)
ADD_PROJECT_PRIVATE_DEPENDENCY(eigenpy 2.9.2 REQUIRED)
add_subdirectory(python)
endif()
endif()
if(BUILD_TESTING)
add_subdirectory(test)
endif(BUILD_TESTING)
PKG_CONFIG_APPEND_LIBS("coal")
if(COAL_HAS_OCTOMAP)
# FCL_HAVE_OCTOMAP kept for backward compatibility reasons.
PKG_CONFIG_APPEND_CFLAGS(
"-DCOAL_HAS_OCTOMAP -DCOAL_HAVE_OCTOMAP -DFCL_HAVE_OCTOMAP -DOCTOMAP_MAJOR_VERSION=${OCTOMAP_MAJOR_VERSION} -DOCTOMAP_MINOR_VERSION=${OCTOMAP_MINOR_VERSION} -DOCTOMAP_PATCH_VERSION=${OCTOMAP_PATCH_VERSION}"
)
endif(COAL_HAS_OCTOMAP)
if(
COAL_BACKWARD_COMPATIBILITY_WITH_HPP_FCL
AND NOT BUILD_STANDALONE_PYTHON_INTERFACE
)
include(CMakePackageConfigHelpers)
write_basic_package_version_file(
hpp-fclConfigVersion.cmake
VERSION 3.0.0
COMPATIBILITY AnyNewerVersion
)
install(
FILES
hpp-fclConfig.cmake
${CMAKE_CURRENT_BINARY_DIR}/hpp-fclConfigVersion.cmake
DESTINATION lib/cmake/hpp-fcl
COMPONENT hpp-fcl-compatibility
)
include("${JRL_CMAKE_MODULES}/install-helpers.cmake")
ADD_INSTALL_TARGET(NAME hpp-fcl-compatibility COMPONENT hpp-fcl-compatibility)
endif()
SETUP_PROJECT_FINALIZE()
================================================
FILE: LICENSE
================================================
Software License Agreement (BSD License)
Copyright (c) 2008-2014, Willow Garage, Inc.
Copyright (c) 2014-2015, Open Source Robotics Foundation
Copyright (c) 2014-2023, CNRS
Copyright (c) 2018-2025, INRIA
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above
copyright notice, this list of conditions and the following
disclaimer in the documentation and/or other materials provided
with the distribution.
* Neither the name of Open Source Robotics Foundation nor the names of its
contributors may be used to endorse or promote products derived
from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
================================================
FILE: README.md
================================================
# Coal — An extension of the Flexible Collision Library
<p align="center">
<a href="https://gitlab.laas.fr/coal-library/coal/commits/devel/"><img src="https://gitlab.laas.fr/coal-library/coal/badges/devel/pipeline.svg" alt="Pipeline status"/></a>
<a href="https://gepettoweb.laas.fr/doc/coal-library/coal/devel/doxygen-html/"><img src="https://img.shields.io/badge/docs-online-brightgreen" alt="Documentation"/></a>
<a href="https://gepettoweb.laas.fr/doc/coal-library/coal/devel/coverage/"><img src="https://gepgitlab.laas.fr/coal-library/badges/devel/coverage.svg?job=doc-coverage" alt="Coverage report"/></a>
<a href="https://anaconda.org/conda-forge/coal"><img src="https://img.shields.io/conda/dn/conda-forge/coal.svg" alt="Conda Downloads"/></a>
<a href="https://anaconda.org/conda-forge/coal"><img src="https://img.shields.io/conda/vn/conda-forge/coal.svg" alt="Conda Version"/></a>
<a href="https://badge.fury.io/py/coal"><img src="https://badge.fury.io/py/coal.svg" alt="PyPI version"></a>
<a href="https://github.com/psf/black"><img alt="black" src="https://img.shields.io/badge/code%20style-black-000000.svg"></a>
<a href="https://github.com/astral-sh/ruff"><img alt="ruff" src="https://img.shields.io/endpoint?url=https://raw.githubusercontent.com/astral-sh/ruff/main/assets/badge/v2.json"></a>
</p>
[FCL](https://github.com/flexible-collision-library/fcl) was forked in 2015, creating a new project called HPP-FCL.
Since then, a large part of the code has been rewritten or removed (unused and untested code), and new features have been introduced (see below).
Due to these major changes, it was decided in 2024 to rename the HPP-FCL project to **Coal**.
If you use **Coal** in your projects and research papers, we would appreciate it if you would [cite it](https://raw.githubusercontent.com/coal-library/coal/devel/CITATION.bib).
## New features
Compared to the original [FCL](https://github.com/flexible-collision-library/fcl) library, the main new features are:
- dedicated and efficient implementations of the GJK and the EPA algorithms (we do not rely on [libccd](https://github.com/danfis/libccd))
- the support of safety margins for collision detection
- an accelerated version of collision detection *à la Nesterov*, which leads to increased performance (up to a factor of 2). More details are available in this [paper](https://hal.archives-ouvertes.fr/hal-03662157/)
- the computation of a lower bound of the distance between two objects when collision checking is performed, and no collision is found
- the implementation of Python bindings for easy code prototyping
- the support of new geometries such as height fields, capsules, ellipsoids, etc.
- enhance reliability with the fix of a myriad of bugs
- efficient computation of **contact points** and **contact patches** between objects
- full support of object serialization via Boost.Serialization
Note: the broad phase was reintroduced by [Justin Carpentier](https://github.com/jcarpent) in 2022, based on the FCL version 0.7.0.
This project is now used in several robotics frameworks such as [Pinocchio](https://github.com/stack-of-tasks/pinocchio), an open-source library which implements efficient and versatile rigid-body dynamics algorithms, the [Humanoid Path Planner](https://humanoid-path-planner.github.io/hpp-doc), an open-source library for Motion and Manipulation Planning. **Coal** has recently also been used to develop [Simple](https://github.com/Simple-Robotics/Simple), a new (differentiable) and efficient simulator for robotics and beyond.
## A high-performance library
Unlike the original FCL library, Coal implements the well-established [GJK algorithm](https://en.wikipedia.org/wiki/Gilbert%E2%80%93Johnson%E2%80%93Keerthi_distance_algorithm) and [its variants](https://hal.archives-ouvertes.fr/hal-03662157/) for collision detection and distance computation. These implementations lead to state-of-the-art performance, as shown in the figures below.
On the one hand, we have benchmarked Coal against major state-of-the-art software alternatives:
1. the [Bullet simulator](https://github.com/bulletphysics/bullet3),
2. the original [FCL library](https://github.com/flexible-collision-library/fcl) (used in the [Drake framework]()),
3. the [libccd library](https://github.com/danfis/libccd) (used in [MuJoCo](http://mujoco.org/)).
The results are depicted in the following figure, which notably shows that the accelerated variants of GJK largely outperform by a large margin (from 5x up to 15x times faster).
Please notice that the y-axis is in log scale.
<p align="center">
<img src="./doc/images/coal-vs-the-rest-of-the-world.png" width="600" alt="Coal vs the rest of the world" align="center"/>
</p>
On the other hand, why do we care about dedicated collision detection solvers like GJK for the narrow phase? Why can't we simply formulate the collision detection problem as a quadratic problem and call an off-the-shelf optimization solver like [ProxQP](https://github.com/Simple-Robotics/proxsuite))? Here is why:
<p align="center">
<img src="./doc/images/coal-performances.jpg" width="600" alt="Coal vs generic QP solvers" align="center"/>
</p>
One can observe that GJK-based approaches largely outperform solutions based on classic optimization solvers (e.g., QP solver like [ProxQP](https://github.com/Simple-Robotics/proxsuite)), notably for large geometries composed of tens or hundreds of vertices.
## Open-source projects relying on Coal
- [Pinocchio](https://github.com/stack-of-tasks/pinocchio) A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives.
- [IfcOpenShell](https://github.com/IfcOpenShell/IfcOpenShell) Open source IFC library and geometry engine.
- [Crocoddyl](https://github.com/loco-3d/crocoddyl) A software to realize model predictive control for complex robotics platforms.
- [TSID](https://github.com/stack-of-tasks/tsid/) A software that implements a Task Space Inverse Dynamics QP.
- [HPP](https://humanoid-path-planner.github.io/hpp-doc/) A SDK that implements motion planners for humanoids and other robots.
- [Jiminy](https://github.com/duburcqa/jiminy) A simulator based on Pinocchio.
- [ocs2](https://github.com/leggedrobotics/ocs2) A toolbox for Optimal Control for Switched Systems (OCS2)
## Installation
### Conda
Coal can be installed from the [conda-forge channel](https://anaconda.org/conda-forge/coal):
```bash
conda install coal -c conda-forge
```
### Docker
```
docker run --rm -it ghcr.io/coal-library/coal:devel
```
## Build
You can find build instruction [here](./development/build.md).
## C++ example
Both the C++ library and the python bindings can be installed as simply as `conda -c conda-forge install coal`.
The `.so` library, include files and python bindings will then be installed under `$CONDA_PREFIX/lib`, `$CONDA_PREFIX/include` and `$CONDA_PREFIX/lib/python3.XX/site-packages`.
Here is an example of using Coal in C++:
```cpp
#include "coal/math/transform.h"
#include "coal/mesh_loader/loader.h"
#include "coal/BVH/BVH_model.h"
#include "coal/collision.h"
#include "coal/collision_data.h"
#include <iostream>
#include <memory>
// Function to load a convex mesh from a `.obj`, `.stl` or `.dae` file.
//
// This function imports the object inside the file as a BVHModel, i.e. a point cloud
// which is hierarchically transformed into a tree of bounding volumes.
// The leaves of this tree are the individual points of the point cloud
// stored in the `.obj` file.
// This BVH can then be used for collision detection.
//
// For better computational efficiency, we sometimes prefer to work with
// the convex hull of the point cloud. This insures that the underlying object
// is convex and thus very fast collision detection algorithms such as
// GJK or EPA can be called with this object.
// Consequently, after creating the BVH structure from the point cloud, this function
// also computes its convex hull.
std::shared_ptr<coal::ConvexBase> loadConvexMesh(const std::string& file_name) {
coal::NODE_TYPE bv_type = coal::BV_AABB;
coal::MeshLoader loader(bv_type);
coal::BVHModelPtr_t bvh = loader.load(file_name);
bvh->buildConvexHull(true, "Qt");
return bvh->convex;
}
int main() {
// Create the coal shapes.
// Coal supports many primitive shapes: boxes, spheres, capsules, cylinders, ellipsoids, cones, planes,
// halfspace and convex meshes (i.e. convex hulls of clouds of points).
// It also supports BVHs (bounding volumes hierarchies), height-fields and octrees.
std::shared_ptr<coal::Ellipsoid> shape1 = std::make_shared<coal::Ellipsoid>(0.7, 1.0, 0.8);
std::shared_ptr<coal::ConvexBase> shape2 = loadConvexMesh("../path/to/mesh/file.obj");
// Define the shapes' placement in 3D space
coal::Transform3s T1;
T1.setQuatRotation(coal::Quaternion3f::UnitRandom());
T1.setTranslation(coal::Vec3s::Random());
coal::Transform3s T2 = coal::Transform3s::Identity();
T2.setQuatRotation(coal::Quaternion3f::UnitRandom());
T2.setTranslation(coal::Vec3s::Random());
// Define collision requests and results.
//
// The collision request allows to set parameters for the collision pair.
// For example, we can set a positive or negative security margin.
// If the distance between the shapes is less than the security margin, the shapes
// will be considered in collision.
// Setting a positive security margin can be usefull in motion planning,
// i.e to prevent shapes from getting too close to one another.
// In physics simulation, allowing a negative security margin may be usefull to stabilize the simulation.
coal::CollisionRequest col_req;
col_req.security_margin = 1e-1;
// A collision result stores the result of the collision test (signed distance between the shapes,
// witness points location, normal etc.)
coal::CollisionResult col_res;
// Collision call
coal::collide(shape1.get(), T1, shape2.get(), T2, col_req, col_res);
// We can access the collision result once it has been populated
std::cout << "Collision? " << col_res.isCollision() << "\n";
if (col_res.isCollision()) {
coal::Contact contact = col_res.getContact(0);
// The penetration depth does **not** take into account the security margin.
// Consequently, the penetration depth is the true signed distance which separates the shapes.
// To have the distance which takes into account the security margin, we can simply add the two together.
std::cout << "Penetration depth: " << contact.penetration_depth << "\n";
std::cout << "Distance between the shapes including the security margin: " << contact.penetration_depth + col_req.security_margin << "\n";
std::cout << "Witness point on shape1: " << contact.nearest_points[0].transpose() << "\n";
std::cout << "Witness point on shape2: " << contact.nearest_points[1].transpose() << "\n";
std::cout << "Normal: " << contact.normal.transpose() << "\n";
}
// Before calling another collision test, it is important to clear the previous results stored in the collision result.
col_res.clear();
return 0;
}
```
## Python example
Here is the C++ example from above translated in python using the python bindings of Coal:
```python
import numpy as np
import coal
# Optional:
# The Pinocchio library is a rigid body algorithms library and has a handy SE3 module.
# It can be installed as simply as `conda -c conda-forge install pinocchio`.
# Installing pinocchio also installs coal.
import pinocchio as pin
def loadConvexMesh(file_name: str):
loader = coal.MeshLoader()
bvh: coal.BVHModelBase = loader.load(file_name)
bvh.buildConvexHull(True, "Qt")
return bvh.convex
if __name__ == "__main__":
# Create coal shapes
shape1 = coal.Ellipsoid(0.7, 1.0, 0.8)
shape2 = loadConvexMesh("../path/to/mesh/file.obj")
# Define the shapes' placement in 3D space
T1 = coal.Transform3s()
T1.setTranslation(pin.SE3.Random().translation)
T1.setRotation(pin.SE3.Random().rotation)
T2 = coal.Transform3s();
# Using np arrays also works
T1.setTranslation(np.random.rand(3))
T2.setRotation(pin.SE3.Random().rotation)
# Define collision requests and results
col_req = coal.CollisionRequest()
col_res = coal.CollisionResult()
# Collision call
coal.collide(shape1, T1, shape2, T2, col_req, col_res)
# Accessing the collision result once it has been populated
print("Is collision? ", {col_res.isCollision()})
if col_res.isCollision():
contact: coal.Contact = col_res.getContact(0)
print("Penetration depth: ", contact.penetration_depth)
print("Distance between the shapes including the security margin: ", contact.penetration_depth + col_req.security_margin)
print("Witness point shape1: ", contact.getNearestPoint1())
print("Witness point shape2: ", contact.getNearestPoint2())
print("Normal: ", contact.normal)
# Before running another collision call, it is important to clear the old one
col_res.clear()
```
## Acknowledgments
The development of **Coal** is actively supported by the [Gepetto team](http://projects.laas.fr/gepetto/) [@LAAS-CNRS](http://www.laas.fr), the [Willow team](https://www.di.ens.fr/willow/) [@INRIA](http://www.inria.fr) and, to some extent, [Eureka Robotics](https://eurekarobotics.com/).
================================================
FILE: colcon.pkg
================================================
{
"hooks": [
"share/hpp-fcl/hook/ament_prefix_path.dsv",
"share/hpp-fcl/hook/python_path.dsv"
]
}
================================================
FILE: development/build.md
================================================
# Build and install from source with Pixi
To build Coal from source the easiest way is to use [Pixi](https://pixi.sh/latest/#installation).
[Pixi](https://pixi.sh/latest/) is a cross-platform package management tool for developers that
will install all required dependencies in `.pixi` directory.
It's used by our CI agent so you have the guarantee to get the right dependencies.
Run the following command to install dependencies, configure, build and test the project:
```bash
pixi run test
```
The project will be built in the `build` directory.
You can run `pixi shell` and build the project with `cmake` and `ninja` manually.
================================================
FILE: development/release.md
================================================
# Release with Pixi
To create a release with Pixi run the following commands on the **devel** branch:
```bash
COAL_VERSION=X.Y.Z pixi run release-new-version
git push origin
git push origin vX.Y.Z
```
Where `X.Y.Z` is the new version.
Be careful to follow the [Semantic Versioning](https://semver.org/spec/v2.0.0.html) rules.
You will find the following assets:
- `./build_new_version/coal-X.Y.Z.tar.gz`
- `./build_new_version/coal-X.Y.Z.tar.gz.sig`
Then, create a new release on [GitHub](https://github.com/coal-library/coal/releases/new) with:
* Tag: vX.Y.Z
* Title: Coal X.Y.Z
* Body:
```
## What's Changed
CHANGELOG CONTENT
**Full Changelog**: https://github.com/coal-library/coal/compare/vXX.YY.ZZ...vX.Y.Z
```
Where `XX.YY.ZZ` is the last release version.
Then upload `coal-X.Y.Z.tar.gz` and `coal-X.Y.Z.tar.gz.sig` and publish the release.
================================================
FILE: development/scripts/pixi/activation.bat
================================================
:: Find Python executable path for nanobind and Boost.Python
for /f "tokens=*" %%i in ('python -c "import sys; print(sys.executable)"') do set PYTHON_EXECUTABLE=%%i
:: Set default build value only if not previously set
if not defined COAL_BUILD_TYPE (set COAL_BUILD_TYPE=Release)
if not defined COAL_PYTHON_STUBS (set COAL_PYTHON_STUBS=ON)
if not defined COAL_PYTHON_NANOBIND (set COAL_PYTHON_NANOBIND=ON)
if not defined COAL_HAS_QHULL (set COAL_HAS_QHULL=OFF)
================================================
FILE: development/scripts/pixi/activation.sh
================================================
#! /bin/bash
# Activation script
# Remove flags setup from cxx-compiler
unset CFLAGS
unset CPPFLAGS
unset CXXFLAGS
unset DEBUG_CFLAGS
unset DEBUG_CPPFLAGS
unset DEBUG_CXXFLAGS
unset LDFLAGS
if [[ $host_alias == *"apple"* ]];
then
# On OSX setting the rpath and -L it's important to use the conda libc++ instead of the system one.
# If conda-forge use install_name_tool to package some libs, -headerpad_max_install_names is then mandatory
export LDFLAGS="-Wl,-headerpad_max_install_names -Wl,-rpath,$CONDA_PREFIX/lib -L$CONDA_PREFIX/lib"
elif [[ $host_alias == *"linux"* ]];
then
# On GNU/Linux, I don't know if these flags are mandatory with g++ but
# it allow to use clang++ as compiler
export LDFLAGS="-Wl,-rpath,$CONDA_PREFIX/lib -Wl,-rpath-link,$CONDA_PREFIX/lib -L$CONDA_PREFIX/lib"
# Conda compiler is named x86_64-conda-linux-gnu-c++, ccache can't resolve it
# (https://ccache.dev/manual/latest.html#config_compiler_type)
export CCACHE_COMPILERTYPE=gcc
fi
# Without -isystem, some LSP can't find headers
export COAL_CXX_FLAGS="$CXXFLAGS -isystem $CONDA_PREFIX/include"
# Set Python interpreter path for nanobind
export PYTHON_EXECUTABLE=$(which python)
# Set default build value only if not previously set
export COAL_BUILD_TYPE=${COAL_BUILD_TYPE:=Release}
export COAL_PYTHON_STUBS=${COAL_PYTHON_STUBS:=ON}
export COAL_PYTHON_NANOBIND=${COAL_PYTHON_NANOBIND:=ON}
export COAL_HAS_QHULL=${COAL_HAS_QHULL:=OFF}
================================================
FILE: doc/CMakeLists.txt
================================================
set(DOXYGEN_XML_OUTPUT "doxygen-xml" PARENT_SCOPE)
set(DOXYGEN_FILE_PATTERNS "*.h *.hh *.hxx" PARENT_SCOPE)
set(DOXYGEN_GENERATE_XML "YES" PARENT_SCOPE)
set(DOXYGEN_EXPAND_ONLY_PREDEF "NO" PARENT_SCOPE)
set(DOXYGEN_ENABLE_PREPROCESSING "YES" PARENT_SCOPE)
set(DOXYGEN_MACRO_EXPANSION "YES" PARENT_SCOPE)
set(DOXYGEN_EXCLUDE "${PROJECT_SOURCE_DIR}/include/hpp/")
# We must not document octree if Octomap is not setup.
# This create a build issue when building the bindings because doxygen-autodoc will
# include octree.h that will include octomap.h.
if(NOT COAL_HAS_OCTOMAP)
set(
DOXYGEN_EXCLUDE
"${DOXYGEN_EXCLUDE} ${PROJECT_SOURCE_DIR}/include/coal/octree.h"
)
set(
DOXYGEN_EXCLUDE
"${DOXYGEN_EXCLUDE} ${PROJECT_SOURCE_DIR}/include/coal/serialization/octree.h"
)
set(
DOXYGEN_EXCLUDE
"${DOXYGEN_EXCLUDE} ${PROJECT_SOURCE_DIR}/include/coal/internal/traversal_node_octree.h"
)
endif()
set(DOXYGEN_EXCLUDE ${DOXYGEN_EXCLUDE} PARENT_SCOPE)
set(DOXYGEN_PREDEFINED "IS_DOXYGEN" PARENT_SCOPE)
================================================
FILE: doc/Doxyfile.extra.in
================================================
USE_MATHJAX= YES
================================================
FILE: doc/generate_distance_plot.py
================================================
import matplotlib.pyplot as plt
import numpy as np
interactive = False
m = 1.0
b = 1.2
mb = m + b
X = np.array([-mb / 2, 0, m, mb, 2 * mb])
# X = np.linspace(-1, 4., 21)
def dlb(d):
if d < 0:
return None
if d > mb:
u = d - mb
return mb - m + u / 2
return d - m
plt.figure(figsize=(9, 3.5))
# plt.plot(X, X-m, ":k")
# plt.plot([m+b, X[-1]], [b, b], ":k")
plt.fill_between(
[m + b, X[-1]],
[b, b],
[b, X[-1] - m],
alpha=0.2,
hatch="|",
facecolor="g",
label="Distance lower band area",
)
plt.plot(X, [dlb(x) for x in X], "-g", label="distance lower bound")
# plt.plot([X[0], m, m, X[-1]], [0, 0, b, b], ":k")
plt.axvspan(X[0], m, alpha=0.5, hatch="\\", facecolor="r", label="Collision area")
ax = plt.gca()
ax.set_xlabel("Object distance")
ax.set_xticks([0, m, mb])
ax.set_xticklabels(["0", "security margin", "security margin\n+ break distance"])
ax.set_yticks([0, b])
ax.set_yticklabels(["0", "break distance"])
ax.grid(which="major", ls="solid")
ax.grid(which="minor", ls="dashed")
plt.axvline(0, ls="solid")
# plt.axvline(m, ls="dashed", label="margin")
# plt.axvline(mb, ls="dashed")
plt.axhline(0.0, ls="solid")
plt.title("Collision and distance lower band")
plt.legend(loc="lower right")
if interactive:
plt.show()
else:
import os.path as path
dir_path = path.dirname(path.realpath(__file__))
plt.savefig(
path.join(dir_path, "distance_computation.png"),
bbox_inches="tight",
orientation="landscape",
)
================================================
FILE: doc/gjk.py
================================================
#!/usr/bin/env python3
import pdb
import sys
# ABC = AB^AC
# (ABC^AJ).a = (j.c - j.b) a.a + (j.a - j.c) b.a + (j.b - j.a) c.a, for j = b or c
segment_fmt = "{j}a_aa"
plane_fmt = ""
edge_fmt = "{j}a * {b}a_{c}a + {j}{b} * {c}a_aa - {j}{c} * {b}a_aa"
# These checks must be negative and not positive, as in the cheat sheet.
# They are the same as in the cheat sheet, except that we consider (...).dot(A)
# instead of (...).dot(-A)
plane_tests = ["C.dot (a_cross_b)", "D.dot(a_cross_c)", "-D.dot(a_cross_b)"]
checks = (
plane_tests
+ [edge_fmt.format(**{"j": j, "b": "b", "c": "c"}) for j in ["b", "c"]]
+ [edge_fmt.format(**{"j": j, "b": "c", "c": "d"}) for j in ["c", "d"]]
+ [edge_fmt.format(**{"j": j, "b": "d", "c": "b"}) for j in ["d", "b"]]
+ [segment_fmt.format(**{"j": j}) for j in ["b", "c", "d"]]
)
checks_hr = (
["ABC.AO >= 0", "ACD.AO >= 0", "ADB.AO >= 0"]
+ ["(ABC ^ {}).AO >= 0".format(n) for n in ["AB", "AC"]]
+ ["(ACD ^ {}).AO >= 0".format(n) for n in ["AC", "AD"]]
+ ["(ADB ^ {}).AO >= 0".format(n) for n in ["AD", "AB"]]
+ ["AB.AO >= 0", "AC.AO >= 0", "AD.AO >= 0"]
)
# weights of the checks.
weights = (
[
2,
]
* 3
+ [
3,
]
* 6
+ [
1,
]
* 3
)
# Segment tests first, because they have lower weight.
# tests = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, ]
tests = [
9,
10,
11,
0,
1,
2,
3,
4,
5,
6,
7,
8,
]
assert len(tests) == len(checks)
assert sorted(tests) == list(range(len(tests)))
regions = [
"ABC",
"ACD",
"ADB",
"AB",
"AC",
"AD",
"A",
"Inside",
]
cases = list(range(len(regions)))
# The following 3 lists refer to table doc/GJK_tetrahedra_boolean_table.ods
# A check ID is (+/- (index+1)) where a minus sign encodes a NOT operation
# and index refers to an index in list checks.
# definitions is a list of list of check IDs to be ANDed.
# For instance, a0.a3.!a4 -> [ 1, 4, -5]
definitions = [
[1, 4, -5],
[2, 6, -7],
[3, 8, -9],
[-4, 9, 10],
[-6, 5, 11],
[-8, 7, 12],
[-10, -11, -12],
[-1, -2, -3],
]
# conditions is a list of (list of (list of check IDs to be ANDed) to be ORed).
conditions = [
[],
[],
[],
[],
[],
[],
[],
[], # [ [10, 11, 12], ], # I don't think this is always true...
]
# rejections is a list of (list of (list of check IDs to be ANDed) to be ORed).
rejections = [
[
[2, 6, 7],
[3, -8, -9],
],
[
[3, 8, 9],
[1, -4, -5],
],
[
[1, 4, 5],
[2, -6, -7],
],
[
[-1, -3],
],
[
[-2, -1],
],
[
[-3, -2],
],
[
[4, -5],
[6, -7],
[8, -9],
],
[],
]
implications = [
[
[
4,
5,
10,
],
[11],
],
[
[
6,
7,
11,
],
[12],
],
[
[
8,
9,
12,
],
[10],
],
[
[
-4,
-5,
11,
],
[10],
],
[
[
-6,
-7,
12,
],
[11],
],
[
[
-8,
-9,
10,
],
[12],
],
[[1, 4, 5, 6], [-7]],
[[2, 6, 9, 8], [-9]],
[[3, 8, 9, 4], [-5]],
[
[
-4,
5,
10,
],
[-11],
],
[
[
4,
-5,
-10,
],
[11],
],
[
[
-6,
7,
11,
],
[-12],
],
[
[
6,
-7,
-11,
],
[12],
],
[
[
-8,
9,
12,
],
[-10],
],
[
[
8,
-9,
-12,
],
[10],
],
[[10, 3, 9, -12, 4, -5], [1]],
[[10, -3, 1, -4], [9]],
[[10, -3, -1, 2, -6, 11], [5]],
[[-10, 11, 2, -12, -5, -1], [6]],
[[-10, 11, -2, 1, 5], [-6]],
[[-10, -11, 12, 1, -7, -2, 4], [-5]],
[[-10, -11, 12, -3, 2, 7], [-8]],
[[-10, -11, 12, -3, -2], [-1]],
]
def set_test_values(current_tests, test_values, itest, value):
def satisfies(values, indices):
for k in indices:
if k > 0 and values[k - 1] is not True:
return False
if k < 0 and values[-k - 1] is not False:
return False
return True
remaining_tests = list(current_tests)
next_test_values = list(test_values)
remaining_tests.remove(itest)
next_test_values[itest] = value
rerun = True
while rerun:
rerun = False
for impl in implications:
if satisfies(next_test_values, impl[0]):
for id in impl[1]:
k = (id - 1) if id > 0 else (-id - 1)
if k in remaining_tests:
next_test_values[k] = id > 0
remaining_tests.remove(k)
rerun = True
else:
if next_test_values[k] != (id > 0):
raise ValueError("Absurd case")
return remaining_tests, next_test_values
def set_tests_values(current_tests, test_values, itests, values):
for itest, value in zip(itests, values):
current_tests, test_values = set_test_values(
current_tests, test_values, itest, value
)
return current_tests, test_values
def apply_test_values(cases, test_values):
def canSatisfy(values, indices):
for k in indices:
if k > 0 and values[k - 1] is False:
return False
if k < 0 and values[-k - 1] is True:
return False
return True
def satisfies(values, indices):
for k in indices:
if k > 0 and values[k - 1] is not True:
return False
if k < 0 and values[-k - 1] is not False:
return False
return True
# Check all cases.
left_cases = []
for case in cases:
defi = definitions[case]
conds = conditions[case]
rejs = rejections[case]
if satisfies(test_values, defi):
# A definition is True, stop recursion
return [case]
if not canSatisfy(test_values, defi):
continue
for cond in conds:
if satisfies(test_values, cond):
# A condition is True, stop recursion
return [case]
append = True
for rej in rejs:
if satisfies(test_values, rej):
# A rejection is True, discard this case
append = False
break
if append:
left_cases.append(case)
return left_cases
def max_number_of_tests(
current_tests,
cases,
test_values=[
None,
]
* len(tests),
prevBestScore=float("inf"),
prevScore=0,
):
for test in current_tests:
assert test_values[test] is None, "Test " + str(test) + " already performed"
left_cases = apply_test_values(cases, test_values)
if len(left_cases) == 1:
return prevScore, {
"case": left_cases[0],
}
elif len(left_cases) == 0:
return prevScore, {
"case": None,
"comments": [
"applied " + str(test_values),
"to " + ", ".join([regions[c] for c in cases]),
],
}
assert len(current_tests) > 0, "No more test but " + str(left_cases) + " remains"
currentBestScore = prevBestScore
bestScore = float("inf")
bestOrder = [None, None]
for i, test in enumerate(current_tests):
assert bestScore >= currentBestScore
currentScore = prevScore + len(left_cases) * weights[test]
# currentScore = prevScore + weights[test]
if currentScore > currentBestScore: # Cannot do better -> stop
continue
try:
remaining_tests, next_test_values = set_test_values(
current_tests, test_values, test, True
)
except ValueError:
remaining_tests = None
if remaining_tests is not None:
# Do not put this in try catch as I do not want other ValueError to be
# understood as an infeasible branch.
score_if_t, order_if_t = max_number_of_tests(
remaining_tests,
left_cases,
next_test_values,
currentBestScore,
currentScore,
)
if score_if_t >= currentBestScore: # True didn't do better -> stop
continue
else:
score_if_t, order_if_t = prevScore, None
try:
remaining_tests, next_test_values = set_test_values(
current_tests, test_values, test, False
)
except ValueError:
remaining_tests = None
if remaining_tests is not None:
# Do not put this in try catch as I do not want other ValueError to be
# understood as an infeasible branch.
score_if_f, order_if_f = max_number_of_tests(
remaining_tests,
left_cases,
next_test_values,
currentBestScore,
currentScore,
)
else:
score_if_f, order_if_f = prevScore, None
currentScore = max(score_if_t, score_if_f)
if currentScore < bestScore:
if currentScore < currentBestScore:
bestScore = currentScore
bestOrder = {"test": test, "true": order_if_t, "false": order_if_f}
# pdb.set_trace()
currentBestScore = currentScore
if len(tests) == len(current_tests):
print("New best score: {}".format(currentBestScore))
return bestScore, bestOrder
def printComments(order, indent, file):
if "comments" in order:
for comment in order["comments"]:
print(indent + "// " + comment, file=file)
def printOrder(order, indent="", start=True, file=sys.stdout, curTests=[]):
if start:
print(
"bool GJK::projectTetrahedraOrigin(const Simplex& current, Simplex& next)",
file=file,
)
print("{", file=file)
print(
indent + "// The code of this function was generated using doc/gjk.py",
file=file,
)
print(indent + "const vertex_id_t a = 3, b = 2, c = 1, d = 0;", file=file)
for v in "abcd":
print(
indent
+ "const Vec3s& {} (current.vertex[{}]->w);".format(v.upper(), v),
file=file,
)
print(indent + "const Scalar aa = A.squaredNorm();".format(), file=file)
for v in "dcb":
for m in "abcd":
if m <= v:
print(
indent
+ "const Scalar {0}{1} = {2}.dot({3});".format(
v, m, v.upper(), m.upper()
),
file=file,
)
else:
print(
indent + "const Scalar& {0}{1} = {1}{0};".format(v, m),
file=file,
)
print(indent + "const Scalar {0}a_aa = {0}a - aa;".format(v), file=file)
for l0, l1 in zip("bcd", "cdb"):
print(
indent + "const Scalar {0}a_{1}a = {0}a - {1}a;".format(l0, l1),
file=file,
)
for v in "bc":
print(
indent + "const Vec3s a_cross_{0} = A.cross({1});".format(v, v.upper()),
file=file,
)
print("", file=file)
print("#define REGION_INSIDE() " + indent + "\\", file=file)
print(indent + " ray.setZero(); \\", file=file)
print(indent + " next.vertex[0] = current.vertex[d]; \\", file=file)
print(indent + " next.vertex[1] = current.vertex[c]; \\", file=file)
print(indent + " next.vertex[2] = current.vertex[b]; \\", file=file)
print(indent + " next.vertex[3] = current.vertex[a]; \\", file=file)
print(indent + " next.rank=4; \\", file=file)
print(indent + " return true;", file=file)
print("", file=file)
if "case" in order:
case = order["case"]
if case is None:
print(
indent + "// There are no case corresponding to this set of tests.",
file=file,
)
printComments(order, indent, file)
print(indent + "assert(false);", file=file)
return
region = regions[case]
print(indent + "// Region " + region, file=file)
printComments(order, indent, file)
toFree = ["b", "c", "d"]
if region == "Inside":
print(indent + "REGION_INSIDE()", file=file)
toFree = []
elif region == "A":
print(indent + "originToPoint (current, a, A, next, ray);", file=file)
elif len(region) == 2:
region[0]
B = region[1]
print(
indent
+ "originToSegment "
"(current, a, {b}, A, {B}, {B}-A, -{b}a_aa, next, ray);".format(
**{"b": B.lower(), "B": B}
),
file=file,
)
toFree.remove(B.lower())
elif len(region) == 3:
B = region[1]
C = region[2]
test = plane_tests[["ABC", "ACD", "ADB"].index(region)]
if test.startswith("-"):
test = test[1:]
else:
test = "-" + test
print(
indent
+ "originToTriangle "
"(current, a, {b}, {c}, ({B}-A).cross({C}-A), {t}, next, ray);".format(
**{"b": B.lower(), "c": C.lower(), "B": B, "C": C, "t": test}
),
file=file,
)
toFree.remove(B.lower())
toFree.remove(C.lower())
else:
assert False, "Unknown region " + region
for pt in toFree:
print(
indent + "free_v[nfree++] = current.vertex[{}];".format(pt), file=file
)
else:
assert "test" in order and "true" in order and "false" in order
check = checks[order["test"]]
check_hr = checks_hr[order["test"]]
printComments(order, indent, file)
nextTests_t = curTests + [
"a" + str(order["test"] + 1),
]
nextTests_f = curTests + [
"!a" + str(order["test"] + 1),
]
if order["true"] is None:
if order["false"] is None:
print(
indent
+ """assert(false && "Case {} should never happen.");""".format(
check_hr
)
)
else:
print(
indent
+ "assert(!({} <= 0)); // Not {} / {}".format(
check, check_hr, ".".join(nextTests_f)
),
file=file,
)
printOrder(
order["false"],
indent=indent,
start=False,
file=file,
curTests=nextTests_f,
)
elif order["false"] is None:
print(
indent
+ "assert({} <= 0); // {} / {}".format(
check, check_hr, ".".join(nextTests_t)
),
file=file,
)
printOrder(
order["true"],
indent=indent,
start=False,
file=file,
curTests=nextTests_t,
)
else:
print(
indent
+ "if ({} <= 0) {{ // if {} / {}".format(
check, check_hr, ".".join(nextTests_t)
),
file=file,
)
printOrder(
order["true"],
indent=indent + " ",
start=False,
file=file,
curTests=nextTests_t,
)
print(
indent
+ "}} else {{ // not {} / {}".format(check_hr, ".".join(nextTests_f)),
file=file,
)
printOrder(
order["false"],
indent=indent + " ",
start=False,
file=file,
curTests=nextTests_f,
)
print(indent + "}} // end of {}".format(check_hr), file=file)
if start:
print("", file=file)
print("#undef REGION_INSIDE", file=file)
print(indent + "return false;", file=file)
print("}", file=file)
def unit_tests():
# a4, a5, a10, a11, a12
cases = list(range(len(regions)))
pdb.set_trace()
left_cases = apply_test_values(
cases,
test_values=[
None,
None,
None,
True,
True,
None,
None,
None,
None,
True,
True,
True,
],
)
assert len(left_cases) > 1
# unit_tests()
score, order = max_number_of_tests(tests, cases)
print(score)
printOrder(order, indent=" ")
# TODO add weights such that:
# - it is preferred to have all the use of one check in one branch.
# idea: ponderate by the number of remaining tests.
================================================
FILE: doc/mesh-mesh-collision-call.dot
================================================
digraph CD {
rankdir = BT
compound=true
size = 11.7
"std::size_t BVHCollide(const CollisionGeometry* o1,\nconst Transform3s& tf1, const CollisionGeometry* o2,\nconst Transform3s& tf2, const CollisionRequest& request,\nCollisionResult& result)" [shape = box]
"bool OBB::overlap(const OBB& other,\nconst CollisionRequest& request,\nScalar& sqrDistLowerBound) const" [shape = box]
"bool OBBRSS::overlap(const OBBRSS& other,\nconst CollisionRequest& request,\nScalar& sqrDistLowerBound) const" [shape = box]
"bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBB& b1, const OBB& b2,\n const CollisionRequest& request, Scalar& sqrDistLowerBound)" [shape = box]
"bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBBRSS& b1, const OBBRSS& b2,\nconst CollisionRequest& request, Scalar& sqrDistLowerBound)" [shape = box]
"bool BVNode::overlap(const BVNode& other,\nconst CollisionRequest& request,\nScalar& sqrDistLowerBound) const" [shape = box]
"bool BVHCollisionTraversalNode::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\n -request\n - result" [shape = box]
"bool MeshCollisionTraversalNode<T_BVH>::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\n -request\n - result" [shape = box]
"void collide(MeshCollisionTraversalNode<T_BVH>* node,\n const CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)" [shape = box]
"void collisionRecurse(MeshCollisionTraversalNode<T_BVH>* node,\n int b1, int b2, BVHFrontList* front_list, Scalar& sqrDistLowerBound)" [shape = box]
"void propagateBVHFrontListCollisionRecurse(MeshCollisionTraversalNode<T_BVH>* node\n, BVHFrontList* front_list, const CollisionRequest& request, CollisionResult& result)" [shape = box]
"bool MeshCollisionTraversalNodeOBBRSS::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\n -request\n - result" [shape = box]
"MeshCollisionTraversalNode<T_BVH>::leafTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\n -request\n - result" [shape = box]
"bool obbDisjointAndLowerBoundDistance\n(const Matrix3s& B, const Vec3s& T, const Vec3s& a, const Vec3s& b,\n Scalar& squaredLowerBoundDistance)" [shape = box]
"std::size_t BVHCollide(const CollisionGeometry* o1,\nconst Transform3s& tf1, const CollisionGeometry* o2,\nconst Transform3s& tf2, const CollisionRequest& request,\nCollisionResult& result)" -> "void collide(MeshCollisionTraversalNode<T_BVH>* node,\n const CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)"
"bool OBB::overlap(const OBB& other,\nconst CollisionRequest& request,\nScalar& sqrDistLowerBound) const" -> "bool obbDisjointAndLowerBoundDistance\n(const Matrix3s& B, const Vec3s& T, const Vec3s& a, const Vec3s& b,\n Scalar& squaredLowerBoundDistance)"
"bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBB& b1, const OBB& b2,\n const CollisionRequest& request, Scalar& sqrDistLowerBound)" -> "bool obbDisjointAndLowerBoundDistance\n(const Matrix3s& B, const Vec3s& T, const Vec3s& a, const Vec3s& b,\n Scalar& squaredLowerBoundDistance)"
"bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBBRSS& b1, const OBBRSS& b2,\nconst CollisionRequest& request, Scalar& sqrDistLowerBound)" -> "bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBB& b1, const OBB& b2,\n const CollisionRequest& request, Scalar& sqrDistLowerBound)"
"void collide(MeshCollisionTraversalNode<T_BVH>* node,\n const CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)"-> "void propagateBVHFrontListCollisionRecurse(MeshCollisionTraversalNode<T_BVH>* node\n, BVHFrontList* front_list, const CollisionRequest& request, CollisionResult& result)"
"void collide(MeshCollisionTraversalNode<T_BVH>* node,\n const CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)" -> "void collisionRecurse(MeshCollisionTraversalNode<T_BVH>* node,\n int b1, int b2, BVHFrontList* front_list, Scalar& sqrDistLowerBound)"
"void collisionRecurse(MeshCollisionTraversalNode<T_BVH>* node,\n int b1, int b2, BVHFrontList* front_list, Scalar& sqrDistLowerBound)" -> "bool MeshCollisionTraversalNode<T_BVH>::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\n -request\n - result"
"void collisionRecurse(MeshCollisionTraversalNode<T_BVH>* node,\n int b1, int b2, BVHFrontList* front_list, Scalar& sqrDistLowerBound)" -> "MeshCollisionTraversalNode<T_BVH>::leafTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\n -request\n - result"
"void propagateBVHFrontListCollisionRecurse(MeshCollisionTraversalNode<T_BVH>* node\n, BVHFrontList* front_list, const CollisionRequest& request, CollisionResult& result)" -> "void collisionRecurse(MeshCollisionTraversalNode<T_BVH>* node,\n int b1, int b2, BVHFrontList* front_list, Scalar& sqrDistLowerBound)"
"void propagateBVHFrontListCollisionRecurse(MeshCollisionTraversalNode<T_BVH>* node\n, BVHFrontList* front_list, const CollisionRequest& request, CollisionResult& result)" -> "bool MeshCollisionTraversalNode<T_BVH>::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\n -request\n - result"
"bool MeshCollisionTraversalNodeOBBRSS::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\n -request\n - result" -> "bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBBRSS& b1, const OBBRSS& b2,\nconst CollisionRequest& request, Scalar& sqrDistLowerBound)"
"bool MeshCollisionTraversalNode<T_BVH>::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\n -request\n - result" -> "bool MeshCollisionTraversalNodeOBBRSS::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\n -request\n - result" [color=red]
"bool MeshCollisionTraversalNode<T_BVH>::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\n -request\n - result" -> "bool BVHCollisionTraversalNode::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\n -request\n - result" [color = red]
"bool OBBRSS::overlap(const OBBRSS& other,\nconst CollisionRequest& request,\nScalar& sqrDistLowerBound) const" -> "bool OBB::overlap(const OBB& other,\nconst CollisionRequest& request,\nScalar& sqrDistLowerBound) const"
"bool BVNode::overlap(const BVNode& other,\nconst CollisionRequest& request,\nScalar& sqrDistLowerBound) const" -> "bool OBB::overlap(const OBB& other,\nconst CollisionRequest& request,\nScalar& sqrDistLowerBound) const"
"bool BVHCollisionTraversalNode::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\n -request\n - result" -> "bool BVNode::overlap(const BVNode& other,\nconst CollisionRequest& request,\nScalar& sqrDistLowerBound) const"
}
================================================
FILE: doc/notes
================================================
In include/hpp/fcl/traversal:
- some initialize method compute the position of all triangles in
global frame before performing collision test,
- bool initialize(MeshShapeCollisionTraversalNode<BV, S, NarrowPhaseSolver>& node, ...
- bool initialize(ShapeMeshCollisionTraversalNode<S, BV, NarrowPhaseSolver>& node, ...
- bool initialize(MeshCollisionTraversalNode<BV>& node,...
- other do not.
- bool initialize(MeshOcTreeCollisionTraversalNode<BV, NarrowPhaseSolver>& node, ...
- bool initialize(OcTreeMeshCollisionTraversalNode<BV, NarrowPhaseSolver>& node, ...
- bool initialize(MeshShapeCollisionTraversalNodeOBB<S, NarrowPhaseSolver>& node, ...
- bool initialize(MeshShapeCollisionTraversalNodeRSS<S, NarrowPhaseSolver>& node, ...
- bool initialize(MeshShapeCollisionTraversalNodekIOS<S, NarrowPhaseSolver>& node, ...
- bool initialize(MeshShapeCollisionTraversalNodeOBBRSS<S, NarrowPhaseSolver>& node, ...
- bool initialize(ShapeMeshCollisionTraversalNodeOBB<S, NarrowPhaseSolver>& node, ...
- bool initialize(ShapeMeshCollisionTraversalNodeRSS<S, NarrowPhaseSolver>& node, ...
- bool initialize(ShapeMeshCollisionTraversalNodekIOS<S, NarrowPhaseSolver>& node, ...
- bool initialize(ShapeMeshCollisionTraversalNodeOBBRSS<S, NarrowPhaseSolver>& node, ...
- bool initialize(MeshCollisionTraversalNodeOBB& node, ...
- bool initialize(MeshCollisionTraversalNodeRSS& node, ...
- bool initialize(MeshCollisionTraversalNodekIOS& node, ...
- bool initialize(MeshCollisionTraversalNodeOBBRSS& node, ...
-------------------------------------------------------------------------------
classes
- MeshCollisionTraversalNodeRSS,
- MeshCollisionTraversalNodekIOS,
- MeshCollisionTraversalNodeOBBRSS
derive from
- MeshCollisionTraversalNode <RSS>,
- MeshCollisionTraversalNode <kIOS>,
- MeshCollisionTraversalNode <OBBRSS>.
They store the relative position and orientation between two objects to test for
collision. before calling overlap function, this additional information computes
the relative positions of the bounding volumes.
-------------------------------------------------------------------------------
For primitive shapes, collision and distance computation are very close.
ShapeShapeCollide calls indeed ShapeShapeDistance. It would be convenient to
merge CollisionRequest and DistanceRequest on the one hand and CollisionResult
and DistanceResult on the other hand into two classes InteractionRequest and
InteractionResult.
================================================
FILE: doc/python/doxygen-boost.hh
================================================
#ifndef DOXYGEN_BOOST_DOC_HH
#define DOXYGEN_BOOST_DOC_HH
#ifndef DOXYGEN_DOC_HH
#error "You should have included doxygen.hh first."
#endif // DOXYGEN_DOC_HH
#include <boost/python.hpp>
namespace doxygen {
namespace visitor {
template <typename function_type,
typename policy_type = boost::python::default_call_policies>
struct member_func_impl : boost::python::def_visitor<
member_func_impl<function_type, policy_type> > {
member_func_impl(const char* n, const function_type& f)
: name(n), function(f) {}
member_func_impl(const char* n, const function_type& f, policy_type p)
: name(n), function(f), policy(p) {}
template <class classT>
inline void visit(classT& c) const {
// Either a boost::python::keyword<N> object or a void_ object
call(c, member_func_args(function));
}
template <class classT, std::size_t nkeywords>
inline void call(
classT& c, const boost::python::detail::keywords<nkeywords>& args) const {
c.def(name, function, member_func_doc(function), args, policy);
}
template <class classT>
inline void call(classT& c, const void_&) const {
c.def(name, function, member_func_doc(function), policy);
}
const char* name;
const function_type& function;
policy_type policy;
};
// TODO surprisingly, this does not work when defined here but it works when
// defined after the generated files are included.
template <typename function_type>
inline member_func_impl<function_type> member_func(
const char* name, const function_type& function) {
return member_func_impl<function_type>(name, function);
}
template <typename function_type, typename policy_type>
inline member_func_impl<function_type, policy_type> member_func(
const char* name, const function_type& function,
const policy_type& policy) {
return member_func_impl<function_type, policy_type>(name, function, policy);
}
#define DOXYGEN_DOC_DECLARE_INIT_VISITOR(z, nargs, unused) \
template <typename Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, class Arg)> \
struct init_##nargs##_impl \
: boost::python::def_visitor< \
init_##nargs##_impl<Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, Arg)> > { \
typedef constructor_##nargs##_impl<Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, Arg)> \
constructor; \
typedef boost::python::init<BOOST_PP_ENUM_PARAMS(nargs, Arg)> init_base; \
\
template <class classT> \
inline void visit(classT& c) const { \
call(c, constructor::args()); \
} \
\
template <class classT> \
void call(classT& c, \
const boost::python::detail::keywords<nargs + 1>& args) const { \
c.def(init_base(constructor::doc(), args)); \
} \
\
template <class classT> \
void call(classT& c, const void_&) const { \
c.def(init_base(constructor::doc())); \
} \
}; \
\
template <typename Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, class Arg)> \
inline init_##nargs##_impl<Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, Arg)> \
init() { \
return init_##nargs##_impl<Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, Arg)>(); \
}
BOOST_PP_REPEAT(DOXYGEN_DOC_MAX_NUMBER_OF_ARGUMENTS_IN_CONSTRUCTOR,
DOXYGEN_DOC_DECLARE_INIT_VISITOR, ~)
#undef DOXYGEN_DOC_DECLARE_INIT_VISITOR
} // namespace visitor
template <typename Func>
void def(const char* name, Func func) {
boost::python::def(name, func, member_func_doc(func));
}
} // namespace doxygen
#endif // DOXYGEN_BOOST_DOC_HH
================================================
FILE: doc/python/doxygen.hh
================================================
#ifndef DOXYGEN_DOC_HH
#define DOXYGEN_DOC_HH
#include <boost/preprocessor/repetition.hpp>
#include <boost/preprocessor/punctuation/comma_if.hpp>
#include <boost/mpl/void.hpp>
#ifndef DOXYGEN_DOC_MAX_NUMBER_OF_ARGUMENTS_IN_CONSTRUCTOR
#define DOXYGEN_DOC_MAX_NUMBER_OF_ARGUMENTS_IN_CONSTRUCTOR 10
#endif
namespace doxygen {
typedef boost::mpl::void_ void_;
template <typename _class>
struct class_doc_impl {
static inline const char* run() { return ""; }
static inline const char* attribute(const char*) { return ""; }
};
template <typename _class>
inline const char* class_doc() {
return class_doc_impl<_class>::run();
}
template <typename _class>
inline const char* class_attrib_doc(const char* name) {
return class_doc_impl<_class>::attribute(name);
}
template <typename FuncPtr>
inline const char* member_func_doc(FuncPtr) {
return "";
}
template <typename FuncPtr>
inline void_ member_func_args(FuncPtr) {
return void_();
}
#define DOXYGEN_DOC_DECLARE_CONSTRUCTOR(z, nargs, unused) \
template <typename Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, class Arg)> \
struct constructor_##nargs##_impl { \
static inline const char* doc() { return ""; } \
static inline void_ args() { return void_(); } \
}; \
\
template <typename Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, class Arg)> \
inline const char* constructor_doc() { \
return constructor_##nargs##_impl<Class BOOST_PP_COMMA_IF( \
nargs) BOOST_PP_ENUM_PARAMS(nargs, Arg)>::doc(); \
}
BOOST_PP_REPEAT(DOXYGEN_DOC_MAX_NUMBER_OF_ARGUMENTS_IN_CONSTRUCTOR,
DOXYGEN_DOC_DECLARE_CONSTRUCTOR, ~)
#undef DOXYGEN_DOC_DECLARE_CONSTRUCTOR
/*
template <typename Class>
inline const char* constructor_doc ()
{
return "";
}
*/
template <typename Class>
struct destructor_doc_impl {
static inline const char* run() { return ""; }
};
template <typename Class>
inline const char* destructor_doc() {
return destructor_doc_impl<Class>::run();
}
/* TODO class attribute can be handled by
template <typename Class, typename AttributeType>
const char* attribute_doc (AttributeType Class::* ptr)
{
// Body looks like
// if (ptr == &Class::attributeName)
// return "attrib documentation";
return "undocumented";
}
*/
} // namespace doxygen
#endif // DOXYGEN_DOC_HH
================================================
FILE: doc/python/doxygen_xml_parser.py
================================================
#!/usr/bin/python3
# ruff: noqa: E501
from __future__ import print_function
from lxml import etree
from os import path
from xml_docstring import XmlDocString
import sys
template_file_header = """#ifndef DOXYGEN_AUTODOC_{header_guard}
#define DOXYGEN_AUTODOC_{header_guard}
#include "{path}/doxygen.hh"
"""
template_file_footer = """
#endif // DOXYGEN_AUTODOC_{header_guard}
"""
template_class_doc = """
template <{tplargs}>
struct class_doc_impl< {classname} >
{{
static inline const char* run ()
{{
return "{docstring}";
}}
static inline const char* attribute (const char* attrib)
{{{attributes}
(void)attrib; // turn off unused parameter warning.
return "";
}}
}};"""
template_class_attribute_body = """
if (strcmp(attrib, "{attribute}") == 0)
return "{docstring}";"""
template_constructor_doc = """
template <{tplargs}>
struct constructor_{nargs}_impl< {classname_prefix}{comma}{argsstring} >
{{
static inline const char* doc ()
{{
return "{docstring}";
}}
static inline boost::python::detail::keywords<{nargs}+1> args ()
{{
return ({argnamesstring});
}}
}};"""
template_destructor_doc = """
template <{tplargs}>
struct destructor_doc_impl < {classname_prefix} >
{{
static inline const char* run ()
{{
return "{docstring}";
}}
}};"""
template_member_func_doc = """
{template}inline const char* member_func_doc ({rettype} ({classname_prefix}*function_ptr) {argsstring})
{{{body}
return "";
}}"""
template_member_func_doc_body = """
if (function_ptr == static_cast<{rettype} ({classname_prefix}*) {argsstring}>(&{classname_prefix}{membername}))
return "{docstring}";"""
template_member_func_args = """
{template}inline boost::python::detail::keywords<{n}> member_func_args ({rettype} ({classname_prefix}*function_ptr) {argsstring})
{{{body}
return ({default_args});
}}"""
template_member_func_args_body = """
if (function_ptr == static_cast<{rettype} ({classname_prefix}*) {argsstring}>(&{classname_prefix}{membername}))
return ({args});"""
template_static_func_doc = """
{template}inline const char* member_func_doc ({rettype} (*function_ptr) {argsstring})
{{{body}
return "";
}}"""
template_static_func_doc_body = """
if (function_ptr == static_cast<{rettype} (*) {argsstring}>(&{namespace}::{membername}))
return "{docstring}";"""
template_open_namespace = """namespace {namespace} {{"""
template_close_namespace = """}} // namespace {namespace}"""
template_include_intern = """#include <doxygen_autodoc/{filename}>
"""
template_include_extern = """#include <{filename}>
"""
def _templateParamToDict(param):
type_ = param.find("type")
declname = param.find("declname")
defname = param.find("defname")
# FIXME type may contain references in two ways:
# - the real param type
# - the name of the template argument is recognized as the name of a type...
if defname is None and declname is None:
typetext = type_.text
if typetext is None:
typetext = ""
for c in type_.iter():
if c == type_:
continue
if c.text is not None:
typetext += c.text
if c.tail is not None:
typetext += c.tail
if typetext.startswith("typename") or typetext.startswith("class"):
if sys.version_info.major == 2:
s = typetext.split()
return {"type": s[0].strip(), "name": typetext[len(s[0]) :].strip()}
else:
s = typetext.split(maxsplit=1)
assert len(s) == 2
return {"type": s[0].strip(), "name": s[1].strip()}
else:
return {"type": type_.text, "name": ""}
else:
if type_.text is None:
# type_ is not a typename but an existing type
type_ = type_.find("ref")
assert defname.text == declname.text
return {"type": type_.text, "name": defname.text}
def makeHeaderGuard(filename):
return filename.upper().replace(".", "_").replace("/", "_").replace("-", "_")
def format_description(brief, detailed):
b = [el.text.strip() for el in brief.iter() if el.text] if brief is not None else []
d = (
[el.text.strip() for el in detailed.iter() if el.text]
if detailed is not None
else []
)
text = "".join(b)
if d:
text += "\n" + "".join(d)
return text
class Reference(object):
def __init__(self, index, id=None, name=None):
self.id = id
self.name = name
self.index = index
def xmlToType(self, node, array=None, parentClass=None, tplargs=None):
"""
- node:
- parentClass: a class
- tplargs: if one of the args is parentClass and no template arguments are provided,
set the template arguments to this value
- array: content of the sibling tag 'array'
"""
if node.text is not None:
t = node.text.strip()
else:
t = ""
for c in node.iterchildren():
if c.tag == "ref":
refid = c.attrib["refid"]
if parentClass is not None and refid == parentClass.id:
t += " " + parentClass.name
if c.tail is not None and c.tail.lstrip()[0] != "<":
if tplargs is not None:
t += tplargs
elif (
parentClass is not None
and isinstance(parentClass, ClassCompound)
and parentClass.hasTypeDef(c.text.strip())
):
parent_has_templates = len(parentClass.template_params) > 0
if parent_has_templates:
t += " typename " + parentClass._className() + "::"
else:
t += " " + parentClass._className() + "::"
self_has_templates = (
c.tail is not None and c.tail.strip().find("<") != -1
)
if self_has_templates:
t += " template "
t += c.text.strip()
elif self.index.hasref(refid):
t += " " + self.index.getref(refid).name
else:
self.index.output.warn("Unknown reference: ", c.text, refid)
t += " " + c.text.strip()
else:
if c.text is not None:
t += " " + c.text.strip()
if c.tail is not None:
t += " " + c.tail.strip()
if array is not None:
t += array.text
return t
# Only for function as of now.
class MemberDef(Reference):
def __init__(self, index, memberdefxml, parent):
super(MemberDef, self).__init__(
index=index,
id=memberdefxml.attrib["id"],
name=memberdefxml.find("definition").text,
)
self.parent = parent
self.xml = memberdefxml
self.const = memberdefxml.attrib["const"] == "yes"
self.static = memberdefxml.attrib["static"] == "yes"
self.rettype = memberdefxml.find("type")
self.params = tuple(
[
(param.find("type"), param.find("declname"), param.find("array"))
for param in self.xml.findall("param")
]
)
self.special = (
self.rettype.text is None and len(self.rettype.getchildren()) == 0
)
# assert self.special or len(self.rettype.text) > 0
self._templateParams(self.xml.find("templateparamlist"))
def _templateParams(self, tpl):
if tpl is not None:
self.template_params = tuple(
[_templateParamToDict(param) for param in tpl.iterchildren(tag="param")]
)
else:
self.template_params = tuple()
def prototypekey(self):
prototype = (
self.xmlToType(self.rettype, parentClass=self.parent),
tuple([tuple(t.items()) for t in self.template_params]),
tuple(
[
self.xmlToType(param.find("type"), parentClass=self.parent)
for param in self.xml.findall("param")
]
),
self.const,
)
return prototype
def s_prototypeArgs(self):
return "({0}){1}".format(self.s_args(), " const" if self.const else "")
def s_args(self):
# If the class is templated, check if one of the argument is the class itself.
# If so, we must add the template arguments to the class (if there is none)
if len(self.parent.template_params) > 0:
tplargs = (
" <"
+ ", ".join([d["name"] for d in self.parent.template_params])
+ " > "
)
args = ", ".join(
[
self.xmlToType(
type, array, parentClass=self.parent, tplargs=tplargs
)
for type, declname, array in self.params
]
)
else:
args = ", ".join(
[
self.xmlToType(type, array, parentClass=self.parent)
for type, declname, array in self.params
]
)
return args
def s_tpldecl(self):
if len(self.template_params) == 0:
return ""
return ", ".join([d["type"] + " " + d["name"] for d in self.template_params])
def s_rettype(self):
assert not self.special, (
"Member {} ({}) is a special function and no return type".format(
self.name, self.id
)
)
if len(self.parent.template_params) > 0:
tplargs = (
" <"
+ ", ".join([d["name"] for d in self.parent.template_params])
+ " > "
)
else:
tplargs = None
if isinstance(self.parent, ClassCompound):
return self.xmlToType(
self.rettype, parentClass=self.parent, tplargs=tplargs
)
else:
return self.xmlToType(self.rettype)
def s_name(self):
return self.xml.find("name").text.strip()
def s_docstring(self):
return self.index.xml_docstring.getDocString(
self.xml.find("briefdescription"),
self.xml.find("detaileddescription"),
self.index.output,
)
def n_args(self):
return len(self.params)
def s_argnamesstring(self):
def getdeclname(i, declname):
if declname is None or declname.text is None or declname.text.strip() == "":
return "arg{}".format(i)
return declname.text.strip()
arg = """boost::python::arg("{}")"""
argnames = [
"self",
] + [getdeclname(i, declname) for i, (_, declname, _) in enumerate(self.params)]
return ", ".join([arg.format(n) for n in argnames])
def include(self):
loc = self.xml.find("location")
# The location is based on $CMAKE_SOURCE_DIR. Remove first directory.
return loc.attrib["file"].split("/", 1)[1]
class CompoundBase(Reference):
def __init__(self, compound, index):
self.compound = compound
self.filename = path.join(index.directory, compound.attrib["refid"] + ".xml")
self.tree = etree.parse(self.filename)
self.definition = self.tree.getroot().find("compounddef")
super(CompoundBase, self).__init__(
index,
id=self.definition.attrib["id"],
name=self.definition.find("compoundname").text,
)
class NamespaceCompound(CompoundBase):
def __init__(self, *args):
super(NamespaceCompound, self).__init__(*args)
self.typedefs = []
self.enums = []
self.static_funcs = []
self.template_params = tuple()
# Add references
for section in self.definition.iterchildren("sectiondef"):
assert "kind" in section.attrib
kind = section.attrib["kind"]
if kind == "enum":
self.parseEnumSection(section)
elif kind == "typedef":
self.parseTypedefSection(section)
elif kind == "func":
self.parseFuncSection(section)
def parseEnumSection(self, section):
for member in section.iterchildren("memberdef"):
ref = Reference(
index=self.index,
id=member.attrib["id"],
name=self.name + "::" + member.find("name").text,
)
self.index.registerReference(ref)
self.enums.append(member)
for value in member.iterchildren("enumvalue"):
ref = Reference(
index=self.index,
id=value.attrib["id"],
name=self.name + "::" + member.find("name").text,
)
def parseTypedefSection(self, section):
for member in section.iterchildren("memberdef"):
ref = Reference(
index=self.index,
id=member.attrib["id"],
name=self.name + "::" + member.find("name").text,
)
self.index.registerReference(ref)
self.typedefs.append(member)
def parseFuncSection(self, section):
for member in section.iterchildren("memberdef"):
self.static_funcs.append(MemberDef(self.index, member, self))
def innerNamespace(self):
return self.name
def write(self, output):
pass
class ClassCompound(CompoundBase):
def __init__(self, *args):
super(ClassCompound, self).__init__(*args)
self.member_funcs = list()
self.static_funcs = list()
self.special_funcs = list()
self.attributes = list()
self.struct = self.compound.attrib["kind"] == "struct"
self.public = self.definition.attrib["prot"] == "public"
self.template_specialization = self.name.find("<") > 0
self.typedef = dict()
# Handle templates
self._templateParams(self.definition.find("templateparamlist"))
for memberdef in self.definition.iter(tag="memberdef"):
if memberdef.attrib["prot"] != "public":
continue
if memberdef.attrib["kind"] == "variable":
self._attribute(memberdef)
elif memberdef.attrib["kind"] == "typedef":
ref = Reference(
index=self.index,
id=memberdef.attrib["id"],
name=self._className() + "::" + memberdef.find("name").text,
)
self.index.registerReference(ref)
self.typedef[memberdef.find("name").text.strip()] = True
elif memberdef.attrib["kind"] == "enum":
if memberdef.find("name").text is None:
ref_name = self._className() + "::" + "anonymous_enum"
else:
ref_name = self._className() + "::" + memberdef.find("name").text
ref = Reference(
index=self.index,
id=memberdef.attrib["id"],
name=ref_name,
)
self.index.registerReference(ref)
for value in memberdef.iterchildren("enumvalue"):
value_ref = Reference(
index=self.index,
id=value.attrib["id"],
name=ref.name,
)
self.index.registerReference(value_ref)
elif memberdef.attrib["kind"] == "function":
self._memberfunc(memberdef)
def _templateParams(self, tpl):
if tpl is not None:
self.template_params = tuple(
[_templateParamToDict(param) for param in tpl.iterchildren(tag="param")]
)
else:
self.template_params = tuple()
def _templateDecl(self):
if not hasattr(self, "template_params") or len(self.template_params) == 0:
return ""
return ", ".join([d["type"] + " " + d["name"] for d in self.template_params])
def _className(self):
if not hasattr(self, "template_params") or len(self.template_params) == 0:
return self.name
return (
self.name
+ " <"
+ ", ".join([d["name"] for d in self.template_params])
+ " >"
)
def hasTypeDef(self, typename):
return typename in self.typedef
def innerNamespace(self):
return self._className()
def _memberfunc(self, member):
m = MemberDef(self.index, member, self)
if m.special:
self.special_funcs.append(m)
elif m.static:
self.static_funcs.append(m)
else:
self.member_funcs.append(m)
def _writeClassDoc(self, output):
docstring = self.index.xml_docstring.getDocString(
self.definition.find("briefdescription"),
self.definition.find("detaileddescription"),
self.index.output,
)
attribute_docstrings = ""
for member in self.attributes:
_dc = self.index.xml_docstring.getDocString(
member.find("briefdescription"),
member.find("detaileddescription"),
self.index.output,
)
if len(_dc) == 0:
continue
attribute_docstrings += template_class_attribute_body.format(
attribute=member.find("name").text,
docstring=_dc,
)
if len(docstring) == 0 and len(attribute_docstrings) == 0:
return
output.out(
template_class_doc.format(
tplargs=self._templateDecl(),
classname=self._className(),
docstring=docstring,
attributes=attribute_docstrings,
)
)
def write(self, output):
if not self.public:
return
if self.template_specialization:
output.warn(
"Disable class {} because template argument are not resolved for templated class specialization.".format(
self.name
)
)
return
include = self.definition.find("includes")
if include is None:
output.err("Does not know where to write doc of", self.name)
return
output.open(include.text)
output.out(template_include_extern.format(filename=include.text))
output.out(template_open_namespace.format(namespace="doxygen"))
# Write class doc
self._writeClassDoc(output)
# Group member function by prototype
member_funcs = dict()
for m in self.member_funcs:
prototype = m.prototypekey()
if prototype in member_funcs:
member_funcs[prototype].append(m)
else:
member_funcs[prototype] = [
m,
]
classname_prefix = self._className() + "::"
for member in self.special_funcs:
docstring = member.s_docstring()
argnamesstring = member.s_argnamesstring()
if len(docstring) == 0 and len(argnamesstring) == 0:
continue
if member.s_name()[0] == "~":
output.out(
template_destructor_doc.format(
tplargs=self._templateDecl(),
classname_prefix=self._className(),
docstring=docstring,
)
)
else:
output.out(
template_constructor_doc.format(
tplargs=", ".join(
[
d["type"] + " " + d["name"]
for d in self.template_params + member.template_params
]
),
nargs=len(member.params),
comma=", " if len(member.params) > 0 else "",
classname_prefix=self._className(),
argsstring=member.s_args(),
docstring=docstring,
argnamesstring=argnamesstring,
)
)
for prototype, members in member_funcs.items():
# remove undocumented members
documented_members = []
docstrings = []
argnamesstrings = []
for member in members:
docstring = member.s_docstring()
argnamesstring = member.s_argnamesstring()
if len(docstring) == 0 and len(argnamesstring) == 0:
continue
documented_members.append(member)
docstrings.append(docstring)
argnamesstrings.append(argnamesstring)
if len(documented_members) == 0:
continue
# Write docstrings
body = "".join(
[
template_member_func_doc_body.format(
classname_prefix=classname_prefix,
membername=member.s_name(),
docstring=docstring,
rettype=member.s_rettype(),
argsstring=member.s_prototypeArgs(),
)
for member, docstring in zip(documented_members, docstrings)
]
)
member = members[0]
tplargs = ", ".join(
[
d["type"] + " " + d["name"]
for d in self.template_params + member.template_params
]
)
output.out(
template_member_func_doc.format(
template=(
"template <{}>\n".format(tplargs) if len(tplargs) > 0 else ""
),
rettype=member.s_rettype(),
classname_prefix=classname_prefix,
argsstring=member.s_prototypeArgs(),
body=body,
)
)
# Write argnamesstrings
body = "".join(
[
template_member_func_args_body.format(
classname_prefix=classname_prefix,
membername=member.s_name(),
args=argnamesstring,
rettype=member.s_rettype(),
argsstring=member.s_prototypeArgs(),
)
for member, argnamesstring in zip(
documented_members, argnamesstrings
)
]
)
n_args = member.n_args()
default_args = ", ".join(
[
"""boost::python::arg("self")""",
]
+ ["""boost::python::arg("arg{}")""".format(i) for i in range(n_args)]
)
output.out(
template_member_func_args.format(
template=(
"template <{}>\n".format(tplargs) if len(tplargs) > 0 else ""
),
rettype=member.s_rettype(),
n=n_args + 1,
default_args=default_args,
classname_prefix=classname_prefix,
argsstring=member.s_prototypeArgs(),
body=body,
)
)
output.out(template_close_namespace.format(namespace="doxygen"))
output.close()
def _attribute(self, member):
self.attributes.append(member)
class Index:
"""
This class is responsible for generating the list of all C++-usable documented elements.
"""
def __init__(self, input, output):
self.tree = etree.parse(input)
self.directory = path.dirname(input)
self.xml_docstring = XmlDocString(self)
self.compounds = list()
self.references = dict()
self.output = output
def parseCompound(self):
for compound in self.tree.getroot().iterchildren("compound"):
if compound.attrib["kind"] in ["class", "struct"]:
obj = ClassCompound(compound, self)
elif compound.attrib["kind"] == "namespace":
obj = NamespaceCompound(compound, self)
if obj.id not in self.compounds:
self.compounds.append(obj.id)
self.registerReference(obj)
def write(self):
# Header
self.output.open("doxygen_xml_parser_for_cmake.hh")
# self.output.out ("// Generated on {}".format (asctime()))
self.output.close()
# Implement template specialization for classes and member functions
for id in self.compounds:
compound = self.references[id]
compound.write(self.output)
self.output.open("functions.h")
# Implement template specialization for static functions
static_funcs = dict()
prototypes = list()
includes = list()
for id in self.compounds:
compound = self.references[id]
for m in compound.static_funcs:
include = m.include()
if include not in includes:
includes.append(include)
docstring = m.s_docstring()
if len(docstring) == 0:
continue
prototype = m.prototypekey()
if prototype in static_funcs:
static_funcs[prototype].append((m, docstring))
else:
static_funcs[prototype] = [
(m, docstring),
]
prototypes.append(prototype)
self.output.out(
"".join(
[
template_include_extern.format(filename=filename)
for filename in includes
]
)
)
self.output.out(template_open_namespace.format(namespace="doxygen"))
for prototype in prototypes:
member_and_docstring_s = static_funcs[prototype]
body = "".join(
[
template_static_func_doc_body.format(
namespace=member.parent.innerNamespace(),
membername=member.s_name(),
docstring=docstring,
rettype=member.s_rettype(),
argsstring=member.s_prototypeArgs(),
)
for member, docstring in member_and_docstring_s
]
)
member = member_and_docstring_s[0][0]
# TODO fix case of static method in templated class.
tplargs = ", ".join(
[
d["type"] + " " + d["name"]
for d in member.parent.template_params + member.template_params
]
)
self.output.out(
template_static_func_doc.format(
template=(
"template <{}>\n".format(tplargs) if len(tplargs) > 0 else ""
),
rettype=member.s_rettype(),
argsstring=member.s_prototypeArgs(),
body=body,
)
)
self.output.out(template_close_namespace.format(namespace="doxygen"))
self.output.close()
def registerReference(self, obj, overwrite=True):
if obj.id in self.references:
if obj.name != self.references[obj.id].name:
self.output.warn(
"!!!! Compounds " + obj.id + " already exists.",
obj.name,
self.references[obj.id].name,
)
else:
self.output.warn("Reference " + obj.id + " already exists.", obj.name)
if not overwrite:
return
self.references[obj.id] = obj
def hasref(self, id):
return id in self.references
def getref(self, id):
return self.references[id]
class OutputStreams(object):
def __init__(self, output_dir, warn, error, errorPrefix=""):
self.output_dir = output_dir
self._out = None
self._warn = warn
self._err = error
self.errorPrefix = errorPrefix
self._created_files = dict()
def open(self, name):
assert self._out is None, "You did not close the previous file"
import os
fullname = os.path.join(self.output_dir, name)
dirname = os.path.dirname(fullname)
if not os.path.isdir(dirname):
os.makedirs(dirname)
if name in self._created_files:
self._out = self._created_files[name]
else:
import codecs
if sys.version_info >= (3,):
encoding = "utf-8"
else:
encoding = "latin1"
self._out = codecs.open(fullname, mode="w", encoding=encoding)
self._created_files[name] = self._out
# Header
self.out(
template_file_header.format(
path=os.path.dirname(os.path.abspath(__file__)),
header_guard=makeHeaderGuard(name),
)
)
def close(self):
self._out = None
def writeFooterAndCloseFiles(self):
for n, f in self._created_files.items():
# Footer
self._out = f
self.out(
template_file_footer.format(
header_guard=makeHeaderGuard(n),
)
)
f.close()
self._created_files.clear()
self._out = None
def out(self, *args):
if sys.version_info >= (3,):
print(*args, file=self._out)
else:
print(" ".join(str(arg) for arg in args).decode("latin1"), file=self._out)
def warn(self, *args):
print(self.errorPrefix, *args, file=self._warn)
def err(self, *args):
print(self.errorPrefix, *args, file=self._err)
if __name__ == "__main__":
import argparse
parser = argparse.ArgumentParser(
description="Process Doxygen XML documentation and generate C++ code."
)
parser.add_argument("doxygen_index_xml", type=str, help="the Doxygen XML index.")
parser.add_argument("output_directory", type=str, help="the output directory.")
args = parser.parse_args()
index = Index(
input=sys.argv[1],
output=OutputStreams(args.output_directory, sys.stdout, sys.stderr),
)
index.parseCompound()
index.write()
index.output.writeFooterAndCloseFiles()
assert index.output._out is None
================================================
FILE: doc/python/xml_docstring.py
================================================
class XmlDocString(object):
def __init__(self, index):
self.index = index
self.tags = {
"para": self.para,
"ref": self.ref,
"briefdescription": self.otherTags,
"detaileddescription": self.otherTags,
"parameterlist": self.parameterlist,
"parameterdescription": self.otherTags,
"emphasis": self.emphasis,
"simplesect": self.simplesect,
"formula": self.formula,
"itemizedlist": self.itemizedlist,
"listitem": self.listitem,
}
self.unkwownTags = set()
self.unkwownReferences = dict()
self._linesep = '\\n"\n"'
try:
from pylatexenc.latex2text import LatexNodes2Text
self.latex = LatexNodes2Text()
except ImportError:
self.latex = None
def clear(self):
self.lines = []
self.unkwownTags.clear()
self.unkwownReferences.clear()
def writeErrors(self, output):
ret = False
for t in self.unkwownTags:
output.warn("Unknown tag: ", t)
ret = True
for ref, node in self.unkwownReferences.items():
output.warn("Unknown reference: ", ref, node.text)
ret = True
return ret
def _write(self, str):
nlines = str.split("\n")
if len(self.lines) == 0:
self.lines += nlines
else:
self.lines[-1] += nlines[0]
self.lines += nlines[1:]
# self.lines += nlines[1:]
def _newline(self, n=1):
self.lines.extend(
[
"",
]
* n
)
def _clean(self):
s = 0
for line in self.lines:
if len(line.strip()) == 0:
s += 1
else:
break
e = len(self.lines)
for line in reversed(self.lines):
if len(line.strip()) == 0:
e -= 1
else:
break
self.lines = self.lines[s:e]
def getDocString(self, brief, detailled, output):
self.clear()
if brief is not None:
self.visit(brief)
if detailled is not None and len(detailled.getchildren()) > 0:
if brief is not None:
self._newline()
self.visit(detailled)
from sys import version_info
self.writeErrors(output)
self._clean()
if version_info[0] == 2:
return self._linesep.join(self.lines).encode("utf-8")
else:
return self._linesep.join(self.lines)
def visit(self, node):
assert isinstance(node.tag, str)
tag = node.tag
if tag not in self.tags:
self.unknownTag(node)
else:
self.tags[tag](node)
def unknownTag(self, node):
self.unkwownTags.add(node.tag)
self.otherTags(node)
def otherTags(self, node):
if node.text:
self._write(node.text.strip().replace('"', r"\""))
for c in node.iterchildren():
self.visit(c)
if c.tail:
self._write(c.tail.strip().replace('"', r"\""))
def emphasis(self, node):
self._write("*")
self.otherTags(node)
self._write("*")
def simplesect(self, node):
self._write(node.attrib["kind"].title() + ": ")
self.otherTags(node)
def para(self, node):
if node.text:
self._write(node.text.replace('"', r"\""))
for c in node.iterchildren():
self.visit(c)
if c.tail:
self._write(c.tail.replace('"', r"\""))
self._newline()
def ref(self, node):
refid = node.attrib["refid"]
if self.index.hasref(refid):
self._write(self.index.getref(refid).name)
else:
self.unkwownReferences[refid] = node
self._write(node.text)
assert len(node.getchildren()) == 0
def parameterlist(self, node):
self._newline()
self._write(node.attrib["kind"].title())
self._newline()
for item in node.iterchildren("parameteritem"):
self.parameteritem(item)
def parameteritem(self, node):
indent = " "
self._write(indent + "- ")
# should contain two children
assert len(node.getchildren()) == 2
namelist = node.find("parameternamelist")
desc = node.find("parameterdescription")
sep = ""
for name in namelist.iterchildren("parametername"):
self._write(sep + name.text)
sep = ", "
self._write(" ")
self.visit(desc)
def itemizedlist(self, node):
self._newline()
self.otherTags(node)
def listitem(self, node):
self._write("- ")
self.otherTags(node)
def formula(self, node):
if node.text:
if self.latex is None:
self._write(node.text.strip())
else:
self._write(self.latex.latex_to_text(node.text))
================================================
FILE: doc/shape-mesh-collision-call.dot
================================================
digraph CD {
rankdir = BT
compound=true
size = 11.7
"BVHShapeCollider<OBBRSS, Shape, NarrowPhaseSolver>::collide\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver,\nconst CollisionRequest& request, CollisionResult& result)\ncollision_func_matrix.cpp" [shape = box]
"details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeOBBRSS\n<T_SH, NarrowPhaseSolver>, OBBRSS, T_SH, NarrowPhaseSolver>\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s&tf2,\nNarrowPhaseSolver* nsolver, const CollisionRequest& request,\nCollisionResult& result)\ncollision_func_matrix.cpp" [shape = box]
"void collide(CollisionTraversalNodeBase* node,\nconst CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)\ncollision_node.cpp" [shape = box]
"void propagateBVHFrontListCollisionRecurse\n(CollisionTraversalNodeBase* node, const CollisionRequest& request,\nCollisionResult& result, BVHFrontList* front_list)\ntraversal/traversal_recurse.cpp" [shape = box]
"void collisionRecurse(CollisionTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list,\nScalar& sqrDistLowerBound)\ntraversal/traversal_recurse.cpp" [shape = box]
"virtual bool CollisionTraversalNodeBase::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const = 0\ntraversal/traversal_node_base.h" [shape = box]
"virtual void CollisionTraversalNodeBase::leafTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\ntraversal/traversal_node_base.h" [shape = box]
"bool MeshShapeCollisionTraversalNodeOBBRSS::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" [shape = box]
"bool MeshShapeCollisionTraversalNodeOBBRSS::leafTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" [shape = box]
"bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBBRSS& b1,\nconst OBBRSS& b2, const CollisionRequest& request,\nScalar& sqrDistLowerBound)\nBV/OBBRSS.cpp" [shape = box]
"bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBB& b1, const OBB& b2,\nconst CollisionRequest& request, Scalar& sqrDistLowerBound)\nBV/OBB.cpp" [shape = box]
"bool obbDisjointAndLowerBoundDistance (const Matrix3s& B, const Vec3s& T,\nconst Vec3s& a, const Vec3s& b,\nconst CollisionRequest& request,\nScalar& squaredLowerBoundDistance)\nBV/OBB.cpp" [shape = box]
"void details::meshShapeCollisionOrientedNodeLeafTesting <OBBRSS, Shape, NarrowPhaseSolver>\n(int b1, int b2, const BVHModel<BV>* model1, const S& model2,\nVec3s* vertices, Triangle* tri_indices, const Transform3s& tf1,\nconst Transform3s& tf2, const NarrowPhaseSolver* nsolver,\nbool enable_statistics, int& num_leaf_tests,\nconst CollisionRequest& request, CollisionResult& result,\nScalar& sqrDistLowerBound)\ntraversal/traversal_node_bvh_shape.h:293" [shape = box]
"bool GJKSolver_indep::shapeTriangleIntersect<Shape>\n(const S& s, const Transform3s& tf,\nconst Vec3s& P1, const Vec3s& P2, const Vec3s& P3,\nScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h:156" [shape = box]
"BVHShapeCollider<OBBRSS, Shape, NarrowPhaseSolver>::collide\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver,\nconst CollisionRequest& request, CollisionResult& result)\ncollision_func_matrix.cpp" -> "details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeOBBRSS\n<T_SH, NarrowPhaseSolver>, OBBRSS, T_SH, NarrowPhaseSolver>\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s&tf2,\nNarrowPhaseSolver* nsolver, const CollisionRequest& request,\nCollisionResult& result)\ncollision_func_matrix.cpp"
"details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeOBBRSS\n<T_SH, NarrowPhaseSolver>, OBBRSS, T_SH, NarrowPhaseSolver>\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s&tf2,\nNarrowPhaseSolver* nsolver, const CollisionRequest& request,\nCollisionResult& result)\ncollision_func_matrix.cpp" -> "void collide(CollisionTraversalNodeBase* node,\nconst CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)\ncollision_node.cpp"
"void collide(CollisionTraversalNodeBase* node,\nconst CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)\ncollision_node.cpp" -> "void propagateBVHFrontListCollisionRecurse\n(CollisionTraversalNodeBase* node, const CollisionRequest& request,\nCollisionResult& result, BVHFrontList* front_list)\ntraversal/traversal_recurse.cpp"
"void collide(CollisionTraversalNodeBase* node,\nconst CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)\ncollision_node.cpp" -> "void collisionRecurse(CollisionTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list,\nScalar& sqrDistLowerBound)\ntraversal/traversal_recurse.cpp"
"void propagateBVHFrontListCollisionRecurse\n(CollisionTraversalNodeBase* node, const CollisionRequest& request,\nCollisionResult& result, BVHFrontList* front_list)\ntraversal/traversal_recurse.cpp" -> "void collisionRecurse(CollisionTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list,\nScalar& sqrDistLowerBound)\ntraversal/traversal_recurse.cpp"
"void collisionRecurse(CollisionTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list,\nScalar& sqrDistLowerBound)\ntraversal/traversal_recurse.cpp" -> "virtual bool CollisionTraversalNodeBase::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const = 0\ntraversal/traversal_node_base.h"
"void collisionRecurse(CollisionTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list,\nScalar& sqrDistLowerBound)\ntraversal/traversal_recurse.cpp" -> "virtual void CollisionTraversalNodeBase::leafTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\ntraversal/traversal_node_base.h"
"virtual bool CollisionTraversalNodeBase::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const = 0\ntraversal/traversal_node_base.h" -> "bool MeshShapeCollisionTraversalNodeOBBRSS::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" [color=red]
"virtual void CollisionTraversalNodeBase::leafTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\ntraversal/traversal_node_base.h" -> "bool MeshShapeCollisionTraversalNodeOBBRSS::leafTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" [color = red]
"bool MeshShapeCollisionTraversalNodeOBBRSS::BVTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" -> "bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBBRSS& b1,\nconst OBBRSS& b2, const CollisionRequest& request,\nScalar& sqrDistLowerBound)\nBV/OBBRSS.cpp"
"bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBBRSS& b1,\nconst OBBRSS& b2, const CollisionRequest& request,\nScalar& sqrDistLowerBound)\nBV/OBBRSS.cpp" -> "bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBB& b1, const OBB& b2,\nconst CollisionRequest& request, Scalar& sqrDistLowerBound)\nBV/OBB.cpp"
"bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBB& b1, const OBB& b2,\nconst CollisionRequest& request, Scalar& sqrDistLowerBound)\nBV/OBB.cpp" -> "bool obbDisjointAndLowerBoundDistance (const Matrix3s& B, const Vec3s& T,\nconst Vec3s& a, const Vec3s& b,\nconst CollisionRequest& request,\nScalar& squaredLowerBoundDistance)\nBV/OBB.cpp"
"bool MeshShapeCollisionTraversalNodeOBBRSS::leafTesting\n(int b1, int b2, Scalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" -> "void details::meshShapeCollisionOrientedNodeLeafTesting <OBBRSS, Shape, NarrowPhaseSolver>\n(int b1, int b2, const BVHModel<BV>* model1, const S& model2,\nVec3s* vertices, Triangle* tri_indices, const Transform3s& tf1,\nconst Transform3s& tf2, const NarrowPhaseSolver* nsolver,\nbool enable_statistics, int& num_leaf_tests,\nconst CollisionRequest& request, CollisionResult& result,\nScalar& sqrDistLowerBound)\ntraversal/traversal_node_bvh_shape.h:293"
"void details::meshShapeCollisionOrientedNodeLeafTesting <OBBRSS, Shape, NarrowPhaseSolver>\n(int b1, int b2, const BVHModel<BV>* model1, const S& model2,\nVec3s* vertices, Triangle* tri_indices, const Transform3s& tf1,\nconst Transform3s& tf2, const NarrowPhaseSolver* nsolver,\nbool enable_statistics, int& num_leaf_tests,\nconst CollisionRequest& request, CollisionResult& result,\nScalar& sqrDistLowerBound)\ntraversal/traversal_node_bvh_shape.h:293" -> "bool GJKSolver_indep::shapeTriangleIntersect<Shape>\n(const S& s, const Transform3s& tf,\nconst Vec3s& P1, const Vec3s& P2, const Vec3s& P3,\nScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h:156"
}
================================================
FILE: doc/shape-shape-collision-call.dot
================================================
digraph CD {
rankdir = BT
compound=true
size = 11.7
"template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nstd::size_t ShapeShapeCollide(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver,const CollisionRequest& request,\nCollisionResult& result)" [shape = box]
"template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nScalar ShapeShapeDistance(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver, const DistanceRequest& request,\nDistanceResult& result)" [shape = box]
"void distance(DistanceTraversalNodeBase* node,\nBVHFrontList* front_list, int qsize)" [shape = box]
"void distanceRecurse(DistanceTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list)" [shape = box]
"void ShapeDistanceTraversalNode::leafTesting(int, int) const\ntraversal/traversal_node_shapes.h" [shape = box]
"template<typename S1, typename S2> bool GJKSolver_indep::shapeDistance\n(const S1& s1, const Transform3s& tf1, const S2& s2, const Transform3s& tf2,\nScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h" [shape = box]
"template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nstd::size_t ShapeShapeCollide(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver,const CollisionRequest& request,\nCollisionResult& result)" -> "template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nScalar ShapeShapeDistance(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver, const DistanceRequest& request,\nDistanceResult& result)"
"template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nScalar ShapeShapeDistance(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver, const DistanceRequest& request,\nDistanceResult& result)" -> "void distance(DistanceTraversalNodeBase* node,\nBVHFrontList* front_list, int qsize)"
"void distance(DistanceTraversalNodeBase* node,\nBVHFrontList* front_list, int qsize)" -> "void distanceRecurse(DistanceTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list)"
"void distanceRecurse(DistanceTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list)" -> "void ShapeDistanceTraversalNode::leafTesting(int, int) const\ntraversal/traversal_node_shapes.h"
"void ShapeDistanceTraversalNode::leafTesting(int, int) const\ntraversal/traversal_node_shapes.h" -> "template<typename S1, typename S2> bool GJKSolver_indep::shapeDistance\n(const S1& s1, const Transform3s& tf1, const S2& s2, const Transform3s& tf2,\nScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h"
}
================================================
FILE: dockgen.toml
================================================
[eigenpy]
url = "github:stack-of-tasks"
[coal]
url = "."
apt_deps = ["libassimp-dev", "liboctomap-dev"]
src_deps = ["eigenpy"]
================================================
FILE: flake.nix
================================================
{
description = "An extension of the Flexible Collision Library";
inputs = {
gepetto.url = "github:gepetto/nix";
# eigenpy v3.12.0 does not handle eigen v5, so we need devel for now
eigenpy.url = "github:stack-of-tasks/eigenpy";
eigenpy.inputs.gepetto.follows = "gepetto";
};
outputs =
inputs:
inputs.gepetto.lib.mkFlakoboros inputs (
{ lib, ... }:
{
overlays = [ inputs.eigenpy.overlays.flakoboros ];
extraDevPyPackages = [ "coal" ];
overrideAttrs.coal =
{ drv-prev, ... }:
{
cmakeFlags = drv-prev.cmakeFlags ++ [
"-DCOAL_DISABLE_HPP_FCL_WARNINGS=ON"
"-DGENERATE_PYTHON_STUBS=OFF"
];
src = lib.fileset.toSource {
root = ./.;
fileset = lib.fileset.unions [
./CMakeLists.txt
./doc
./hpp-fclConfig.cmake
./include
./package.xml
./python
./python-nb
./src
./test
];
};
};
extends = {
inherit (inputs.eigenpy.overlays) eigen5;
full = _final: prev: {
pythonPackagesExtensions = prev.pythonPackagesExtensions ++ [
(_python-final: python-prev: {
coal = python-prev.coal.override { buildStandalone = false; };
})
];
};
nanobind = _final: prev: {
pythonPackagesExtensions = prev.pythonPackagesExtensions ++ [
(python-final: python-prev: {
coal = python-prev.coal.overrideAttrs (super: {
pname = "coal-nb";
cmakeFlags = super.cmakeFlags ++ [
"-DCOAL_PYTHON_NANOBIND=ON"
];
postPatch = ''
substituteInPlace python-nb/CMakeLists.txt --replace-fail \
"$""{Python_SITELIB}" \
"${python-final.python.sitePackages}"
'';
propagatedBuildInputs = super.propagatedBuildInputs ++ [
python-final.nanobind
python-final.nanoeigenpy
];
pythonImportsCheck = [ "coal" ]; # hppfcl is broken with nanobind
});
})
];
};
};
}
);
}
================================================
FILE: hpp-fclConfig.cmake
================================================
# This file provide bacward compatiblity for `find_package(hpp-fcl)`.
if(NOT COAL_DISABLE_HPP_FCL_WARNINGS)
message(
WARNING
"Please update your CMake from 'hpp-fcl' to 'coal', or define COAL_DISABLE_HPP_FCL_WARNINGS"
)
endif()
find_package(coal REQUIRED)
if(NOT TARGET hpp-fcl::hpp-fcl)
add_library(hpp-fcl::hpp-fcl INTERFACE IMPORTED)
# Compute the installation prefix relative to this file.
# This code is taken from generated cmake xxxTargets.cmake.
get_filename_component(_IMPORT_PREFIX "${CMAKE_CURRENT_LIST_FILE}" PATH)
get_filename_component(_IMPORT_PREFIX "${_IMPORT_PREFIX}" PATH)
get_filename_component(_IMPORT_PREFIX "${_IMPORT_PREFIX}" PATH)
get_filename_component(_IMPORT_PREFIX "${_IMPORT_PREFIX}" PATH)
if(_IMPORT_PREFIX STREQUAL "/")
set(_IMPORT_PREFIX "")
endif()
set_target_properties(
hpp-fcl::hpp-fcl
PROPERTIES
INTERFACE_COMPILE_DEFINITIONS "COAL_BACKWARD_COMPATIBILITY_WITH_HPP_FCL"
INTERFACE_INCLUDE_DIRECTORIES "${_IMPORT_PREFIX}/include"
INTERFACE_LINK_LIBRARIES "coal::coal"
)
endif()
================================================
FILE: include/coal/BV/AABB.h
================================================
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2011-2014, Willow Garage, Inc.
* Copyright (c) 2014-2015, Open Source Robotics Foundation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Open Source Robotics Foundation nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO
gitextract_n08c_ker/
├── .clang-format
├── .gersemirc
├── .git-blame-ignore-revs
├── .gitattributes
├── .github/
│ ├── dependabot.yml
│ └── workflows/
│ ├── check-changelog.yml
│ ├── dockgen.yml
│ ├── macos-linux-pip.yml
│ ├── macos-linux-windows-pixi.yml
│ ├── nix.yml
│ ├── ros_ci.yml
│ ├── update-flake-lock.yml
│ └── update_pixi_lockfile.yml
├── .gitignore
├── .gitlab-ci.yml
├── .gitmodules
├── .pre-commit-config.yaml
├── CHANGELOG.md
├── CITATION.bib
├── CITATION.cff
├── CMakeLists.txt
├── LICENSE
├── README.md
├── colcon.pkg
├── development/
│ ├── build.md
│ ├── release.md
│ └── scripts/
│ └── pixi/
│ ├── activation.bat
│ └── activation.sh
├── doc/
│ ├── CMakeLists.txt
│ ├── Doxyfile.extra.in
│ ├── generate_distance_plot.py
│ ├── gjk.py
│ ├── mesh-mesh-collision-call.dot
│ ├── notes
│ ├── python/
│ │ ├── doxygen-boost.hh
│ │ ├── doxygen.hh
│ │ ├── doxygen_xml_parser.py
│ │ └── xml_docstring.py
│ ├── shape-mesh-collision-call.dot
│ └── shape-shape-collision-call.dot
├── dockgen.toml
├── flake.nix
├── hpp-fclConfig.cmake
├── include/
│ ├── coal/
│ │ ├── BV/
│ │ │ ├── AABB.h
│ │ │ ├── BV.h
│ │ │ ├── BV_node.h
│ │ │ ├── OBB.h
│ │ │ ├── OBBRSS.h
│ │ │ ├── RSS.h
│ │ │ ├── kDOP.h
│ │ │ └── kIOS.h
│ │ ├── BVH/
│ │ │ ├── BVH_front.h
│ │ │ ├── BVH_internal.h
│ │ │ ├── BVH_model.h
│ │ │ └── BVH_utility.h
│ │ ├── alloca.h
│ │ ├── broadphase/
│ │ │ ├── broadphase.h
│ │ │ ├── broadphase_SSaP.h
│ │ │ ├── broadphase_SaP.h
│ │ │ ├── broadphase_bruteforce.h
│ │ │ ├── broadphase_callbacks.h
│ │ │ ├── broadphase_collision_manager.h
│ │ │ ├── broadphase_continuous_collision_manager-inl.h
│ │ │ ├── broadphase_continuous_collision_manager.h
│ │ │ ├── broadphase_dynamic_AABB_tree-inl.h
│ │ │ ├── broadphase_dynamic_AABB_tree.h
│ │ │ ├── broadphase_dynamic_AABB_tree_array-inl.h
│ │ │ ├── broadphase_dynamic_AABB_tree_array.h
│ │ │ ├── broadphase_interval_tree.h
│ │ │ ├── broadphase_spatialhash-inl.h
│ │ │ ├── broadphase_spatialhash.h
│ │ │ ├── default_broadphase_callbacks.h
│ │ │ └── detail/
│ │ │ ├── hierarchy_tree-inl.h
│ │ │ ├── hierarchy_tree.h
│ │ │ ├── hierarchy_tree_array-inl.h
│ │ │ ├── hierarchy_tree_array.h
│ │ │ ├── interval_tree.h
│ │ │ ├── interval_tree_node-inl.h
│ │ │ ├── interval_tree_node.h
│ │ │ ├── morton-inl.h
│ │ │ ├── morton.h
│ │ │ ├── node_base-inl.h
│ │ │ ├── node_base.h
│ │ │ ├── node_base_array-inl.h
│ │ │ ├── node_base_array.h
│ │ │ ├── simple_hash_table-inl.h
│ │ │ ├── simple_hash_table.h
│ │ │ ├── simple_interval-inl.h
│ │ │ ├── simple_interval.h
│ │ │ ├── sparse_hash_table-inl.h
│ │ │ ├── sparse_hash_table.h
│ │ │ ├── spatial_hash-inl.h
│ │ │ └── spatial_hash.h
│ │ ├── collision.h
│ │ ├── collision_data.h
│ │ ├── collision_func_matrix.h
│ │ ├── collision_object.h
│ │ ├── collision_utility.h
│ │ ├── contact_patch/
│ │ │ ├── contact_patch_simplifier.h
│ │ │ ├── contact_patch_solver.h
│ │ │ ├── contact_patch_solver.hxx
│ │ │ └── polygon_convex_hull.h
│ │ ├── contact_patch.h
│ │ ├── contact_patch_func_matrix.h
│ │ ├── data_types.h
│ │ ├── distance.h
│ │ ├── distance_func_matrix.h
│ │ ├── doc.hh
│ │ ├── fwd.hh
│ │ ├── hfield.h
│ │ ├── internal/
│ │ │ ├── BV_fitter.h
│ │ │ ├── BV_splitter.h
│ │ │ ├── intersect.h
│ │ │ ├── intersect.hxx
│ │ │ ├── shape_shape_contact_patch_func.h
│ │ │ ├── shape_shape_func.h
│ │ │ ├── tools.h
│ │ │ ├── traversal.h
│ │ │ ├── traversal_node_base.h
│ │ │ ├── traversal_node_bvh_hfield.h
│ │ │ ├── traversal_node_bvh_shape.h
│ │ │ ├── traversal_node_bvhs.h
│ │ │ ├── traversal_node_hfield_shape.h
│ │ │ ├── traversal_node_octree.h
│ │ │ ├── traversal_node_setup.h
│ │ │ ├── traversal_node_shapes.h
│ │ │ └── traversal_recurse.h
│ │ ├── logging.h
│ │ ├── math/
│ │ │ ├── matrix_3f.h
│ │ │ ├── transform.h
│ │ │ ├── types.h
│ │ │ └── vec_3f.h
│ │ ├── mesh_loader/
│ │ │ ├── assimp.h
│ │ │ └── loader.h
│ │ ├── narrowphase/
│ │ │ ├── gjk.h
│ │ │ ├── minkowski_difference.h
│ │ │ ├── narrowphase.h
│ │ │ ├── narrowphase_defaults.h
│ │ │ ├── support_data.h
│ │ │ └── support_functions.h
│ │ ├── octree.h
│ │ ├── serialization/
│ │ │ ├── AABB.h
│ │ │ ├── BVH_model.h
│ │ │ ├── BV_node.h
│ │ │ ├── BV_splitter.h
│ │ │ ├── OBB.h
│ │ │ ├── OBBRSS.h
│ │ │ ├── RSS.h
│ │ │ ├── archive.h
│ │ │ ├── collision_data.h
│ │ │ ├── collision_object.h
│ │ │ ├── contact_patch.h
│ │ │ ├── convex.h
│ │ │ ├── eigen.h
│ │ │ ├── fwd.h
│ │ │ ├── geometric_shapes.h
│ │ │ ├── hfield.h
│ │ │ ├── kDOP.h
│ │ │ ├── kIOS.h
│ │ │ ├── memory.h
│ │ │ ├── octree.h
│ │ │ ├── quadrilateral.h
│ │ │ ├── serializer.h
│ │ │ ├── transform.h
│ │ │ └── triangle.h
│ │ ├── shape/
│ │ │ ├── convex.h
│ │ │ ├── convex.hxx
│ │ │ ├── geometric_shape_to_BVH_model.h
│ │ │ ├── geometric_shapes.h
│ │ │ ├── geometric_shapes.hxx
│ │ │ ├── geometric_shapes_traits.h
│ │ │ └── geometric_shapes_utility.h
│ │ ├── shared_ptr_comparison.h
│ │ ├── third_party/
│ │ │ └── boost/
│ │ │ └── core/
│ │ │ ├── data.hpp
│ │ │ ├── detail/
│ │ │ │ └── assert.hpp
│ │ │ ├── make_span.hpp
│ │ │ └── span.hpp
│ │ └── timings.h
│ └── hpp/
│ └── fcl/
│ ├── BV/
│ │ ├── AABB.h
│ │ ├── BV.h
│ │ ├── BV_node.h
│ │ ├── OBB.h
│ │ ├── OBBRSS.h
│ │ ├── RSS.h
│ │ ├── kDOP.h
│ │ └── kIOS.h
│ ├── BVH/
│ │ ├── BVH_front.h
│ │ ├── BVH_internal.h
│ │ ├── BVH_model.h
│ │ └── BVH_utility.h
│ ├── broadphase/
│ │ ├── broadphase.h
│ │ ├── broadphase_SSaP.h
│ │ ├── broadphase_SaP.h
│ │ ├── broadphase_bruteforce.h
│ │ ├── broadphase_callbacks.h
│ │ ├── broadphase_collision_manager.h
│ │ ├── broadphase_continuous_collision_manager-inl.h
│ │ ├── broadphase_continuous_collision_manager.h
│ │ ├── broadphase_dynamic_AABB_tree-inl.h
│ │ ├── broadphase_dynamic_AABB_tree.h
│ │ ├── broadphase_dynamic_AABB_tree_array-inl.h
│ │ ├── broadphase_dynamic_AABB_tree_array.h
│ │ ├── broadphase_interval_tree.h
│ │ ├── broadphase_spatialhash-inl.h
│ │ ├── broadphase_spatialhash.h
│ │ ├── default_broadphase_callbacks.h
│ │ └── detail/
│ │ ├── hierarchy_tree-inl.h
│ │ ├── hierarchy_tree.h
│ │ ├── hierarchy_tree_array-inl.h
│ │ ├── hierarchy_tree_array.h
│ │ ├── interval_tree.h
│ │ ├── interval_tree_node.h
│ │ ├── morton-inl.h
│ │ ├── morton.h
│ │ ├── node_base-inl.h
│ │ ├── node_base.h
│ │ ├── node_base_array-inl.h
│ │ ├── node_base_array.h
│ │ ├── simple_hash_table-inl.h
│ │ ├── simple_hash_table.h
│ │ ├── simple_interval-inl.h
│ │ ├── simple_interval.h
│ │ ├── sparse_hash_table-inl.h
│ │ ├── sparse_hash_table.h
│ │ ├── spatial_hash-inl.h
│ │ └── spatial_hash.h
│ ├── coal.hpp
│ ├── collision.h
│ ├── collision_data.h
│ ├── collision_func_matrix.h
│ ├── collision_object.h
│ ├── collision_utility.h
│ ├── config.hh
│ ├── contact_patch/
│ │ ├── contact_patch_solver.h
│ │ └── contact_patch_solver.hxx
│ ├── contact_patch.h
│ ├── contact_patch_func_matrix.h
│ ├── data_types.h
│ ├── deprecated.hh
│ ├── distance.h
│ ├── distance_func_matrix.h
│ ├── fwd.hh
│ ├── hfield.h
│ ├── internal/
│ │ ├── BV_fitter.h
│ │ ├── BV_splitter.h
│ │ ├── intersect.h
│ │ ├── shape_shape_contact_patch_func.h
│ │ ├── shape_shape_func.h
│ │ ├── tools.h
│ │ ├── traversal.h
│ │ ├── traversal_node_base.h
│ │ ├── traversal_node_bvh_shape.h
│ │ ├── traversal_node_bvhs.h
│ │ ├── traversal_node_hfield_shape.h
│ │ ├── traversal_node_octree.h
│ │ ├── traversal_node_setup.h
│ │ ├── traversal_node_shapes.h
│ │ └── traversal_recurse.h
│ ├── logging.h
│ ├── math/
│ │ ├── matrix_3f.h
│ │ ├── transform.h
│ │ ├── types.h
│ │ └── vec_3f.h
│ ├── mesh_loader/
│ │ ├── assimp.h
│ │ └── loader.h
│ ├── narrowphase/
│ │ ├── gjk.h
│ │ ├── minkowski_difference.h
│ │ ├── narrowphase.h
│ │ ├── narrowphase_defaults.h
│ │ ├── support_data.h
│ │ ├── support_functions.h
│ │ └── support_functions.hxx
│ ├── octree.h
│ ├── serialization/
│ │ ├── AABB.h
│ │ ├── BVH_model.h
│ │ ├── BV_node.h
│ │ ├── BV_splitter.h
│ │ ├── OBB.h
│ │ ├── OBBRSS.h
│ │ ├── RSS.h
│ │ ├── archive.h
│ │ ├── collision_data.h
│ │ ├── collision_object.h
│ │ ├── contact_patch.h
│ │ ├── convex.h
│ │ ├── eigen.h
│ │ ├── fwd.h
│ │ ├── geometric_shapes.h
│ │ ├── hfield.h
│ │ ├── kDOP.h
│ │ ├── kIOS.h
│ │ ├── memory.h
│ │ ├── octree.h
│ │ ├── quadrilateral.h
│ │ ├── serializer.h
│ │ ├── transform.h
│ │ └── triangle.h
│ ├── shape/
│ │ ├── convex.h
│ │ ├── convex.hxx
│ │ ├── geometric_shape_to_BVH_model.h
│ │ ├── geometric_shapes.h
│ │ ├── geometric_shapes.hxx
│ │ ├── geometric_shapes_traits.h
│ │ └── geometric_shapes_utility.h
│ ├── timings.h
│ └── warning.hh
├── package.xml
├── pixi.toml
├── python/
│ ├── CMakeLists.txt
│ ├── broadphase/
│ │ ├── broadphase.cc
│ │ ├── broadphase_callbacks.hh
│ │ ├── broadphase_collision_manager.hh
│ │ └── fwd.hh
│ ├── coal/
│ │ ├── __init__.py
│ │ ├── viewer.py
│ │ └── windows_dll_manager.py
│ ├── coal.cc
│ ├── coal.hh
│ ├── collision-geometries.cc
│ ├── collision.cc
│ ├── contact_patch.cc
│ ├── deprecation.hh
│ ├── distance.cc
│ ├── fwd.hh
│ ├── gjk.cc
│ ├── hppfcl/
│ │ ├── __init__.py
│ │ └── viewer.py
│ ├── math.cc
│ ├── octree.cc
│ ├── pickle.hh
│ ├── printable.hh
│ ├── serializable.hh
│ ├── utils/
│ │ └── std-pair.hh
│ └── version.cc
├── python-nb/
│ ├── CMakeLists.txt
│ ├── aabb.cc
│ ├── broadphase/
│ │ ├── broadphase.cc
│ │ └── broadphase_callbacks_collision_manager.hh
│ ├── bvh.cc
│ ├── coal/
│ │ ├── __init__.py
│ │ └── windows_dll_manager.py
│ ├── collision-geometries.cc
│ ├── collision.cc
│ ├── contact_patch.cc
│ ├── distance.cc
│ ├── fwd.h
│ ├── gjk.cc
│ ├── height_field.cc
│ ├── math.cc
│ ├── memory-footprint.cc
│ ├── module.cc
│ ├── octree.cc
│ ├── pickle.hh
│ ├── serializable.hh
│ └── shapes.cc
├── src/
│ ├── BV/
│ │ ├── AABB.cpp
│ │ ├── OBB.cpp
│ │ ├── OBB.h
│ │ ├── OBBRSS.cpp
│ │ ├── RSS.cpp
│ │ ├── kDOP.cpp
│ │ └── kIOS.cpp
│ ├── BVH/
│ │ ├── BVH_model.cpp
│ │ ├── BVH_utility.cpp
│ │ ├── BV_fitter.cpp
│ │ └── BV_splitter.cpp
│ ├── CMakeLists.txt
│ ├── broadphase/
│ │ ├── broadphase_SSaP.cpp
│ │ ├── broadphase_SaP.cpp
│ │ ├── broadphase_bruteforce.cpp
│ │ ├── broadphase_collision_manager.cpp
│ │ ├── broadphase_dynamic_AABB_tree.cpp
│ │ ├── broadphase_dynamic_AABB_tree_array.cpp
│ │ ├── broadphase_interval_tree.cpp
│ │ ├── default_broadphase_callbacks.cpp
│ │ └── detail/
│ │ ├── interval_tree.cpp
│ │ ├── interval_tree_node.cpp
│ │ ├── morton-inl.h
│ │ ├── morton.cpp
│ │ ├── simple_interval.cpp
│ │ └── spatial_hash.cpp
│ ├── collision.cpp
│ ├── collision_data.cpp
│ ├── collision_func_matrix.cpp
│ ├── collision_node.cpp
│ ├── collision_node.h
│ ├── collision_object.cpp
│ ├── collision_utility.cpp
│ ├── contact_patch/
│ │ ├── contact_patch_simplifier.cpp
│ │ ├── contact_patch_solver.cpp
│ │ └── polygon_convex_hull.cpp
│ ├── contact_patch.cpp
│ ├── contact_patch_func_matrix.cpp
│ ├── distance/
│ │ ├── box_halfspace.cpp
│ │ ├── box_plane.cpp
│ │ ├── box_sphere.cpp
│ │ ├── capsule_capsule.cpp
│ │ ├── capsule_halfspace.cpp
│ │ ├── capsule_plane.cpp
│ │ ├── cone_halfspace.cpp
│ │ ├── cone_plane.cpp
│ │ ├── convex_halfspace.cpp
│ │ ├── convex_plane.cpp
│ │ ├── cylinder_halfspace.cpp
│ │ ├── cylinder_plane.cpp
│ │ ├── ellipsoid_halfspace.cpp
│ │ ├── ellipsoid_plane.cpp
│ │ ├── halfspace_halfspace.cpp
│ │ ├── halfspace_plane.cpp
│ │ ├── plane_plane.cpp
│ │ ├── sphere_capsule.cpp
│ │ ├── sphere_cylinder.cpp
│ │ ├── sphere_halfspace.cpp
│ │ ├── sphere_plane.cpp
│ │ ├── sphere_sphere.cpp
│ │ ├── triangle_halfspace.cpp
│ │ ├── triangle_plane.cpp
│ │ ├── triangle_sphere.cpp
│ │ └── triangle_triangle.cpp
│ ├── distance.cpp
│ ├── distance_func_matrix.cpp
│ ├── hfield.cpp
│ ├── intersect.cpp
│ ├── math/
│ │ └── transform.cpp
│ ├── mesh_loader/
│ │ ├── assimp.cpp
│ │ └── loader.cpp
│ ├── narrowphase/
│ │ ├── details.h
│ │ ├── gjk.cpp
│ │ ├── minkowski_difference.cpp
│ │ └── support_functions.cpp
│ ├── octree.cpp
│ ├── serialization/
│ │ └── serialization.cpp
│ ├── shape/
│ │ ├── geometric_shapes.cpp
│ │ └── geometric_shapes_utility.cpp
│ ├── traits_traversal.h
│ └── traversal/
│ └── traversal_recurse.cpp
└── test/
├── CMakeLists.txt
├── accelerated_gjk.cpp
├── alloca.cpp
├── benchmark/
│ └── test_fcl_gjk.output
├── benchmark.cpp
├── box_box_collision.cpp
├── box_box_distance.cpp
├── broadphase.cpp
├── broadphase_collision_1.cpp
├── broadphase_collision_2.cpp
├── broadphase_dynamic_AABB_tree.cpp
├── bvh_models.cpp
├── capsule_box_1.cpp
├── capsule_box_2.cpp
├── capsule_capsule.cpp
├── collision.cpp
├── collision_node_asserts.cpp
├── contact_patch.cpp
├── convex.cpp
├── distance.cpp
├── distance_lower_bound.cpp
├── fcl_resources/
│ ├── config.h.in
│ ├── env.obj
│ ├── env.octree
│ ├── illformated_mesh.dae
│ ├── rob.obj
│ └── staircases_koroibot_hr.dae
├── frontlist.cpp
├── geometric_shapes.cpp
├── gjk-geometric-tools-benchmark
├── gjk.cpp
├── gjk_asserts.cpp
├── gjk_convergence_criterion.cpp
├── hfields.cpp
├── math.cpp
├── normal_and_nearest_points.cpp
├── obb.cpp
├── octree.cpp
├── patch_simplifier.cpp
├── pixi_build/
│ └── CMakeLists.txt
├── polygon_convex_hull.cpp
├── profiling.cpp
├── python_unit/
│ ├── CMakeLists.txt
│ ├── api.py
│ ├── collision.py
│ ├── collision_manager.py
│ ├── geometric_shapes.py
│ ├── pickling.py
│ └── test_case.py
├── scripts/
│ ├── collision-bench.py
│ ├── collision.py
│ ├── distance_lower_bound.py
│ ├── geometric_shapes.py
│ ├── gjk.py
│ ├── obb.py
│ └── octree.py
├── security_margin.cpp
├── serialization.cpp
├── shape_inflation.cpp
├── shape_mesh_consistency.cpp
├── simple.cpp
├── swept_sphere_radius.cpp
├── utility.cpp
└── utility.h
SYMBOL INDEX (1677 symbols across 296 files)
FILE: doc/generate_distance_plot.py
function dlb (line 15) | def dlb(d):
FILE: doc/gjk.py
function set_test_values (line 248) | def set_test_values(current_tests, test_values, itest, value):
function set_tests_values (line 279) | def set_tests_values(current_tests, test_values, itests, values):
function apply_test_values (line 287) | def apply_test_values(cases, test_values):
function max_number_of_tests (line 330) | def max_number_of_tests(
function printComments (line 426) | def printComments(order, indent, file):
function printOrder (line 432) | def printOrder(order, indent="", start=True, file=sys.stdout, curTests=[]):
function unit_tests (line 628) | def unit_tests():
FILE: doc/python/doxygen-boost.hh
type doxygen (line 10) | namespace doxygen {
type visitor (line 12) | namespace visitor {
type member_func_impl (line 16) | struct member_func_impl : boost::python::def_visitor<
method member_func_impl (line 18) | member_func_impl(const char* n, const function_type& f)
method member_func_impl (line 21) | member_func_impl(const char* n, const function_type& f, policy_typ...
method visit (line 25) | inline void visit(classT& c) const {
method call (line 31) | inline void call(
method call (line 37) | inline void call(classT& c, const void_&) const {
function member_func (line 49) | inline member_func_impl<function_type> member_func(
function member_func (line 55) | inline member_func_impl<function_type, policy_type> member_func(
FILE: doc/python/doxygen.hh
type doxygen (line 13) | namespace doxygen {
type class_doc_impl (line 17) | struct class_doc_impl {
function void_ (line 38) | inline void_ member_func_args(FuncPtr) {
FILE: doc/python/doxygen_xml_parser.py
function _templateParamToDict (line 90) | def _templateParamToDict(param):
function makeHeaderGuard (line 126) | def makeHeaderGuard(filename):
function format_description (line 130) | def format_description(brief, detailed):
class Reference (line 143) | class Reference(object):
method __init__ (line 144) | def __init__(self, index, id=None, name=None):
method xmlToType (line 149) | def xmlToType(self, node, array=None, parentClass=None, tplargs=None):
class MemberDef (line 201) | class MemberDef(Reference):
method __init__ (line 202) | def __init__(self, index, memberdefxml, parent):
method _templateParams (line 227) | def _templateParams(self, tpl):
method prototypekey (line 235) | def prototypekey(self):
method s_prototypeArgs (line 249) | def s_prototypeArgs(self):
method s_args (line 252) | def s_args(self):
method s_tpldecl (line 279) | def s_tpldecl(self):
method s_rettype (line 284) | def s_rettype(self):
method s_name (line 305) | def s_name(self):
method s_docstring (line 308) | def s_docstring(self):
method n_args (line 315) | def n_args(self):
method s_argnamesstring (line 318) | def s_argnamesstring(self):
method include (line 330) | def include(self):
class CompoundBase (line 336) | class CompoundBase(Reference):
method __init__ (line 337) | def __init__(self, compound, index):
class NamespaceCompound (line 349) | class NamespaceCompound(CompoundBase):
method __init__ (line 350) | def __init__(self, *args):
method parseEnumSection (line 368) | def parseEnumSection(self, section):
method parseTypedefSection (line 384) | def parseTypedefSection(self, section):
method parseFuncSection (line 394) | def parseFuncSection(self, section):
method innerNamespace (line 398) | def innerNamespace(self):
method write (line 401) | def write(self, output):
class ClassCompound (line 405) | class ClassCompound(CompoundBase):
method __init__ (line 406) | def __init__(self, *args):
method _templateParams (line 455) | def _templateParams(self, tpl):
method _templateDecl (line 463) | def _templateDecl(self):
method _className (line 468) | def _className(self):
method hasTypeDef (line 478) | def hasTypeDef(self, typename):
method innerNamespace (line 481) | def innerNamespace(self):
method _memberfunc (line 484) | def _memberfunc(self, member):
method _writeClassDoc (line 493) | def _writeClassDoc(self, output):
method write (line 523) | def write(self, output):
method _attribute (line 679) | def _attribute(self, member):
class Index (line 683) | class Index:
method __init__ (line 688) | def __init__(self, input, output):
method parseCompound (line 696) | def parseCompound(self):
method write (line 706) | def write(self):
method registerReference (line 790) | def registerReference(self, obj, overwrite=True):
method hasref (line 804) | def hasref(self, id):
method getref (line 807) | def getref(self, id):
class OutputStreams (line 811) | class OutputStreams(object):
method __init__ (line 812) | def __init__(self, output_dir, warn, error, errorPrefix=""):
method open (line 821) | def open(self, name):
method close (line 850) | def close(self):
method writeFooterAndCloseFiles (line 853) | def writeFooterAndCloseFiles(self):
method out (line 866) | def out(self, *args):
method warn (line 872) | def warn(self, *args):
method err (line 875) | def err(self, *args):
FILE: doc/python/xml_docstring.py
class XmlDocString (line 1) | class XmlDocString(object):
method __init__ (line 2) | def __init__(self, index):
method clear (line 28) | def clear(self):
method writeErrors (line 33) | def writeErrors(self, output):
method _write (line 43) | def _write(self, str):
method _newline (line 52) | def _newline(self, n=1):
method _clean (line 60) | def _clean(self):
method getDocString (line 75) | def getDocString(self, brief, detailled, output):
method visit (line 92) | def visit(self, node):
method unknownTag (line 100) | def unknownTag(self, node):
method otherTags (line 104) | def otherTags(self, node):
method emphasis (line 112) | def emphasis(self, node):
method simplesect (line 117) | def simplesect(self, node):
method para (line 121) | def para(self, node):
method ref (line 130) | def ref(self, node):
method parameterlist (line 139) | def parameterlist(self, node):
method parameteritem (line 146) | def parameteritem(self, node):
method itemizedlist (line 160) | def itemizedlist(self, node):
method listitem (line 164) | def listitem(self, node):
method formula (line 168) | def formula(self, node):
FILE: include/coal/BV/AABB.h
type CollisionRequest (line 46) | struct CollisionRequest
function class (line 56) | class COAL_DLLAPI AABB {
FILE: include/coal/BV/BV.h
function namespace (line 50) | namespace coal {
FILE: include/coal/BV/BV_node.h
function namespace (line 44) | namespace coal {
FILE: include/coal/BV/OBB.h
function namespace (line 44) | namespace coal {
FILE: include/coal/BV/OBBRSS.h
function namespace (line 45) | namespace coal {
function overlap (line 137) | inline bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBBRSS& b1,
function overlap (line 148) | inline bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBBRSS& b1,
FILE: include/coal/BV/RSS.h
function namespace (line 46) | namespace coal {
FILE: include/coal/BV/kDOP.h
function namespace (line 44) | namespace coal {
FILE: include/coal/BV/kIOS.h
function namespace (line 44) | namespace coal {
FILE: include/coal/BVH/BVH_front.h
function BVHFrontNode (line 52) | struct COAL_DLLAPI BVHFrontNode {
FILE: include/coal/BVH/BVH_internal.h
function namespace (line 43) | namespace coal {
FILE: include/coal/BVH/BVH_model.h
function namespace (line 52) | namespace coal {
FILE: include/coal/BVH/BVH_utility.h
function namespace (line 43) | namespace coal {
FILE: include/coal/broadphase/broadphase_SSaP.h
function namespace (line 44) | namespace coal {
FILE: include/coal/broadphase/broadphase_SaP.h
function namespace (line 46) | namespace coal {
FILE: include/coal/broadphase/broadphase_bruteforce.h
function namespace (line 44) | namespace coal {
FILE: include/coal/broadphase/broadphase_callbacks.h
function namespace (line 43) | namespace coal {
FILE: include/coal/broadphase/broadphase_collision_manager.h
function namespace (line 48) | namespace coal {
FILE: include/coal/broadphase/broadphase_continuous_collision_manager-inl.h
function namespace (line 44) | namespace coal {
FILE: include/coal/broadphase/broadphase_dynamic_AABB_tree-inl.h
function namespace (line 52) | namespace coal {
FILE: include/coal/broadphase/broadphase_dynamic_AABB_tree.h
function empty (line 126) | bool empty() const;
FILE: include/coal/broadphase/broadphase_dynamic_AABB_tree_array-inl.h
function namespace (line 48) | namespace coal {
FILE: include/coal/broadphase/broadphase_interval_tree.h
function namespace (line 47) | namespace coal {
FILE: include/coal/broadphase/broadphase_spatialhash-inl.h
function namespace (line 43) | namespace coal {
FILE: include/coal/broadphase/broadphase_spatialhash.h
function namespace (line 49) | namespace coal {
FILE: include/coal/broadphase/default_broadphase_callbacks.h
function namespace (line 51) | namespace coal {
function clear (line 68) | void clear() {
type DistanceData (line 76) | struct DistanceData {
function clear (line 89) | void clear() {
function CollisionCallBackDefault (line 196) | struct COAL_DLLAPI CollisionCallBackDefault : CollisionCallBackBase {
function DistanceCallBackDefault (line 210) | struct COAL_DLLAPI DistanceCallBackDefault : DistanceCallBackBase {
function CollisionCallBackCollect (line 223) | struct COAL_DLLAPI CollisionCallBackCollect : CollisionCallBackBase {
FILE: include/coal/broadphase/detail/hierarchy_tree-inl.h
function namespace (line 43) | namespace coal {
function run (line 160) | static bool run(const HierarchyTree<BV>& tree,
function run (line 168) | static bool run(const HierarchyTree<BV>& tree,
function run (line 938) | static std::size_t run(const NodeBase<BV>& /*query*/,
function run (line 944) | static std::size_t run(const BV& /*query*/, const NodeBase<BV>& /*node1*/,
function run (line 981) | static std::size_t run(const AABB& query, const NodeBase<AABB>& node1,
FILE: include/coal/broadphase/detail/hierarchy_tree.h
function namespace (line 52) | namespace detail {
FILE: include/coal/broadphase/detail/hierarchy_tree_array-inl.h
function namespace (line 46) | namespace coal {
function SortByMorton (line 618) | const SortByMorton comp{nodes, split};
function SortByMorton (line 655) | const SortByMorton comp{nodes, split};
function run (line 910) | static bool run(size_t query, size_t node1, size_t node2,
function run (line 920) | static bool run(const BV& query, size_t node1, size_t node2,
function run (line 947) | static bool run(size_t query, size_t node1, size_t node2,
function run (line 960) | static bool run(const AABB& query, size_t node1, size_t node2,
FILE: include/coal/broadphase/detail/hierarchy_tree_array.h
function namespace (line 52) | namespace detail {
FILE: include/coal/broadphase/detail/interval_tree.h
function namespace (line 47) | namespace coal {
FILE: include/coal/broadphase/detail/interval_tree_node-inl.h
function namespace (line 46) | namespace coal {
FILE: include/coal/broadphase/detail/interval_tree_node.h
function namespace (line 44) | namespace coal {
FILE: include/coal/broadphase/detail/morton-inl.h
function namespace (line 44) | namespace coal { /// @cond IGNORE
FILE: include/coal/broadphase/detail/morton.h
function namespace (line 46) | namespace coal {
FILE: include/coal/broadphase/detail/node_base-inl.h
function namespace (line 43) | namespace coal {
FILE: include/coal/broadphase/detail/node_base.h
function namespace (line 43) | namespace coal {
FILE: include/coal/broadphase/detail/node_base_array-inl.h
function namespace (line 43) | namespace coal {
FILE: include/coal/broadphase/detail/node_base_array.h
function namespace (line 43) | namespace coal {
FILE: include/coal/broadphase/detail/simple_hash_table-inl.h
function namespace (line 44) | namespace coal {
FILE: include/coal/broadphase/detail/simple_hash_table.h
function namespace (line 45) | namespace coal {
FILE: include/coal/broadphase/detail/simple_interval-inl.h
function namespace (line 44) | namespace coal {
FILE: include/coal/broadphase/detail/simple_interval.h
function namespace (line 44) | namespace coal {
FILE: include/coal/broadphase/detail/sparse_hash_table-inl.h
function namespace (line 43) | namespace coal {
FILE: include/coal/broadphase/detail/sparse_hash_table.h
function namespace (line 46) | namespace coal {
FILE: include/coal/broadphase/detail/spatial_hash-inl.h
function namespace (line 44) | namespace coal {
FILE: include/coal/broadphase/detail/spatial_hash.h
function namespace (line 44) | namespace coal {
FILE: include/coal/collision.h
function namespace (line 48) | namespace coal {
FILE: include/coal/collision_data.h
function namespace (line 56) | namespace coal {
function operator (line 179) | bool operator==(const Contact& other) const {
function operator (line 202) | bool operator!=(const Contact& other) const { return !(*this == other); }
function resolveReferences (line 212) | void resolveReferences(
type QueryResult (line 247) | struct QueryResult
function QueryRequest (line 250) | struct COAL_DLLAPI QueryRequest {
function QueryResult (line 396) | struct COAL_DLLAPI QueryResult {
function Scalar (line 558) | inline Scalar Contact::getDistanceToCollision(
function CollisionResult (line 564) | struct COAL_DLLAPI CollisionResult : QueryResult {
function resolveReferences (line 622) | void resolveReferences(
function updateDistanceLowerBound (line 636) | inline void updateDistanceLowerBound(const Scalar& distance_lower_bound_) {
function addContact (line 642) | inline void addContact(const Contact& c) { contacts.push_back(c); }
function other (line 645) | inline bool operator==(const CollisionResult& other) const {
function Contact (line 671) | const Contact& getContact(size_t i) const {
function setContact (line 684) | void setContact(size_t i, const Contact& c) {
function getContacts (line 697) | void getContacts(std::vector<Contact>& contacts_) const {
function clear (line 705) | void clear() {
function ContactPatch (line 763) | struct COAL_DLLAPI ContactPatch {
function Scalar (line 832) | Scalar computeArea() const {
function addPoint (line 854) | void addPoint(const Vec3s& point_3d) {
function Vec3s (line 860) | Vec3s getPoint(const size_t i) const {
function Vec3s (line 870) | Vec3s getPointShape1(const size_t i) const {
function Vec3s (line 879) | Vec3s getPointShape2(const size_t i) const {
function Vec2s (line 901) | const Vec2s& point(const size_t i) const {
function clear (line 910) | void clear() {
function constructContactPatchFrameFromContact (line 1008) | inline void constructContactPatchFrameFromContact(const Contact& contact,
function ContactPatchRequest (line 1028) | struct COAL_DLLAPI ContactPatchRequest {
function setNumSamplesCurvedShapes (line 1085) | void setNumSamplesCurvedShapes(const size_t num_samples_curved_shapes) {
function setPatchTolerance (line 1102) | void setPatchTolerance(const Scalar patch_tolerance) {
function ContactPatchResult (line 1154) | struct COAL_DLLAPI ContactPatchResult {
function ContactPatch (line 1258) | const ContactPatch& getContactPatch(const size_t i) const {
function clear (line 1286) | void clear() {
function set (line 1295) | void set(const ContactPatchRequest& request) {
function DistanceResult (line 1486) | struct COAL_DLLAPI DistanceResult : QueryResult {
function CollisionGeometry (line 1544) | const CollisionGeometry*> new_o1_o2)
function resolveReferences (line 1553) | void resolveReferences(
function update (line 1560) | void update(Scalar distance, const CollisionGeometry* o1_,
function update (line 1572) | void update(Scalar distance, const CollisionGeometry* o1_,
function update (line 1588) | void update(const DistanceResult& other_result) {
function clear (line 1602) | void clear() {
function other (line 1617) | inline bool operator==(const DistanceResult& other) const {
function other (line 1640) | inline bool operator!=(const DistanceResult& other) const {
function namespace (line 1674) | namespace internal {
FILE: include/coal/collision_func_matrix.h
function namespace (line 45) | namespace coal {
FILE: include/coal/collision_object.h
function namespace (line 50) | namespace coal {
FILE: include/coal/collision_utility.h
function namespace (line 23) | namespace coal {
FILE: include/coal/contact_patch.h
function namespace (line 46) | namespace coal {
FILE: include/coal/contact_patch/contact_patch_simplifier.h
function namespace (line 45) | namespace coal {
FILE: include/coal/contact_patch/contact_patch_solver.h
function namespace (line 43) | namespace coal {
FILE: include/coal/contact_patch/contact_patch_solver.hxx
type coal (line 47) | namespace coal {
function Vec2s (line 435) | inline Vec2s ContactPatchSolver::computeLineSegmentIntersection(
FILE: include/coal/contact_patch/polygon_convex_hull.h
function namespace (line 13) | namespace coal {
FILE: include/coal/contact_patch_func_matrix.h
function namespace (line 44) | namespace coal {
FILE: include/coal/data_types.h
function namespace (line 63) | namespace coal {
function set (line 171) | inline void set(IndexType p1, IndexType p2, IndexType p3) {
function IndexType (line 178) | inline IndexType operator[](IndexType i) const { return vids[i]; }
function IndexType (line 180) | inline IndexType& operator[](IndexType i) { return vids[i]; }
function size_type (line 182) | static inline size_type size() { return 3; }
type TriangleTpl (line 206) | typedef TriangleTpl<std::uint16_t> Triangle16;
type TriangleTpl (line 208) | typedef TriangleTpl<std::uint32_t> Triangle32;
type _IndexType (line 219) | typedef _IndexType IndexType;
type size_type (line 220) | typedef int size_type;
function set (line 260) | inline void set(IndexType p0, IndexType p1, IndexType p2, IndexType p3) {
function IndexType (line 268) | inline IndexType operator[](IndexType i) const { return vids[i]; }
function IndexType (line 270) | inline IndexType& operator[](IndexType i) { return vids[i]; }
function size_type (line 272) | static inline size_type size() { return 4; }
type QuadrilateralTpl (line 290) | typedef QuadrilateralTpl<std::uint16_t> Quadrilateral16;
type QuadrilateralTpl (line 292) | typedef QuadrilateralTpl<std::uint32_t> Quadrilateral32;
FILE: include/coal/distance.h
function namespace (line 46) | namespace coal {
FILE: include/coal/distance_func_matrix.h
function namespace (line 45) | namespace coal {
FILE: include/coal/doc.hh
type coal (line 35) | namespace coal {
FILE: include/coal/fwd.hh
type coal (line 140) | namespace coal {
class CollisionObject (line 145) | class CollisionObject
class CollisionGeometry (line 148) | class CollisionGeometry
class Transform3s (line 151) | class Transform3s
class AABB (line 153) | class AABB
class BVHModelBase (line 155) | class BVHModelBase
class OcTree (line 158) | class OcTree
type hpp (line 164) | namespace hpp {
type fcl (line 165) | namespace fcl {
FILE: include/coal/hfield.h
function namespace (line 48) | namespace coal {
function COAL_DLLAPI (line 133) | COAL_DLLAPI HFNode : public HFNodeBase {
function virtual (line 174) | virtual ~HFNode() {}
function namespace (line 177) | namespace details {
function COAL_DLLAPI (line 209) | COAL_DLLAPI HeightField : public CollisionGeometry {
function virtual (line 275) | virtual HeightField<BV>* clone() const override {
function virtual (line 282) | virtual ~HeightField() {}
function computeLocalAABB (line 286) | void computeLocalAABB() override {
function updateHeights (line 298) | void updateHeights(const MatrixXs& new_heights) {
function Vec3s (line 345) | Vec3s computeCOM() const override { return Vec3s::Zero(); }
function Matrix3s (line 349) | Matrix3s computeMomentofInertia() const override { return Matrix3s::Zero...
function Scalar (line 383) | Scalar recursiveUpdateHeight(const size_t bv_id) {
function Scalar (line 407) | Scalar recursiveBuildTree(const size_t bv_id, const Eigen::DenseIndex x_id,
FILE: include/coal/internal/BV_fitter.h
function namespace (line 47) | namespace coal {
FILE: include/coal/internal/BV_splitter.h
function namespace (line 47) | namespace coal {
FILE: include/coal/internal/intersect.h
function namespace (line 45) | namespace coal {
FILE: include/coal/internal/intersect.hxx
type coal (line 49) | namespace coal {
FILE: include/coal/internal/shape_shape_contact_patch_func.h
function namespace (line 48) | namespace coal {
FILE: include/coal/internal/shape_shape_func.h
function namespace (line 50) | namespace coal {
function namespace (line 103) | namespace internal {
function run (line 136) | static std::size_t run(const CollisionGeometry* o1, const Transform3s& tf1,
function ShapeShapeCollide (line 167) | size_t ShapeShapeCollide(const CollisionGeometry* o1,
FILE: include/coal/internal/tools.h
function namespace (line 49) | namespace coal {
FILE: include/coal/internal/traversal.h
function namespace (line 42) | namespace coal {
FILE: include/coal/internal/traversal_node_base.h
function namespace (line 47) | namespace coal {
FILE: include/coal/internal/traversal_node_bvh_hfield.h
function namespace (line 58) | namespace coal {
type MeshHeightFieldCollisionTraversalNode (line 239) | typedef MeshHeightFieldCollisionTraversalNode<OBB, 0>
type MeshHeightFieldCollisionTraversalNode (line 241) | typedef MeshHeightFieldCollisionTraversalNode<RSS, 0>
type MeshHeightFieldCollisionTraversalNode (line 243) | typedef MeshHeightFieldCollisionTraversalNode<kIOS, 0>
type MeshHeightFieldCollisionTraversalNode (line 245) | typedef MeshHeightFieldCollisionTraversalNode<OBBRSS, 0>
function namespace (line 250) | namespace details {
function isFirstNodeLeaf (line 330) | bool isFirstNodeLeaf(unsigned int b) const {
function isSecondNodeLeaf (line 335) | bool isSecondNodeLeaf(unsigned int b) const {
function firstOverSecond (line 340) | bool firstOverSecond(unsigned int b1, unsigned int b2) const {
function getFirstLeftChild (line 352) | int getFirstLeftChild(unsigned int b) const {
function getFirstRightChild (line 357) | int getFirstRightChild(unsigned int b) const {
function getSecondLeftChild (line 362) | int getSecondLeftChild(unsigned int b) const {
function getSecondRightChild (line 367) | int getSecondRightChild(unsigned int b) const {
function postprocessOrientedNode (line 512) | void postprocessOrientedNode() {
type MeshDistanceTraversalNode (line 526) | typedef MeshDistanceTraversalNode<RSS, 0> MeshDistanceTraversalNodeRSS;
type MeshDistanceTraversalNode (line 527) | typedef MeshDistanceTraversalNode<kIOS, 0> MeshDistanceTraversalNodekIOS;
type MeshDistanceTraversalNode (line 528) | typedef MeshDistanceTraversalNode<OBBRSS, 0> MeshDistanceTraversalNodeOB...
function namespace (line 534) | namespace details {
FILE: include/coal/internal/traversal_node_bvh_shape.h
function namespace (line 52) | namespace coal {
function BVDisjoints (line 119) | bool BVDisjoints(unsigned int b1, unsigned int /*b2*/,
function leafCollides (line 138) | void leafCollides(unsigned int b1, unsigned int /*b2*/,
function isFirstNodeLeaf (line 214) | bool isFirstNodeLeaf(unsigned int b) const {
function getFirstLeftChild (line 219) | int getFirstLeftChild(unsigned int b) const {
function getFirstRightChild (line 224) | int getFirstRightChild(unsigned int b) const {
function Scalar (line 229) | Scalar BVDistanceLowerBound(unsigned int b1, unsigned int /*b2*/) const {
function isSecondNodeLeaf (line 256) | bool isSecondNodeLeaf(unsigned int b) const {
function getSecondLeftChild (line 261) | int getSecondLeftChild(unsigned int b) const {
function getSecondRightChild (line 266) | int getSecondRightChild(unsigned int b) const {
function Scalar (line 271) | Scalar BVDistanceLowerBound(unsigned int /*b1*/, unsigned int b2) const {
function namespace (line 338) | namespace details {
function distancePreprocessOrientedNode (line 366) | inline void distancePreprocessOrientedNode(
FILE: include/coal/internal/traversal_node_bvhs.h
function namespace (line 56) | namespace coal {
function BVDisjoints (line 151) | bool BVDisjoints(unsigned int b1, unsigned int b2,
function leafCollides (line 183) | void leafCollides(unsigned int b1, unsigned int b2,
type MeshCollisionTraversalNode (line 245) | typedef MeshCollisionTraversalNode<OBB, 0> MeshCollisionTraversalNodeOBB;
type MeshCollisionTraversalNode (line 246) | typedef MeshCollisionTraversalNode<RSS, 0> MeshCollisionTraversalNodeRSS;
type MeshCollisionTraversalNode (line 247) | typedef MeshCollisionTraversalNode<kIOS, 0> MeshCollisionTraversalNodekIOS;
type MeshCollisionTraversalNode (line 248) | typedef MeshCollisionTraversalNode<OBBRSS, 0> MeshCollisionTraversalNode...
function namespace (line 252) | namespace details {
function isFirstNodeLeaf (line 332) | bool isFirstNodeLeaf(unsigned int b) const {
function isSecondNodeLeaf (line 337) | bool isSecondNodeLeaf(unsigned int b) const {
function firstOverSecond (line 342) | bool firstOverSecond(unsigned int b1, unsigned int b2) const {
function getFirstLeftChild (line 354) | int getFirstLeftChild(unsigned int b) const {
function getFirstRightChild (line 359) | int getFirstRightChild(unsigned int b) const {
function getSecondLeftChild (line 364) | int getSecondLeftChild(unsigned int b) const {
function getSecondRightChild (line 369) | int getSecondRightChild(unsigned int b) const {
function postprocessOrientedNode (line 514) | void postprocessOrientedNode() {
type MeshDistanceTraversalNode (line 528) | typedef MeshDistanceTraversalNode<RSS, 0> MeshDistanceTraversalNodeRSS;
type MeshDistanceTraversalNode (line 529) | typedef MeshDistanceTraversalNode<kIOS, 0> MeshDistanceTraversalNodekIOS;
type MeshDistanceTraversalNode (line 530) | typedef MeshDistanceTraversalNode<OBBRSS, 0> MeshDistanceTraversalNodeOB...
function namespace (line 536) | namespace details {
FILE: include/coal/internal/traversal_node_hfield_shape.h
function namespace (line 53) | namespace coal {
FILE: include/coal/internal/traversal_node_octree.h
function namespace (line 54) | namespace coal {
type ConvexTpl (line 615) | typedef ConvexTpl<Triangle32> ConvexTriangle;
type ConvexTpl (line 738) | typedef ConvexTpl<Triangle32> ConvexTriangle;
function OcTreeDistanceRecurse (line 815) | bool OcTreeDistanceRecurse(const OcTree* tree1,
function OcTreeIntersectRecurse (line 896) | bool OcTreeIntersectRecurse(const OcTree* tree1,
function BVDisjoints (line 1034) | bool BVDisjoints(unsigned, unsigned, Scalar&) const { return false; }
function leafCollides (line 1036) | void leafCollides(unsigned, unsigned, Scalar& sqrDistLowerBound) const {
function COAL_DLLAPI (line 1052) | COAL_DLLAPI ShapeOcTreeCollisionTraversalNode
function BVDisjoints (line 1063) | bool BVDisjoints(unsigned int, unsigned int, Scalar&) const { return fal...
function leafCollides (line 1065) | void leafCollides(unsigned int, unsigned int,
function COAL_DLLAPI (line 1083) | COAL_DLLAPI OcTreeShapeCollisionTraversalNode
function BVDisjoints (line 1094) | bool BVDisjoints(unsigned int, unsigned int, coal::Scalar&) const {
function leafCollides (line 1098) | void leafCollides(unsigned int, unsigned int,
function COAL_DLLAPI (line 1115) | COAL_DLLAPI MeshOcTreeCollisionTraversalNode
function BVDisjoints (line 1126) | bool BVDisjoints(unsigned int, unsigned int, Scalar&) const { return fal...
function leafCollides (line 1128) | void leafCollides(unsigned int, unsigned int,
function COAL_DLLAPI (line 1145) | COAL_DLLAPI OcTreeMeshCollisionTraversalNode
function BVDisjoints (line 1156) | bool BVDisjoints(unsigned int, unsigned int, Scalar&) const { return fal...
function leafCollides (line 1158) | void leafCollides(unsigned int, unsigned int,
function COAL_DLLAPI (line 1175) | COAL_DLLAPI OcTreeHeightFieldCollisionTraversalNode
function BVDisjoints (line 1186) | bool BVDisjoints(unsigned int, unsigned int, Scalar&) const { return fal...
function leafCollides (line 1188) | void leafCollides(unsigned int, unsigned int,
function COAL_DLLAPI (line 1204) | COAL_DLLAPI HeightFieldOcTreeCollisionTraversalNode
function BVDisjoints (line 1215) | bool BVDisjoints(unsigned int, unsigned int, Scalar&) const { return fal...
function leafCollides (line 1217) | void leafCollides(unsigned int, unsigned int,
function Scalar (line 1247) | Scalar BVDistanceLowerBound(unsigned, unsigned) const { return -1; }
function BVDistanceLowerBound (line 1249) | bool BVDistanceLowerBound(unsigned, unsigned, Scalar&) const { return fa...
function leafComputeDistance (line 1251) | void leafComputeDistance(unsigned, unsigned int) const {
function COAL_DLLAPI (line 1263) | COAL_DLLAPI ShapeOcTreeDistanceTraversalNode
function COAL_DLLAPI (line 1287) | COAL_DLLAPI OcTreeShapeDistanceTraversalNode
function COAL_DLLAPI (line 1311) | COAL_DLLAPI MeshOcTreeDistanceTraversalNode
function COAL_DLLAPI (line 1335) | COAL_DLLAPI OcTreeMeshDistanceTraversalNode
FILE: include/coal/internal/traversal_node_setup.h
function namespace (line 58) | namespace coal {
function namespace (line 434) | namespace details {
function namespace (line 743) | namespace details {
FILE: include/coal/internal/traversal_node_shapes.h
function namespace (line 49) | namespace coal {
function COAL_DLLAPI (line 91) | COAL_DLLAPI ShapeDistanceTraversalNode
FILE: include/coal/internal/traversal_recurse.h
function namespace (line 48) | namespace coal {
FILE: include/coal/math/transform.h
function namespace (line 44) | namespace coal {
function Quats (line 254) | Quats fromAxisAngle(const Eigen::MatrixBase<Derived>& axis,
function Quats (line 261) | inline Quats uniformRandomQuaternion() {
function setRandom (line 284) | inline void Transform3s::setRandom() {
function Matrix3s (line 292) | inline Matrix3s constructOrthonormalBasisFromVector(const Vec3s& vec) {
FILE: include/coal/mesh_loader/assimp.h
type aiScene (line 46) | struct aiScene
function namespace (line 47) | namespace Assimp {
function namespace (line 51) | namespace coal {
FILE: include/coal/mesh_loader/loader.h
function namespace (line 49) | namespace coal {
FILE: include/coal/narrowphase/gjk.h
function namespace (line 46) | namespace coal {
FILE: include/coal/narrowphase/minkowski_difference.h
function namespace (line 46) | namespace coal {
FILE: include/coal/narrowphase/narrowphase.h
function namespace (line 50) | namespace coal {
FILE: include/coal/narrowphase/narrowphase_defaults.h
function namespace (line 43) | namespace coal {
FILE: include/coal/narrowphase/support_data.h
function namespace (line 45) | namespace coal {
FILE: include/coal/narrowphase/support_functions.h
function namespace (line 47) | namespace coal {
FILE: include/coal/octree.h
function namespace (line 50) | namespace coal {
FILE: include/coal/serialization/AABB.h
function namespace (line 11) | namespace boost {
FILE: include/coal/serialization/BVH_model.h
function namespace (line 17) | namespace boost {
type internal (line 112) | typedef internal::BVHModelAccessor<BV> Accessor;
type BVNode (line 113) | typedef BVNode<BV> Node;
type internal (line 177) | typedef internal::BVHModelAccessor<BV> Accessor;
type BVNode (line 178) | typedef BVNode<BV> Node;
function namespace (line 228) | namespace coal {
FILE: include/coal/serialization/BV_node.h
function namespace (line 13) | namespace boost {
FILE: include/coal/serialization/BV_splitter.h
function namespace (line 12) | namespace boost {
FILE: include/coal/serialization/OBB.h
function namespace (line 12) | namespace boost {
FILE: include/coal/serialization/OBBRSS.h
function namespace (line 14) | namespace boost {
FILE: include/coal/serialization/RSS.h
function namespace (line 12) | namespace boost {
FILE: include/coal/serialization/archive.h
function namespace (line 51) | namespace coal {
FILE: include/coal/serialization/collision_data.h
function namespace (line 11) | namespace boost {
function serialize (line 40) | COAL_SERIALIZATION_SPLIT(coal::Contact)
FILE: include/coal/serialization/collision_object.h
function namespace (line 13) | namespace boost {
function namespace (line 39) | COAL_SERIALIZATION_SPLIT(coal::CollisionGeometry)
FILE: include/coal/serialization/contact_patch.h
function namespace (line 12) | namespace boost {
FILE: include/coal/serialization/convex.h
function namespace (line 16) | namespace boost {
FILE: include/coal/serialization/eigen.h
function namespace (line 32) | namespace boost {
function namespace (line 37) | namespace Eigen {
function namespace (line 54) | namespace boost {
function namespace (line 61) | namespace Eigen {
function namespace (line 79) | namespace boost {
FILE: include/coal/serialization/fwd.h
function namespace (line 62) | namespace serialization {
FILE: include/coal/serialization/geometric_shapes.h
function namespace (line 12) | namespace boost {
FILE: include/coal/serialization/hfield.h
function namespace (line 13) | namespace boost {
function namespace (line 36) | namespace internal {
type internal (line 59) | typedef internal::HeightFieldAccessor<BV> Accessor;
FILE: include/coal/serialization/kDOP.h
function namespace (line 12) | namespace boost {
FILE: include/coal/serialization/kIOS.h
function namespace (line 13) | namespace boost {
FILE: include/coal/serialization/memory.h
function namespace (line 8) | namespace coal {
FILE: include/coal/serialization/octree.h
function namespace (line 16) | namespace boost {
FILE: include/coal/serialization/quadrilateral.h
function namespace (line 11) | namespace boost {
FILE: include/coal/serialization/serializer.h
function namespace (line 10) | namespace coal {
function saveToXML (line 59) | void saveToXML(const T& object, const std::string& filename,
function saveToBinary (line 72) | void saveToBinary(const T& object, const std::string& filename) {
function saveToBuffer (line 84) | void saveToBuffer(const T& object, boost::asio::streambuf& container) {
FILE: include/coal/serialization/transform.h
function namespace (line 11) | namespace boost {
FILE: include/coal/serialization/triangle.h
function namespace (line 11) | namespace boost {
FILE: include/coal/shape/convex.h
function namespace (line 44) | namespace coal {
FILE: include/coal/shape/convex.hxx
type coal (line 46) | namespace coal {
function Matrix3s (line 115) | Matrix3s ConvexTpl<PolygonT>::computeMomentofInertia() const {
function Vec3s (line 175) | Vec3s ConvexTpl<PolygonT>::computeCOM() const {
function Scalar (line 220) | Scalar ConvexTpl<PolygonT>::computeVolume() const {
FILE: include/coal/shape/geometric_shape_to_BVH_model.h
function Triangle32 (line 207) | Triangle32 tmp((h_num + 1) * tot, i, ((i == tot - 1) ? 0 : (i + 1)));
FILE: include/coal/shape/geometric_shapes.h
function namespace (line 51) | namespace orgQhull {
function namespace (line 56) | namespace coal {
function virtual (line 1067) | virtual Plane* clone() const override { return new Plane(*this); }
function Scalar (line 1069) | Scalar signedDistance(const Vec3s& p) const {
function Scalar (line 1081) | Scalar distance(const Vec3s& p) const {
function computeLocalAABB (line 1086) | void computeLocalAABB() override;
FILE: include/coal/shape/geometric_shapes.hxx
type coal (line 47) | namespace coal {
function NODE_TYPE (line 50) | NODE_TYPE ConvexBaseTpl<IndexType>::getNodeType() const {
function NODE_TYPE (line 57) | inline NODE_TYPE ConvexBaseTpl<std::uint16_t>::getNodeType() const {
function NODE_TYPE (line 62) | inline NODE_TYPE ConvexBaseTpl<std::uint32_t>::getNodeType() const {
function reorderTriangle (line 211) | void reorderTriangle(const ConvexTpl<TriangleTpl<IndexType>>* convex_tri,
FILE: include/coal/shape/geometric_shapes_traits.h
function namespace (line 42) | namespace coal {
FILE: include/coal/shape/geometric_shapes_utility.h
function namespace (line 46) | namespace coal {
FILE: include/coal/shared_ptr_comparison.h
function namespace (line 41) | namespace coal {
FILE: include/coal/third_party/boost/core/data.hpp
type boost (line 19) | namespace boost {
function data (line 31) | inline constexpr auto data(C& c) noexcept(noexcept(c.data()))
function data (line 37) | inline constexpr auto data(const C& c) noexcept(noexcept(c.data()))
function T (line 43) | inline constexpr T* data(T (&a)[N]) noexcept {
function T (line 48) | inline constexpr const T* data(std::initializer_list<T> l) noexcept {
type boost (line 28) | namespace boost {
function data (line 31) | inline constexpr auto data(C& c) noexcept(noexcept(c.data()))
function data (line 37) | inline constexpr auto data(const C& c) noexcept(noexcept(c.data()))
function T (line 43) | inline constexpr T* data(T (&a)[N]) noexcept {
function T (line 48) | inline constexpr const T* data(std::initializer_list<T> l) noexcept {
FILE: include/coal/third_party/boost/core/make_span.hpp
type boost (line 13) | namespace boost {
function make_span (line 16) | inline constexpr span<I> make_span(I* f, std::size_t c) noexcept {
function make_span (line 21) | inline constexpr span<I> make_span(I* f, I* l) noexcept {
function make_span (line 26) | inline constexpr span<T, N> make_span(T (&a)[N]) noexcept {
function make_span (line 31) | inline constexpr span<T, N> make_span(std::array<T, N>& a) noexcept {
function make_span (line 36) | inline constexpr span<const T, N> make_span(
function make_span (line 42) | inline span<typename detail::span_data<R>::type> make_span(R&& r) {
FILE: include/coal/third_party/boost/core/span.hpp
type boost (line 18) | namespace boost {
class span (line 23) | class span
method span (line 186) | constexpr span() noexcept : s_(0, 0) {}
method span (line 192) | constexpr span(I* f, size_type c) : s_(f, c) {}
method span (line 198) | explicit constexpr span(I* f, size_type c) : s_(f, c) {}
method span (line 204) | constexpr span(I* f, L* l) : s_(f, l - f) {}
method span (line 210) | explicit constexpr span(I* f, L* l) : s_(f, l - f) {}
method span (line 215) | constexpr span(typename std::enable_if<true, T>::type (&a)[N]) noexcept
method span (line 221) | constexpr span(std::array<U, N>& a) noexcept : s_(a.data(), N) {}
method span (line 227) | constexpr span(const std::array<U, N>& a) noexcept : s_(a.data(), N) {}
method span (line 233) | constexpr span(R&& r) noexcept(noexcept(boost::data(r)) && noexcept(...
method span (line 240) | explicit constexpr span(R&& r) noexcept(noexcept(boost::data(r)) &&
method span (line 249) | constexpr span(const span<U, N>& s) noexcept : s_(s.data(), s.size()...
method span (line 256) | explicit constexpr span(const span<U, N>& s) noexcept
method first (line 260) | constexpr span<T, C> first() const {
method last (line 266) | constexpr span<T, C> last() const {
method subspan (line 272) | constexpr
method subspan (line 281) | constexpr typename std::enable_if<C != dynamic_extent, span<T, C>>::...
method first (line 288) | constexpr span<T, dynamic_extent> first(size_type c) const {
method last (line 293) | constexpr span<T, dynamic_extent> last(size_type c) const {
method subspan (line 298) | constexpr span<T, dynamic_extent> subspan(
method size_type (line 306) | constexpr size_type size() const noexcept { return s_.n; }
method size_type (line 308) | constexpr size_type size_bytes() const noexcept { return s_.n * size...
method empty (line 310) | constexpr bool empty() const noexcept { return s_.n == 0; }
method reference (line 312) | constexpr reference operator[](size_type i) const {
method reference (line 316) | constexpr reference front() const {
method reference (line 320) | constexpr reference back() const {
method pointer (line 324) | constexpr pointer data() const noexcept { return s_.p; }
method iterator (line 326) | constexpr iterator begin() const noexcept { return s_.p; }
method iterator (line 328) | constexpr iterator end() const noexcept { return s_.p + s_.n; }
method reverse_iterator (line 330) | constexpr reverse_iterator rbegin() const noexcept {
method reverse_iterator (line 334) | constexpr reverse_iterator rend() const noexcept {
method const_iterator (line 338) | constexpr const_iterator cbegin() const noexcept { return s_.p; }
method const_iterator (line 340) | constexpr const_iterator cend() const noexcept { return s_.p + s_.n; }
method const_reverse_iterator (line 342) | constexpr const_reverse_iterator crbegin() const noexcept {
method const_reverse_iterator (line 346) | constexpr const_reverse_iterator crend() const noexcept {
type detail (line 25) | namespace detail {
type span_convertible (line 28) | struct span_convertible {
type span_convertible<U, T,
typename std::enable_if<std::is_convertible<
U (*)[], T (*)[]>::value>::type> (line 33) | struct span_convertible<U, T,
type span_capacity (line 40) | struct span_capacity {
type span_compatible (line 45) | struct span_compatible {
type span_is_span (line 55) | struct span_is_span {
type span_is_span<boost::span<T, E>> (line 60) | struct span_is_span<boost::span<T, E>> {
type span_is_array (line 65) | struct span_is_array {
type span_is_array<std::array<T, N>> (line 70) | struct span_is_array<std::array<T, N>> {
type span_data (line 78) | struct span_data {}
type span_data<
T, typename std::enable_if<std::is_pointer<span_ptr<T>>::value>::type> (line 81) | struct span_data<
type span_has_data (line 87) | struct span_has_data {
type span_has_data<R, T,
typename std::enable_if<span_convertible<
typename span_data<R>::type, T>::value>::type> (line 92) | struct span_has_data<R, T,
type span_has_size (line 99) | struct span_has_size {
type span_is_range (line 111) | struct span_is_range {
type span_implicit (line 121) | struct span_implicit {
type span_copyable (line 127) | struct span_copyable {
type span_sub (line 134) | struct span_sub {
type span_store (line 140) | struct span_store {
method span_store (line 141) | constexpr span_store(T* p_, std::size_t) noexcept : p(p_) {}
type span_store<T, boost::dynamic_extent> (line 147) | struct span_store<T, boost::dynamic_extent> {
method span_store (line 148) | constexpr span_store(T* p_, std::size_t n_) noexcept : p(p_), n(n_...
type span_bytes (line 154) | struct span_bytes {
type span_bytes<T, boost::dynamic_extent> (line 159) | struct span_bytes<T, boost::dynamic_extent> {
class span (line 166) | class span {
method span (line 186) | constexpr span() noexcept : s_(0, 0) {}
method span (line 192) | constexpr span(I* f, size_type c) : s_(f, c) {}
method span (line 198) | explicit constexpr span(I* f, size_type c) : s_(f, c) {}
method span (line 204) | constexpr span(I* f, L* l) : s_(f, l - f) {}
method span (line 210) | explicit constexpr span(I* f, L* l) : s_(f, l - f) {}
method span (line 215) | constexpr span(typename std::enable_if<true, T>::type (&a)[N]) noexcept
method span (line 221) | constexpr span(std::array<U, N>& a) noexcept : s_(a.data(), N) {}
method span (line 227) | constexpr span(const std::array<U, N>& a) noexcept : s_(a.data(), N) {}
method span (line 233) | constexpr span(R&& r) noexcept(noexcept(boost::data(r)) && noexcept(...
method span (line 240) | explicit constexpr span(R&& r) noexcept(noexcept(boost::data(r)) &&
method span (line 249) | constexpr span(const span<U, N>& s) noexcept : s_(s.data(), s.size()...
method span (line 256) | explicit constexpr span(const span<U, N>& s) noexcept
method first (line 260) | constexpr span<T, C> first() const {
method last (line 266) | constexpr span<T, C> last() const {
method subspan (line 272) | constexpr
method subspan (line 281) | constexpr typename std::enable_if<C != dynamic_extent, span<T, C>>::...
method first (line 288) | constexpr span<T, dynamic_extent> first(size_type c) const {
method last (line 293) | constexpr span<T, dynamic_extent> last(size_type c) const {
method subspan (line 298) | constexpr span<T, dynamic_extent> subspan(
method size_type (line 306) | constexpr size_type size() const noexcept { return s_.n; }
method size_type (line 308) | constexpr size_type size_bytes() const noexcept { return s_.n * size...
method empty (line 310) | constexpr bool empty() const noexcept { return s_.n == 0; }
method reference (line 312) | constexpr reference operator[](size_type i) const {
method reference (line 316) | constexpr reference front() const {
method reference (line 320) | constexpr reference back() const {
method pointer (line 324) | constexpr pointer data() const noexcept { return s_.p; }
method iterator (line 326) | constexpr iterator begin() const noexcept { return s_.p; }
method iterator (line 328) | constexpr iterator end() const noexcept { return s_.p + s_.n; }
method reverse_iterator (line 330) | constexpr reverse_iterator rbegin() const noexcept {
method reverse_iterator (line 334) | constexpr reverse_iterator rend() const noexcept {
method const_iterator (line 338) | constexpr const_iterator cbegin() const noexcept { return s_.p; }
method const_iterator (line 340) | constexpr const_iterator cend() const noexcept { return s_.p + s_.n; }
method const_reverse_iterator (line 342) | constexpr const_reverse_iterator crbegin() const noexcept {
method const_reverse_iterator (line 346) | constexpr const_reverse_iterator crend() const noexcept {
function as_bytes (line 381) | inline span<const std::byte, detail::span_bytes<T, E>::value> as_bytes(
function as_writable_bytes (line 388) | inline typename std::enable_if<
type span_has_size<
R, typename std::enable_if<std::is_convertible<
decltype(std::declval<R&>().size()), std::size_t>::value>::type> (line 104) | struct span_has_size<
FILE: include/coal/timings.h
function namespace (line 12) | namespace coal {
function start (line 79) | void start() {
function stop (line 88) | void stop() {
function resume (line 100) | void resume() {
FILE: python-nb/aabb.cc
function exposeAABB (line 17) | void exposeAABB(nb::module_& m) {
FILE: python-nb/broadphase/broadphase.cc
function COAL_COMPILER_DIAGNOSTIC_PUSH (line 22) | COAL_COMPILER_DIAGNOSTIC_PUSH
FILE: python-nb/broadphase/broadphase_callbacks_collision_manager.hh
type coal (line 14) | namespace coal {
type CollisionCallBackBaseWrapper (line 16) | struct CollisionCallBackBaseWrapper : CollisionCallBackBase {
method init (line 20) | void init() override { NB_OVERRIDE_PURE(init); }
method collide (line 22) | bool collide(CollisionObject* o1, CollisionObject* o2) override {
method expose (line 26) | static void expose(nb::module_& m) {
type DistanceCallBackBaseWrapper (line 35) | struct DistanceCallBackBaseWrapper : DistanceCallBackBase {
method init (line 40) | void init() override { NB_OVERRIDE_PURE(init); }
method distance (line 42) | bool distance(CollisionObject* o1, CollisionObject* o2,
method distance (line 47) | bool distance(CollisionObject* o1, CollisionObject* o2,
method expose (line 52) | static void expose(nb::module_& m) {
type BroadPhaseCollisionManagerWrapper (line 65) | struct BroadPhaseCollisionManagerWrapper : BroadPhaseCollisionManager {
method registerObjects (line 69) | void registerObjects(
method registerObject (line 73) | void registerObject(CollisionObject* obj) override {
method unregisterObject (line 76) | void unregisterObject(CollisionObject* obj) override {
method update (line 80) | void update(const std::vector<CollisionObject*>& other_objs) override {
method update (line 83) | void update(CollisionObject* obj) override { NB_OVERRIDE_PURE(update...
method update (line 84) | void update() override { NB_OVERRIDE_PURE(update); }
method setup (line 86) | void setup() override { NB_OVERRIDE_PURE(setup); }
method clear (line 87) | void clear() override { NB_OVERRIDE_PURE(clear); }
method getObjects (line 89) | std::vector<CollisionObject*> getObjects() const override {
method collide (line 93) | void collide(CollisionCallBackBase* callback) const override {
method collide (line 96) | void collide(CollisionObject* obj,
method collide (line 100) | void collide(BroadPhaseCollisionManager* other_manager,
method distance (line 105) | void distance(DistanceCallBackBase* callback) const override {
method distance (line 108) | void distance(CollisionObject* obj,
method distance (line 112) | void distance(BroadPhaseCollisionManager* other_manager,
method empty (line 117) | bool empty() const override { NB_OVERRIDE_PURE(empty); }
method size (line 118) | size_t size() const override { NB_OVERRIDE_PURE(size); }
method expose (line 120) | static void expose(nb::module_& m) {
method exposeDerived (line 204) | static void exposeDerived(nb::module_& m, const char* name) {
FILE: python-nb/bvh.cc
function exposeBVHModel (line 21) | void exposeBVHModel(nb::module_& m, const char* name) {
function exposeBVHModels (line 34) | void exposeBVHModels(nb::module_& m) {
FILE: python-nb/coal/windows_dll_manager.py
function get_dll_paths (line 6) | def get_dll_paths():
class PathManager (line 25) | class PathManager(contextlib.AbstractContextManager):
method add_dll_directory (line 28) | def add_dll_directory(self, dll_dir: str):
method __enter__ (line 31) | def __enter__(self):
method __exit__ (line 35) | def __exit__(self, *exc_details):
class DllDirectoryManager (line 39) | class DllDirectoryManager(contextlib.AbstractContextManager):
method add_dll_directory (line 42) | def add_dll_directory(self, dll_dir: str):
method __enter__ (line 52) | def __enter__(self):
method __exit__ (line 56) | def __exit__(self, *exc_details):
function build_directory_manager (line 61) | def build_directory_manager():
FILE: python-nb/collision-geometries.cc
function exposeCollisionGeometries (line 24) | void exposeCollisionGeometries(nb::module_& m) {
function exposeCollisionObject (line 115) | void exposeCollisionObject(nb::module_& m) {
FILE: python-nb/collision.cc
function exposeCollisionAPI (line 18) | void exposeCollisionAPI(nb::module_& m) {
FILE: python-nb/contact_patch.cc
function exposeContactPatchAPI (line 14) | void exposeContactPatchAPI(nb::module_& m) {
FILE: python-nb/distance.cc
function exposeDistanceAPI (line 14) | void exposeDistanceAPI(nb::module_& m) {
FILE: python-nb/gjk.cc
function exposeGJK (line 16) | void exposeGJK(nb::module_& m) {
FILE: python-nb/height_field.cc
function exposeHeightField (line 18) | void exposeHeightField(nb::module_& m, const char* name) {
function exposeHeightFields (line 52) | void exposeHeightFields(nb::module_& m) {
FILE: python-nb/math.cc
function exposeTriangle (line 18) | void exposeTriangle(nb::module_& m, const std::string& classname) {
function exposeMaths (line 43) | void exposeMaths(nb::module_& m) {
FILE: python-nb/memory-footprint.cc
function defComputeMemoryFootprint (line 12) | void defComputeMemoryFootprint(nb::module_& m) {
function exposeComputeMemoryFootprint (line 16) | void exposeComputeMemoryFootprint(nb::module_& m) {
FILE: python-nb/module.cc
function checkVersionAtLeast (line 10) | inline constexpr bool checkVersionAtLeast(int major, int minor, int patc...
function checkVersionAtMost (line 14) | inline constexpr bool checkVersionAtMost(int major, int minor, int patch) {
function exposeVersion (line 18) | void exposeVersion(nb::module_& m) {
function exposeMeshLoader (line 49) | void exposeMeshLoader(nb::module_& m) {
function NB_MODULE (line 81) | NB_MODULE(COAL_PYTHON_LIBNAME, m) {
FILE: python-nb/octree.cc
function tobytes (line 11) | nb::bytes tobytes(const OcTree& self) {
function exposeOctree (line 16) | void exposeOctree(nb::module_& m) {
FILE: python-nb/pickle.hh
type coal::python (line 13) | namespace coal::python {
type v2 (line 14) | namespace v2 {
type PickleVisitor (line 18) | struct PickleVisitor : nb::def_visitor<PickleVisitor<T>> {
method execute (line 20) | void execute(nb::class_<T, Ts...>& cl) {
FILE: python-nb/serializable.hh
type coal::python (line 11) | namespace coal::python {
type v2 (line 12) | namespace v2 {
type SerializableVisitor (line 16) | struct SerializableVisitor : nb::def_visitor<SerializableVisitor<Der...
method execute (line 18) | void execute(nb::class_<Derived, Ts...>& cl) {
FILE: python-nb/shapes.cc
function exposeConvexBase (line 28) | void exposeConvexBase(nb::module_& m, const std::string& classname) {
function exposeConvex (line 126) | void exposeConvex(nb::module_& m, const std::string& classname) {
function exposeShapes (line 169) | void exposeShapes(nb::module_& m) {
FILE: python/broadphase/broadphase_callbacks.hh
type coal (line 50) | namespace coal {
type CollisionCallBackBaseWrapper (line 52) | struct CollisionCallBackBaseWrapper : CollisionCallBackBase,
method init (line 56) | void init() { this->get_override("init")(); }
method collide (line 57) | bool collide(CollisionObject* o1, CollisionObject* o2) {
method expose (line 64) | static void expose() {
type DistanceCallBackBaseWrapper (line 76) | struct DistanceCallBackBaseWrapper : DistanceCallBackBase,
method init (line 81) | void init() { this->get_override("init")(); }
method distance (line 82) | bool distance(CollisionObject* o1, CollisionObject* o2,
method distance (line 87) | bool distance(CollisionObject* o1, CollisionObject* o2, Scalar& dist) {
method expose (line 94) | static void expose() {
FILE: python/broadphase/broadphase_collision_manager.hh
function registerObjects (line 61) | void registerObjects(const std::vector<CollisionObject*>& other_objs) {
function registerObject (line 64) | void registerObject(CollisionObject* obj) {
function unregisterObject (line 67) | void unregisterObject(CollisionObject* obj) {
function update (line 71) | void update(const std::vector<CollisionObject*>& other_objs) {
function update (line 74) | void update(CollisionObject* obj) { this->get_override("update")(obj); }
function update (line 75) | void update() { this->get_override("update")(); }
function setup (line 77) | void setup() { this->get_override("setup")(); }
function clear (line 78) | void clear() { this->get_override("clear")(); }
function getObjects (line 80) | std::vector<CollisionObject*> getObjects() const {
function collide (line 87) | void collide(CollisionCallBackBase* callback) const {
function collide (line 90) | void collide(CollisionObject* obj, CollisionCallBackBase* callback) const {
function collide (line 93) | void collide(BroadPhaseCollisionManager* other_manager,
function distance (line 98) | void distance(DistanceCallBackBase* callback) const {
function distance (line 101) | void distance(CollisionObject* obj, DistanceCallBackBase* callback) const {
function distance (line 104) | void distance(BroadPhaseCollisionManager* other_manager,
function empty (line 109) | bool empty() const {
function size (line 115) | size_t size() const {
FILE: python/broadphase/fwd.hh
type coal (line 10) | namespace coal {
type python (line 11) | namespace python {
FILE: python/coal.cc
function exposeMeshLoader (line 62) | void exposeMeshLoader() {
function BOOST_PYTHON_MODULE (line 86) | BOOST_PYTHON_MODULE(coal_pywrap) {
FILE: python/coal/viewer.py
function applyConfiguration (line 14) | def applyConfiguration(gui, name, tf):
function displayShape (line 20) | def displayShape(gui, name, geom, color=(0.9, 0.9, 0.9, 1.0)):
function displayDistanceResult (line 55) | def displayDistanceResult(gui, group_name, res, closest_points=True, nor...
function displayCollisionResult (line 83) | def displayCollisionResult(gui, group_name, res, color=Color.green):
FILE: python/coal/windows_dll_manager.py
function get_dll_paths (line 6) | def get_dll_paths():
class PathManager (line 25) | class PathManager(contextlib.AbstractContextManager):
method add_dll_directory (line 28) | def add_dll_directory(self, dll_dir: str):
method __enter__ (line 31) | def __enter__(self):
method __exit__ (line 35) | def __exit__(self, *exc_details):
class DllDirectoryManager (line 39) | class DllDirectoryManager(contextlib.AbstractContextManager):
method add_dll_directory (line 42) | def add_dll_directory(self, dll_dir: str):
method __enter__ (line 52) | def __enter__(self):
method __exit__ (line 56) | def __exit__(self, *exc_details):
function build_directory_manager (line 61) | def build_directory_manager():
FILE: python/collision-geometries.cc
type BVHModelBaseWrapper (line 84) | struct BVHModelBaseWrapper {
method Vec3s (line 89) | static Vec3s& vertex(BVHModelBase& bvh, unsigned int i) {
method RefRowMatrixX3 (line 94) | static RefRowMatrixX3 vertices(BVHModelBase& bvh) {
method Triangle32 (line 101) | static Triangle32 tri_indices(const BVHModelBase& bvh, unsigned int i) {
function exposeBVHModel (line 108) | void exposeBVHModel(const std::string& bvname) {
function exposeHeightField (line 130) | void exposeHeightField(const std::string& bvname) {
type ConvexBaseWrapper (line 175) | struct ConvexBaseWrapper {
method Vec3s (line 183) | static Vec3s& point(const ConvexBaseType& convex, unsigned int i) {
method RefRowMatrixX3 (line 189) | static RefRowMatrixX3 points(const ConvexBaseType& convex) {
method Vec3s (line 193) | static Vec3s& normal(const ConvexBaseType& convex, unsigned int i) {
method RefRowMatrixX3 (line 199) | static RefRowMatrixX3 normals(const ConvexBaseType& convex) {
method Scalar (line 204) | static Scalar offset(const ConvexBaseType& convex, unsigned int i) {
method RefVecXs (line 210) | static RefVecXs offsets(const ConvexBaseType& convex) {
method list (line 214) | static list neighbors(const ConvexBaseType& convex, unsigned int i) {
method ConvexBaseType (line 226) | static ConvexBaseType* convexHull(const Vec3ss& points, bool keepTri,
type ConvexWrapper (line 234) | struct ConvexWrapper {
method PolygonT (line 239) | static PolygonT polygons(const Convex_t& convex, unsigned int i) {
method constructor (line 245) | static shared_ptr<Convex_t> constructor(
function defComputeMemoryFootprint (line 263) | void defComputeMemoryFootprint() {
function exposeComputeMemoryFootprint (line 267) | void exposeComputeMemoryFootprint() {
function exposeConvexBase (line 284) | void exposeConvexBase(const std::string& classname) {
function exposeConvex (line 324) | void exposeConvex(const std::string& classname) {
function exposeShapes (line 346) | void exposeShapes() {
function AABB_distance_proxy (line 513) | boost::python::tuple AABB_distance_proxy(const AABB& self, const AABB& o...
function exposeCollisionGeometries (line 519) | void exposeCollisionGeometries() {
function exposeCollisionObject (line 770) | void exposeCollisionObject() {
FILE: python/collision.cc
function CollisionGeometry (line 64) | const CollisionGeometry* geto(const Contact& c) {
type ContactWrapper (line 68) | struct ContactWrapper {
method Vec3s (line 69) | static Vec3s getNearestPoint1(const Contact& contact) {
method Vec3s (line 72) | static Vec3s getNearestPoint2(const Contact& contact) {
function exposeCollisionAPI (line 77) | void exposeCollisionAPI() {
FILE: python/contact_patch.cc
function exposeContactPatchAPI (line 60) | void exposeContactPatchAPI() {
FILE: python/deprecation.hh
type coal (line 12) | namespace coal {
type python (line 13) | namespace python {
type deprecated_warning_policy (line 16) | struct deprecated_warning_policy : Policy {
method deprecated_warning_policy (line 17) | deprecated_warning_policy(const std::string& warning_message = "")
method precall (line 21) | bool precall(ArgumentPackage const& args) const {
type deprecated_member (line 34) | struct deprecated_member : deprecated_warning_policy<Policy> {
method deprecated_member (line 35) | deprecated_member(const std::string& warning_message =
type deprecated_function (line 42) | struct deprecated_function : deprecated_warning_policy<Policy> {
method deprecated_function (line 43) | deprecated_function(const std::string& warning_message =
FILE: python/distance.cc
type DistanceResultWrapper (line 62) | struct DistanceResultWrapper {
method Vec3s (line 63) | static Vec3s getNearestPoint1(const DistanceResult& res) {
method Vec3s (line 66) | static Vec3s getNearestPoint2(const DistanceResult& res) {
function exposeDistanceAPI (line 71) | void exposeDistanceAPI() {
FILE: python/fwd.hh
type doxygen (line 10) | namespace doxygen {
FILE: python/gjk.cc
type MinkowskiDiffWrapper (line 54) | struct MinkowskiDiffWrapper {
method support0 (line 55) | static void support0(MinkowskiDiff& self, const Vec3s& dir, int& hint,
method support1 (line 64) | static void support1(MinkowskiDiff& self, const Vec3s& dir, int& hint,
method set (line 73) | static void set(MinkowskiDiff& self, const ShapeBase* shape0,
method set (line 83) | static void set(MinkowskiDiff& self, const ShapeBase* shape0,
function exposeGJK (line 95) | void exposeGJK() {
FILE: python/math.cc
type TriangleWrapper (line 58) | struct TriangleWrapper {
method getitem (line 59) | static typename TriangleTpl<Integer>::IndexType getitem(
method setitem (line 66) | static void setitem(TriangleTpl<Integer>& t, int i,
function exposeTriangle (line 75) | void exposeTriangle(const std::string& classname) {
function exposeMaths (line 93) | void exposeMaths() {
FILE: python/octree.cc
function toPyBytes (line 14) | bp::object toPyBytes(std::vector<uint8_t>& bytes) {
function tobytes (line 26) | bp::object tobytes(const coal::OcTree& self) {
function exposeOctree (line 31) | void exposeOctree() {
FILE: python/pickle.hh
type PickleObject (line 19) | struct PickleObject : boost::python::pickle_suite {
method getinitargs (line 20) | static boost::python::tuple getinitargs(const T&) {
method getstate (line 24) | static boost::python::tuple getstate(const T& obj) {
method setstate (line 32) | static void setstate(T& obj, boost::python::tuple tup) {
method getstate_manages_dict (line 54) | static bool getstate_manages_dict() { return false; }
FILE: python/printable.hh
type coal (line 12) | namespace coal {
type python (line 13) | namespace python {
type PrintableVisitor (line 22) | struct PrintableVisitor : public bp::def_visitor<PrintableVisitor<C>> {
method visit (line 24) | void visit(PyClass& cl) const {
FILE: python/serializable.hh
type coal (line 15) | namespace coal {
type python (line 16) | namespace python {
type SerializableVisitor (line 23) | struct SerializableVisitor
method visit (line 26) | void visit(PyClass& cl) const {
FILE: python/utils/std-pair.hh
type StdPairConverter (line 12) | struct StdPairConverter {
method PyObject (line 16) | static PyObject* convert(const pair_type& pair) {
method construct (line 34) | static void construct(
method PyTypeObject (line 48) | static PyTypeObject const* get_pytype() {
method registration (line 53) | static void registration() {
FILE: python/version.cc
function checkVersionAtLeast (line 11) | inline bool checkVersionAtLeast(int major, int minor, int patch) {
function checkVersionAtMost (line 15) | inline bool checkVersionAtMost(int major, int minor, int patch) {
function exposeVersion (line 19) | void exposeVersion() {
FILE: src/BV/AABB.cpp
type coal (line 44) | namespace coal {
function Scalar (line 74) | Scalar AABB::distance(const AABB& other, Vec3s* P, Vec3s* Q) const {
function Scalar (line 114) | Scalar AABB::distance(const AABB& other) const {
function overlap (line 134) | bool overlap(const Matrix3s& R0, const Vec3s& T0, const AABB& b1,
function overlap (line 140) | bool overlap(const Matrix3s& R0, const Vec3s& T0, const AABB& b1,
FILE: src/BV/OBB.cpp
type coal (line 47) | namespace coal {
function computeVertices (line 50) | inline void computeVertices(const OBB& b, Vec3s vertices[8]) {
function OBB (line 63) | inline OBB merge_largedist(const OBB& b1, const OBB& b2) {
function OBB (line 115) | inline OBB merge_smalldist(const OBB& b1, const OBB& b2) {
function obbDisjoint (line 161) | bool obbDisjoint(const Matrix3s& B, const Vec3s& T, const Vec3s& a,
type internal (line 288) | namespace internal {
function Scalar (line 289) | inline Scalar obbDisjoint_check_A_axis(const Vec3s& T, const Vec3s& a,
function Scalar (line 297) | inline Scalar obbDisjoint_check_B_axis(const Matrix3s& B, const Vec3...
function obbDisjoint_check_Ai_cross_Bi (line 313) | struct COAL_LOCAL obbDisjoint_check_Ai_cross_Bi {
function obbDisjointAndLowerBoundDistance (line 344) | bool obbDisjointAndLowerBoundDistance(const Matrix3s& B, const Vec3s& T,
function OBB (line 438) | OBB& OBB::operator+=(const Vec3s& p) {
function OBB (line 448) | OBB OBB::operator+(const OBB& other) const {
function Scalar (line 460) | Scalar OBB::distance(const OBB& /*other*/, Vec3s* /*P*/, Vec3s* /*Q*/)...
function overlap (line 465) | bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBB& b1,
function overlap (line 474) | bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBB& b1, const...
function OBB (line 484) | OBB translate(const OBB& bv, const Vec3s& t) {
FILE: src/BV/OBB.h
function namespace (line 39) | namespace coal {
FILE: src/BV/OBBRSS.cpp
type coal (line 40) | namespace coal {
function OBBRSS (line 42) | OBBRSS translate(const OBBRSS& bv, const Vec3s& t) {
FILE: src/BV/RSS.cpp
type coal (line 45) | namespace coal {
function clipToRange (line 48) | void clipToRange(Scalar& val, Scalar a, Scalar b) {
function segCoords (line 66) | void segCoords(Scalar& t, Scalar& u, Scalar a, Scalar b, Scalar A_dot_B,
function inVoronoi (line 94) | bool inVoronoi(Scalar a, Scalar b, Scalar Anorm_dot_B, Scalar Anorm_do...
function Scalar (line 119) | Scalar rectDistance(const Matrix3s& Rab, Vec3s const& Tab, const Scala...
function overlap (line 727) | bool overlap(const Matrix3s& R0, const Vec3s& T0, const RSS& b1,
function overlap (line 742) | bool overlap(const Matrix3s& R0, const Vec3s& T0, const RSS& b1, const...
function RSS (line 791) | RSS& RSS::operator+=(const Vec3s& p) {
function RSS (line 908) | RSS RSS::operator+(const RSS& other) const {
function Scalar (line 983) | Scalar RSS::distance(const RSS& other, Vec3s* P, Vec3s* Q) const {
function Scalar (line 995) | Scalar distance(const Matrix3s& R0, const Vec3s& T0, const RSS& b1,
function RSS (line 1007) | RSS translate(const RSS& bv, const Vec3s& t) {
FILE: src/BV/kDOP.cpp
type coal (line 44) | namespace coal {
function minmax (line 47) | inline void minmax(Scalar a, Scalar b, Scalar& minv, Scalar& maxv) {
function minmax (line 57) | inline void minmax(Scalar p, Scalar& minv, Scalar& maxv) {
function getDistances (line 65) | void getDistances(const Vec3s& /*p*/, Scalar* /*d*/) {}
function Scalar (line 212) | Scalar KDOP<N>::distance(const KDOP<N>& /*other*/, Vec3s* /*P*/,
function translate (line 219) | KDOP<N> translate(const KDOP<N>& bv, const Vec3s& t) {
class KDOP<16> (line 236) | class KDOP<16>
class KDOP<18> (line 237) | class KDOP<18>
class KDOP<24> (line 238) | class KDOP<24>
FILE: src/BV/kIOS.cpp
type coal (line 45) | namespace coal {
function kIOS (line 85) | kIOS& kIOS::operator+=(const Vec3s& p) {
function kIOS (line 98) | kIOS kIOS::operator+(const kIOS& other) const {
function Scalar (line 112) | Scalar kIOS::width() const { return obb.width(); }
function Scalar (line 114) | Scalar kIOS::height() const { return obb.height(); }
function Scalar (line 116) | Scalar kIOS::depth() const { return obb.depth(); }
function Scalar (line 118) | Scalar kIOS::volume() const { return obb.volume(); }
function Scalar (line 120) | Scalar kIOS::size() const { return volume(); }
function Scalar (line 122) | Scalar kIOS::distance(const kIOS& other, Vec3s* P, Vec3s* Q) const {
function overlap (line 151) | bool overlap(const Matrix3s& R0, const Vec3s& T0, const kIOS& b1,
function overlap (line 165) | bool overlap(const Matrix3s& R0, const Vec3s& T0, const kIOS& b1,
function Scalar (line 180) | Scalar distance(const Matrix3s& R0, const Vec3s& T0, const kIOS& b1,
function kIOS (line 190) | kIOS translate(const kIOS& bv, const Vec3s& t) {
FILE: src/BVH/BVH_model.cpp
type coal (line 51) | namespace coal {
function NODE_TYPE (line 1101) | NODE_TYPE BVHModel<AABB>::getNodeType() const {
function NODE_TYPE (line 1106) | NODE_TYPE BVHModel<OBB>::getNodeType() const {
function NODE_TYPE (line 1111) | NODE_TYPE BVHModel<RSS>::getNodeType() const {
function NODE_TYPE (line 1116) | NODE_TYPE BVHModel<kIOS>::getNodeType() const {
function NODE_TYPE (line 1121) | NODE_TYPE BVHModel<OBBRSS>::getNodeType() const {
function NODE_TYPE (line 1126) | NODE_TYPE BVHModel<KDOP<16>>::getNodeType() const {
function NODE_TYPE (line 1131) | NODE_TYPE BVHModel<KDOP<18>>::getNodeType() const {
function NODE_TYPE (line 1136) | NODE_TYPE BVHModel<KDOP<24>>::getNodeType() const {
class BVHModel<KDOP<16>> (line 1140) | class BVHModel<KDOP<16>>
class BVHModel<KDOP<18>> (line 1141) | class BVHModel<KDOP<18>>
class BVHModel<KDOP<24>> (line 1142) | class BVHModel<KDOP<24>>
class BVHModel<OBB> (line 1143) | class BVHModel<OBB>
class BVHModel<AABB> (line 1144) | class BVHModel<AABB>
class BVHModel<RSS> (line 1145) | class BVHModel<RSS>
class BVHModel<kIOS> (line 1146) | class BVHModel<kIOS>
class BVHModel<OBBRSS> (line 1147) | class BVHModel<OBBRSS>
FILE: src/BVH/BVH_utility.cpp
type coal (line 43) | namespace coal {
type details (line 45) | namespace details {
function getCovariance (line 191) | void getCovariance(Vec3s* ps, Vec3s* ps2, Triangle32* ts, unsigned int...
function getRadiusAndOriginAndRectangleSize (line 272) | void getRadiusAndOriginAndRectangleSize(Vec3s* ps, Vec3s* ps2, Triangl...
function getExtentAndCenter_pointcloud (line 495) | static inline void getExtentAndCenter_pointcloud(Vec3s* ps, Vec3s* ps2,
function getExtentAndCenter_mesh (line 537) | static inline void getExtentAndCenter_mesh(Vec3s* ps, Vec3s* ps2,
function getExtentAndCenter (line 586) | void getExtentAndCenter(Vec3s* ps, Vec3s* ps2, Triangle32* ts,
function circumCircleComputation (line 595) | void circumCircleComputation(const Vec3s& a, const Vec3s& b, const Vec...
function Scalar (line 609) | static inline Scalar maximumDistance_mesh(Vec3s* ps, Vec3s* ps2, Trian...
function Scalar (line 642) | static inline Scalar maximumDistance_pointcloud(Vec3s* ps, Vec3s* ps2,
function Scalar (line 667) | Scalar maximumDistance(Vec3s* ps, Vec3s* ps2, Triangle32* ts,
FILE: src/BVH/BV_fitter.cpp
type coal (line 44) | namespace coal {
function axisFromEigen (line 50) | static inline void axisFromEigen(Vec3s eigenV[3], Scalar eigenS[3],
type OBB_fit_functions (line 78) | namespace OBB_fit_functions {
function fit1 (line 80) | void fit1(Vec3s* ps, OBB& bv) {
function fit2 (line 86) | void fit2(Vec3s* ps, OBB& bv) {
function fit3 (line 100) | void fit3(Vec3s* ps, OBB& bv) {
function fit6 (line 124) | void fit6(Vec3s* ps, OBB& bv) {
function fitn (line 131) | void fitn(Vec3s* ps, unsigned int n, OBB& bv) {
type RSS_fit_functions (line 146) | namespace RSS_fit_functions {
function fit1 (line 147) | void fit1(Vec3s* ps, RSS& bv) {
function fit2 (line 155) | void fit2(Vec3s* ps, RSS& bv) {
function fit3 (line 170) | void fit3(Vec3s* ps, RSS& bv) {
function fit6 (line 195) | void fit6(Vec3s* ps, RSS& bv) {
function fitn (line 202) | void fitn(Vec3s* ps, unsigned int n, RSS& bv) {
type kIOS_fit_functions (line 218) | namespace kIOS_fit_functions {
function fit1 (line 220) | void fit1(Vec3s* ps, kIOS& bv) {
function fit2 (line 230) | void fit2(Vec3s* ps, kIOS& bv) {
function fit3 (line 265) | void fit3(Vec3s* ps, kIOS& bv) {
function fitn (line 308) | void fitn(Vec3s* ps, unsigned int n, kIOS& bv) {
type OBBRSS_fit_functions (line 377) | namespace OBBRSS_fit_functions {
function fit1 (line 378) | void fit1(Vec3s* ps, OBBRSS& bv) {
function fit2 (line 383) | void fit2(Vec3s* ps, OBBRSS& bv) {
function fit3 (line 388) | void fit3(Vec3s* ps, OBBRSS& bv) {
function fitn (line 393) | void fitn(Vec3s* ps, unsigned int n, OBBRSS& bv) {
function fit (line 401) | void fit(Vec3s* ps, unsigned int n, OBB& bv) {
function fit (line 421) | void fit(Vec3s* ps, unsigned int n, RSS& bv) {
function fit (line 438) | void fit(Vec3s* ps, unsigned int n, kIOS& bv) {
function fit (line 455) | void fit(Vec3s* ps, unsigned int n, OBBRSS& bv) {
function fit (line 472) | void fit(Vec3s* ps, unsigned int n, AABB& bv) {
function OBB (line 480) | OBB BVFitter<OBB>::fit(unsigned int* primitive_indices,
function OBBRSS (line 501) | OBBRSS BVFitter<OBBRSS>::fit(unsigned int* primitive_indices,
function RSS (line 533) | RSS BVFitter<RSS>::fit(unsigned int* primitive_indices,
function kIOS (line 562) | kIOS BVFitter<kIOS>::fit(unsigned int* primitive_indices,
function AABB (line 643) | AABB BVFitter<AABB>::fit(unsigned int* primitive_indices,
FILE: src/BVH/BV_splitter.cpp
type coal (line 40) | namespace coal {
function computeSplitVector (line 43) | void computeSplitVector(const BV& bv, Vec3s& split_vector) {
function computeSplitValue_bvcenter (line 86) | void computeSplitValue_bvcenter(const BV& bv, Scalar& split_value) {
function computeSplitValue_mean (line 92) | void computeSplitValue_mean(const BV&, Vec3s* vertices, Triangle32* tr...
function computeSplitValue_median (line 120) | void computeSplitValue_median(const BV&, Vec3s* vertices, Triangle32* ...
class BVSplitter<RSS> (line 279) | class BVSplitter<RSS>
class BVSplitter<OBBRSS> (line 280) | class BVSplitter<OBBRSS>
class BVSplitter<OBB> (line 281) | class BVSplitter<OBB>
class BVSplitter<kIOS> (line 282) | class BVSplitter<kIOS>
FILE: src/broadphase/broadphase_SSaP.cpp
type coal (line 41) | namespace coal {
type SortByXLow (line 44) | struct SortByXLow {
type SortByYLow (line 52) | struct SortByYLow {
type SortByZLow (line 60) | struct SortByZLow {
function DummyCollisionObject (line 68) | class COAL_DLLAPI DummyCollisionObject : public CollisionObject {
function computeLocalAABB (line 75) | void computeLocalAABB() {}
FILE: src/broadphase/broadphase_SaP.cpp
type coal (line 41) | namespace coal {
function Vec3s (line 799) | const Vec3s& SaPCollisionManager::EndPoint::getVal() const {
function Vec3s (line 807) | Vec3s& SaPCollisionManager::EndPoint::getVal() {
function Scalar (line 815) | Scalar SaPCollisionManager::EndPoint::getVal(int i) const {
function Scalar (line 823) | Scalar& SaPCollisionManager::EndPoint::getVal(int i) {
FILE: src/broadphase/broadphase_bruteforce.cpp
type coal (line 44) | namespace coal {
FILE: src/broadphase/broadphase_collision_manager.cpp
type coal (line 40) | namespace coal {
type detail (line 42) | namespace detail {
type CollisionCallBackFunctorWrapper (line 43) | struct CollisionCallBackFunctorWrapper : CollisionCallBackBase {
method CollisionCallBackFunctorWrapper (line 44) | CollisionCallBackFunctorWrapper(const CollisionCallBackFunctor& fu...
method init (line 47) | void init() override {}
method collide (line 49) | bool collide(CollisionObject* o1, CollisionObject* o2) override {
type DistanceCallBackFunctorWrapper (line 56) | struct DistanceCallBackFunctorWrapper : DistanceCallBackBase {
method DistanceCallBackFunctorWrapper (line 57) | DistanceCallBackFunctorWrapper(const DistanceCallBackFunctor& func...
method init (line 60) | void init() override {}
method distance (line 62) | bool distance(CollisionObject* o1, CollisionObject* o2,
FILE: src/broadphase/broadphase_dynamic_AABB_tree.cpp
type coal (line 50) | namespace coal {
type detail (line 51) | namespace detail {
type dynamic_AABB_tree (line 53) | namespace dynamic_AABB_tree {
function collisionRecurse_ (line 57) | bool collisionRecurse_(DynamicAABBTreeCollisionManager::DynamicAAB...
function distanceRecurse_ (line 150) | bool distanceRecurse_(DynamicAABBTreeCollisionManager::DynamicAABB...
function collisionRecurse (line 225) | bool collisionRecurse(DynamicAABBTreeCollisionManager::DynamicAABB...
function distanceRecurse (line 237) | bool distanceRecurse(DynamicAABBTreeCollisionManager::DynamicAABBN...
function leafCollide (line 252) | bool leafCollide(CollisionObject* o1, CollisionObject* o2,
function nodeCollide (line 298) | bool nodeCollide(DynamicAABBTreeCollisionManager::DynamicAABBNode*...
function collisionRecurse (line 304) | bool collisionRecurse(DynamicAABBTreeCollisionManager::DynamicAABB...
function collisionRecurse (line 329) | bool collisionRecurse(DynamicAABBTreeCollisionManager::DynamicAABB...
function selfCollisionRecurse (line 361) | bool selfCollisionRecurse(
function distanceRecurse (line 377) | bool distanceRecurse(DynamicAABBTreeCollisionManager::DynamicAABBN...
function distanceRecurse (line 443) | bool distanceRecurse(DynamicAABBTreeCollisionManager::DynamicAABBN...
function selfDistanceRecurse (line 480) | bool selfDistanceRecurse(DynamicAABBTreeCollisionManager::DynamicA...
FILE: src/broadphase/broadphase_dynamic_AABB_tree_array.cpp
type coal (line 43) | namespace coal {
type detail (line 44) | namespace detail {
type dynamic_AABB_tree_array (line 45) | namespace dynamic_AABB_tree_array {
function collisionRecurse_ (line 50) | bool collisionRecurse_(
function distanceRecurse_ (line 148) | bool distanceRecurse_(
function collisionRecurse (line 228) | bool collisionRecurse(
function COAL_DLLAPI (line 265) | inline COAL_DLLAPI bool collisionRecurse(
function selfCollisionRecurse (line 288) | bool selfCollisionRecurse(
function distanceRecurse (line 306) | bool distanceRecurse(
function distanceRecurse (line 386) | bool distanceRecurse(
function selfDistanceRecurse (line 425) | bool selfDistanceRecurse(
function collisionRecurse (line 447) | bool collisionRecurse(
function distanceRecurse (line 461) | bool distanceRecurse(
FILE: src/broadphase/broadphase_interval_tree.cpp
type coal (line 40) | namespace coal {
FILE: src/broadphase/default_broadphase_callbacks.cpp
type coal (line 40) | namespace coal {
function defaultCollisionFunction (line 42) | bool defaultCollisionFunction(CollisionObject* o1, CollisionObject* o2,
function defaultDistanceFunction (line 66) | bool defaultDistanceFunction(CollisionObject* o1, CollisionObject* o2,
FILE: src/broadphase/detail/interval_tree.cpp
type coal (line 45) | namespace coal {
type detail (line 46) | namespace detail {
function IntervalTreeNode (line 183) | IntervalTreeNode* IntervalTree::insert(SimpleInterval* new_interval) {
function IntervalTreeNode (line 234) | IntervalTreeNode* IntervalTree::getSuccessor(IntervalTreeNode* x) co...
function IntervalTreeNode (line 252) | IntervalTreeNode* IntervalTree::getPredecessor(IntervalTreeNode* x) ...
function IntervalTreeNode (line 347) | IntervalTreeNode* IntervalTree::recursiveSearch(IntervalTreeNode* node,
function SimpleInterval (line 362) | SimpleInterval* IntervalTree::deleteNode(IntervalTreeNode* z) {
function overlap (line 412) | bool overlap(Scalar a1, Scalar a2, Scalar b1, Scalar b2) {
FILE: src/broadphase/detail/interval_tree_node.cpp
type coal (line 46) | namespace coal {
type detail (line 47) | namespace detail {
FILE: src/broadphase/detail/morton-inl.h
function namespace (line 44) | namespace coal { /// @cond IGNORE
FILE: src/broadphase/detail/morton.cpp
type coal (line 41) | namespace coal {
type detail (line 44) | namespace detail {
function morton_code (line 47) | uint32_t morton_code(uint32_t x, uint32_t y, uint32_t z) {
function morton_code60 (line 67) | uint64_t morton_code60(uint32_t x, uint32_t y, uint32_t z) {
FILE: src/broadphase/detail/simple_interval.cpp
type coal (line 44) | namespace coal {
type detail (line 45) | namespace detail {
FILE: src/broadphase/detail/spatial_hash.cpp
type coal (line 44) | namespace coal {
type detail (line 45) | namespace detail {
FILE: src/collision.cpp
type coal (line 45) | namespace coal {
function CollisionFunctionMatrix (line 47) | CollisionFunctionMatrix& getCollisionFunctionLookTable() {
function collide (line 63) | std::size_t collide(const CollisionObject* o1, const CollisionObject* o2,
function collide (line 70) | std::size_t collide(const CollisionGeometry* o1, const Transform3s& tf1,
FILE: src/collision_data.cpp
type coal (line 41) | namespace coal {
FILE: src/collision_func_matrix.cpp
type coal (line 47) | namespace coal {
function OctreeCollide (line 52) | std::size_t OctreeCollide(const CollisionGeometry* o1, const Transform...
type details (line 77) | namespace details {
type bvh_shape_traits (line 79) | struct bvh_shape_traits {
function orientedMeshCollide (line 191) | std::size_t orientedMeshCollide(const CollisionGeometry* o1,
function BVHShapeCollider (line 100) | struct COAL_LOCAL BVHShapeCollider {
function HeightFieldShapeCollider (line 167) | struct COAL_LOCAL HeightFieldShapeCollider {
type details (line 189) | namespace details {
type bvh_shape_traits (line 79) | struct bvh_shape_traits {
function orientedMeshCollide (line 191) | std::size_t orientedMeshCollide(const CollisionGeometry* o1,
function BVHCollide (line 212) | std::size_t BVHCollide(const CollisionGeometry* o1, const Transform3s&...
function BVHCollide (line 274) | std::size_t BVHCollide(const CollisionGeometry* o1, const Transform3s&...
FILE: src/collision_node.cpp
type coal (line 41) | namespace coal {
function checkResultLowerBound (line 43) | void checkResultLowerBound(const CollisionResult& result,
function collide (line 61) | void collide(CollisionTraversalNodeBase* node, const CollisionRequest&...
function distance (line 78) | void distance(DistanceTraversalNodeBase* node, BVHFrontList* front_list,
FILE: src/collision_node.h
function namespace (line 50) | namespace coal {
FILE: src/collision_object.cpp
type coal (line 40) | namespace coal {
FILE: src/collision_utility.cpp
type coal (line 20) | namespace coal {
type details (line 21) | namespace details {
function CollisionGeometry (line 24) | inline CollisionGeometry* extractBVHtpl(const CollisionGeometry* model,
function CollisionGeometry (line 41) | CollisionGeometry* extractBVH(const CollisionGeometry* model,
function CollisionGeometry (line 66) | CollisionGeometry* extract(const CollisionGeometry* model,
FILE: src/contact_patch.cpp
type coal (line 42) | namespace coal {
function ContactPatchFunctionMatrix (line 44) | ContactPatchFunctionMatrix& getContactPatchFunctionLookTable() {
function computeContactPatch (line 49) | void computeContactPatch(const CollisionGeometry* o1, const Transform3...
function computeContactPatch (line 101) | void computeContactPatch(const CollisionObject* o1, const CollisionObj...
FILE: src/contact_patch/contact_patch_simplifier.cpp
type coal (line 46) | namespace coal {
function T (line 145) | inline T clamp(T val, T min_val, T max_val) {
function Scalar (line 155) | inline Scalar double_triangle_area(const Vec2s& a, const Vec2s& b,
function Scalar (line 162) | Scalar compute_triangle_area(const std::vector<Vec2s>& pts,
function Scalar (line 176) | Scalar compute_triangle_area_kgon(const std::vector<Vec2s>& pts, //
function Scalar (line 189) | Scalar compute_rooted_kgon(const std::vector<Vec2s>& pts, int root, in...
function solve_recursive (line 255) | void solve_recursive(const std::vector<Vec2s>& pts, int k, int root_st...
FILE: src/contact_patch/contact_patch_solver.cpp
type coal (line 39) | namespace coal {
type details (line 41) | namespace details {
function getShapeSupportSetTpl (line 46) | void getShapeSupportSetTpl(const ShapeBase* shape, SupportSet& suppo...
function getConvexBaseSupportSetTpl (line 58) | void getConvexBaseSupportSetTpl(const ShapeBase* shape, SupportSet& ...
FILE: src/contact_patch/polygon_convex_hull.cpp
type coal (line 6) | namespace coal {
function computePolygonConvexHull (line 7) | void computePolygonConvexHull(const std::vector<Vec2s>& cloud,
FILE: src/contact_patch_func_matrix.cpp
type coal (line 42) | namespace coal {
type BVHShapeComputeContactPatch (line 45) | struct BVHShapeComputeContactPatch {
method run (line 46) | static void run(const CollisionGeometry* o1, const Transform3s& tf1,
type HeightFieldShapeComputeContactPatch (line 70) | struct HeightFieldShapeComputeContactPatch {
method run (line 71) | static void run(const CollisionGeometry* o1, const Transform3s& tf1,
type BVHComputeContactPatch (line 95) | struct BVHComputeContactPatch {
method run (line 96) | static void run(const CollisionGeometry* o1, const Transform3s& tf1,
function COAL_LOCAL (line 119) | COAL_LOCAL void contact_patch_function_not_implemented(
FILE: src/distance.cpp
type coal (line 45) | namespace coal {
function DistanceFunctionMatrix (line 47) | DistanceFunctionMatrix& getDistanceFunctionLookTable() {
function Scalar (line 52) | Scalar distance(const CollisionObject* o1, const CollisionObject* o2,
function Scalar (line 59) | Scalar distance(const CollisionGeometry* o1, const Transform3s& tf1,
function Scalar (line 139) | Scalar ComputeDistance::run(const Transform3s& tf1, const Transform3s&...
function Scalar (line 161) | Scalar ComputeDistance::operator()(const Transform3s& tf1,
FILE: src/distance/box_halfspace.cpp
type coal (line 47) | namespace coal {
type GJKSolver (line 48) | struct GJKSolver
type internal (line 50) | namespace internal {
function Scalar (line 53) | Scalar ShapeShapeDistance<Box, Halfspace>(const CollisionGeometry* o1,
function Scalar (line 70) | Scalar ShapeShapeDistance<Halfspace, Box>(const CollisionGeometry* o1,
FILE: src/distance/box_plane.cpp
type coal (line 47) | namespace coal {
type GJKSolver (line 48) | struct GJKSolver
type internal (line 50) | namespace internal {
function Scalar (line 52) | Scalar ShapeShapeDistance<Box, Plane>(const CollisionGeometry* o1,
function Scalar (line 68) | Scalar ShapeShapeDistance<Plane, Box>(const CollisionGeometry* o1,
FILE: src/distance/box_sphere.cpp
type coal (line 47) | namespace coal {
type GJKSolver (line 48) | struct GJKSolver
type internal (line 50) | namespace internal {
function Scalar (line 52) | Scalar ShapeShapeDistance<Box, Sphere>(const CollisionGeometry* o1,
function Scalar (line 65) | Scalar ShapeShapeDistance<Sphere, Box>(const CollisionGeometry* o1,
FILE: src/distance/capsule_capsule.cpp
type coal (line 48) | namespace coal {
type GJKSolver (line 49) | struct GJKSolver
type internal (line 51) | namespace internal {
function Scalar (line 53) | Scalar clamp(const Scalar& num, const Scalar& denom) {
function clamped_linear (line 64) | void clamped_linear(Vec3s& a_sd, const Vec3s& a, const Scalar& s_n,
function Scalar (line 82) | Scalar ShapeShapeDistance<Capsule, Capsule>(
FILE: src/distance/capsule_halfspace.cpp
type coal (line 47) | namespace coal {
type GJKSolver (line 48) | struct GJKSolver
type internal (line 50) | namespace internal {
function Scalar (line 52) | Scalar ShapeShapeDistance<Capsule, Halfspace>(
function Scalar (line 67) | Scalar ShapeShapeDistance<Halfspace, Capsule>(
FILE: src/distance/capsule_plane.cpp
type coal (line 47) | namespace coal {
type GJKSolver (line 48) | struct GJKSolver
type internal (line 50) | namespace internal {
function Scalar (line 52) | Scalar ShapeShapeDistance<Capsule, Plane>(const CollisionGeometry* o1,
function Scalar (line 69) | Scalar ShapeShapeDistance<Plane, Capsule>(const CollisionGeometry* o1,
FILE: src/distance/cone_halfspace.cpp
type coal (line 47) | namespace coal {
type GJKSolver (line 48) | struct GJKSolver
type internal (line 50) | namespace internal {
function Scalar (line 52) | Scalar ShapeShapeDistance<Cone, Halfspace>(
function Scalar (line 67) | Scalar ShapeShapeDistance<Halfspace, Cone>(
FILE: src/distance/cone_plane.cpp
type coal (line 47) | namespace coal {
type GJKSolver (line 48) | struct GJKSolver
type internal (line 50) | namespace internal {
function Scalar (line 52) | Scalar ShapeShapeDistance<Cone, Plane>(const CollisionGeometry* o1,
function Scalar (line 68) | Scalar ShapeShapeDistance<Plane, Cone>(const CollisionGeometry* o1,
FILE: src/distance/convex_halfspace.cpp
type coal (line 44) | namespace coal {
type internal (line 46) | namespace internal {
FILE: src/distance/convex_plane.cpp
type coal (line 44) | namespace coal {
type internal (line 46) | namespace internal {
FILE: src/distance/cylinder_halfspace.cpp
type coal (line 47) | namespace coal {
type GJKSolver (line 48) | struct GJKSolver
type internal (line 50) | namespace internal {
function Scalar (line 52) | Scalar ShapeShapeDistance<Cylinder, Halfspace>(
function Scalar (line 67) | Scalar ShapeShapeDistance<Halfspace, Cylinder>(
FILE: src/distance/cylinder_plane.cpp
type coal (line 47) | namespace coal {
type GJKSolver (line 48) | struct GJKSolver
type internal (line 50) | namespace internal {
function Scalar (line 52) | Scalar ShapeShapeDistance<Cylinder, Plane>(
function Scalar (line 67) | Scalar ShapeShapeDistance<Plane, Cylinder>(
FILE: src/distance/ellipsoid_halfspace.cpp
type coal (line 45) | namespace coal {
type GJKSolver (line 46) | struct GJKSolver
type internal (line 48) | namespace internal {
function Scalar (line 50) | Scalar ShapeShapeDistance<Ellipsoid, Halfspace>(
function Scalar (line 65) | Scalar ShapeShapeDistance<Halfspace, Ellipsoid>(
FILE: src/distance/ellipsoid_plane.cpp
type coal (line 44) | namespace coal {
type GJKSolver (line 45) | struct GJKSolver
type internal (line 47) | namespace internal {
function Scalar (line 49) | Scalar ShapeShapeDistance<Ellipsoid, Plane>(
function Scalar (line 64) | Scalar ShapeShapeDistance<Plane, Ellipsoid>(
FILE: src/distance/halfspace_halfspace.cpp
type coal (line 44) | namespace coal {
type GJKSolver (line 45) | struct GJKSolver
type internal (line 47) | namespace internal {
function Scalar (line 49) | Scalar ShapeShapeDistance<Halfspace, Halfspace>(
FILE: src/distance/halfspace_plane.cpp
type coal (line 44) | namespace coal {
type GJKSolver (line 45) | struct GJKSolver
type internal (line 47) | namespace internal {
function Scalar (line 49) | Scalar ShapeShapeDistance<Halfspace, Plane>(
function Scalar (line 61) | Scalar ShapeShapeDistance<Plane, Halfspace>(
FILE: src/distance/plane_plane.cpp
type coal (line 44) | namespace coal {
type GJKSolver (line 45) | struct GJKSolver
type internal (line 47) | namespace internal {
function Scalar (line 49) | Scalar ShapeShapeDistance<Plane, Plane>(const CollisionGeometry* o1,
FILE: src/distance/sphere_capsule.cpp
type coal (line 44) | namespace coal {
type GJKSolver (line 45) | struct GJKSolver
type internal (line 47) | namespace internal {
function Scalar (line 49) | Scalar ShapeShapeDistance<Sphere, Capsule>(
function Scalar (line 61) | Scalar ShapeShapeDistance<Capsule, Sphere>(
FILE: src/distance/sphere_cylinder.cpp
type coal (line 47) | namespace coal {
type GJKSolver (line 48) | struct GJKSolver
type internal (line 50) | namespace internal {
function Scalar (line 52) | Scalar ShapeShapeDistance<Sphere, Cylinder>(
function Scalar (line 64) | Scalar ShapeShapeDistance<Cylinder, Sphere>(
FILE: src/distance/sphere_halfspace.cpp
type coal (line 47) | namespace coal {
type GJKSolver (line 48) | struct GJKSolver
type internal (line 50) | namespace internal {
function Scalar (line 52) | Scalar ShapeShapeDistance<Sphere, Halfspace>(
function Scalar (line 67) | Scalar ShapeShapeDistance<Halfspace, Sphere>(
FILE: src/distance/sphere_plane.cpp
type coal (line 47) | namespace coal {
type GJKSolver (line 48) | struct GJKSolver
type internal (line 50) | namespace internal {
function Scalar (line 52) | Scalar ShapeShapeDistance<Sphere, Plane>(const CollisionGeometry* o1,
function Scalar (line 68) | Scalar ShapeShapeDistance<Plane, Sphere>(const CollisionGeometry* o1,
FILE: src/distance/sphere_sphere.cpp
type coal (line 53) | namespace coal {
type GJKSolver (line 54) | struct GJKSolver
type internal (line 56) | namespace internal {
function Scalar (line 58) | Scalar ShapeShapeDistance<Sphere, Sphere>(const CollisionGeometry* o1,
FILE: src/distance/triangle_halfspace.cpp
type coal (line 44) | namespace coal {
type internal (line 46) | namespace internal {
function Scalar (line 48) | Scalar ShapeShapeDistance<TriangleP, Halfspace>(
function Scalar (line 63) | Scalar ShapeShapeDistance<Halfspace, TriangleP>(
FILE: src/distance/triangle_plane.cpp
type coal (line 44) | namespace coal {
type internal (line 46) | namespace internal {
function Scalar (line 48) | Scalar ShapeShapeDistance<TriangleP, Plane>(
function Scalar (line 63) | Scalar ShapeShapeDistance<Plane, TriangleP>(
FILE: src/distance/triangle_sphere.cpp
type coal (line 44) | namespace coal {
type internal (line 46) | namespace internal {
function Scalar (line 48) | Scalar ShapeShapeDistance<TriangleP, Sphere>(
function Scalar (line 63) | Scalar ShapeShapeDistance<Sphere, TriangleP>(
FILE: src/distance/triangle_triangle.cpp
type coal (line 44) | namespace coal {
type internal (line 46) | namespace internal {
function Scalar (line 48) | Scalar ShapeShapeDistance<TriangleP, TriangleP>(
FILE: src/distance_func_matrix.cpp
type coal (line 46) | namespace coal {
function Scalar (line 51) | Scalar Distance(const CollisionGeometry* o1, const Transform3s& tf1,
function COAL_LOCAL (line 69) | COAL_LOCAL Scalar distance_function_not_implemented(
function BVHShapeDistancer (line 86) | struct COAL_LOCAL BVHShapeDistancer {
type details (line 107) | namespace details {
function Scalar (line 111) | Scalar orientedBVHShapeDistance(const CollisionGeometry* o1,
function Scalar (line 223) | Scalar orientedMeshDistance(const CollisionGeometry* o1, const Trans...
type COAL_LOCAL (line 132) | struct COAL_LOCAL
function Scalar (line 133) | static Scalar distance(const CollisionGeometry* o1, const Transform3s&...
type COAL_LOCAL (line 145) | struct COAL_LOCAL
function Scalar (line 146) | static Scalar distance(const CollisionGeometry* o1, const Transform3s&...
type COAL_LOCAL (line 158) | struct COAL_LOCAL
function Scalar (line 159) | static Scalar distance(const CollisionGeometry* o1, const Transform3s&...
function HeightFieldShapeDistancer (line 171) | struct COAL_LOCAL HeightFieldShapeDistancer {
function Scalar (line 201) | Scalar BVHDistance(const CollisionGeometry* o1, const Transform3s& tf1,
type details (line 221) | namespace details {
function Scalar (line 111) | Scalar orientedBVHShapeDistance(const CollisionGeometry* o1,
function Scalar (line 223) | Scalar orientedMeshDistance(const CollisionGeometry* o1, const Trans...
function Scalar (line 241) | Scalar BVHDistance<RSS>(const CollisionGeometry* o1, const Transform3s...
function Scalar (line 250) | Scalar BVHDistance<kIOS>(const CollisionGeometry* o1, const Transform3...
function Scalar (line 259) | Scalar BVHDistance<OBBRSS>(const CollisionGeometry* o1, const Transfor...
function Scalar (line 268) | Scalar BVHDistance(const CollisionGeometry* o1, const Transform3s& tf1,
FILE: src/hfield.cpp
type coal (line 48) | namespace coal {
function NODE_TYPE (line 51) | NODE_TYPE HeightField<AABB>::getNodeType() const {
function NODE_TYPE (line 56) | NODE_TYPE HeightField<OBB>::getNodeType() const {
function NODE_TYPE (line 61) | NODE_TYPE HeightField<RSS>::getNodeType() const {
function NODE_TYPE (line 66) | NODE_TYPE HeightField<kIOS>::getNodeType() const {
function NODE_TYPE (line 71) | NODE_TYPE HeightField<OBBRSS>::getNodeType() const {
function NODE_TYPE (line 76) | NODE_TYPE HeightField<KDOP<16> >::getNodeType() const {
function NODE_TYPE (line 81) | NODE_TYPE HeightField<KDOP<18> >::getNodeType() const {
function NODE_TYPE (line 86) | NODE_TYPE HeightField<KDOP<24> >::getNodeType() const {
class HeightField<OBB> (line 93) | class HeightField<OBB>
class HeightField<AABB> (line 94) | class HeightField<AABB>
class HeightField<RSS> (line 95) | class HeightField<RSS>
class HeightField<OBBRSS> (line 97) | class HeightField<OBBRSS>
FILE: src/intersect.cpp
type coal (line 46) | namespace coal {
function Scalar (line 156) | Scalar TriangleDistance::sqrTriDistance(const Vec3s S[3], const Vec3s ...
function Scalar (line 370) | Scalar TriangleDistance::sqrTriDistance(const Vec3s& S1, const Vec3s& S2,
function Scalar (line 386) | Scalar TriangleDistance::sqrTriDistance(const Vec3s S[3], const Vec3s ...
function Scalar (line 397) | Scalar TriangleDistance::sqrTriDistance(const Vec3s S[3], const Vec3s ...
function Scalar (line 408) | Scalar TriangleDistance::sqrTriDistance(const Vec3s& S1, const Vec3s& S2,
function Scalar (line 420) | Scalar TriangleDistance::sqrTriDistance(const Vec3s& S1, const Vec3s& S2,
FILE: src/math/transform.cpp
type coal (line 40) | namespace coal {
function relativeTransform (line 42) | void relativeTransform(const Transform3s& tf1, const Transform3s& tf2,
function relativeTransform2 (line 47) | void relativeTransform2(const Transform3s& tf1, const Transform3s& tf2,
FILE: src/mesh_loader/assimp.cpp
type coal (line 57) | namespace coal {
type internal (line 59) | namespace internal {
function recurseBuildMesh (line 109) | unsigned recurseBuildMesh(const coal::Vec3s& scale, const aiScene* s...
function buildMesh (line 158) | void buildMesh(const coal::Vec3s& scale, const aiScene* scene,
FILE: src/mesh_loader/loader.cpp
type coal (line 48) | namespace coal {
function BVHModelPtr_t (line 61) | BVHModelPtr_t _load(const std::string& filename, const Vec3s& scale) {
function BVHModelPtr_t (line 67) | BVHModelPtr_t MeshLoader::load(const std::string& filename,
function CollisionGeometryPtr_t (line 92) | CollisionGeometryPtr_t MeshLoader::loadOctree(const std::string& filen...
function BVHModelPtr_t (line 102) | BVHModelPtr_t CachedMeshLoader::load(const std::string& filename,
FILE: src/narrowphase/details.h
function namespace (line 45) | namespace coal {
FILE: src/narrowphase/gjk.cpp
type coal (line 48) | namespace coal {
type details (line 50) | namespace details {
function Vec3ps (line 72) | Vec3ps GJK::getGuessFromSimplex() const { return ray; }
type details (line 74) | namespace details {
function getClosestPoints (line 96) | void getClosestPoints(const GJK::Simplex& simplex, Vec3ps& w0, Vec...
function inflate (line 162) | void inflate(const MinkowskiDiff& shape, const Vec3ps& normal, Vec...
function originToPoint (line 502) | inline void originToPoint(const GJK::Simplex& current, GJK::vertex_i...
function originToSegment (line 510) | inline void originToSegment(const GJK::Simplex& current, GJK::vertex...
function originToTriangle (line 526) | inline bool originToTriangle(const GJK::Simplex& current, GJK::verte...
FILE: src/narrowphase/minkowski_difference.cpp
type coal (line 42) | namespace coal {
type details (line 43) | namespace details {
function getSupportTpl (line 48) | void getSupportTpl(const Shape0* s0, const Shape1* s1, const Matrix3...
function getSupportFuncTpl (line 67) | void getSupportFuncTpl(const MinkowskiDiff& md, const Vec3s& dir,
function makeGetSupportFunction1 (line 78) | MinkowskiDiff::GetSupportFunction makeGetSupportFunction1(
function makeGetSupportFunction0 (line 183) | MinkowskiDiff::GetSupportFunction makeGetSupportFunction0(
function getNormalizeSupportDirection (line 264) | bool getNormalizeSupportDirection(const ShapeBase* shape) {
function getNormalizeSupportDirectionFromShapes (line 299) | void getNormalizeSupportDirectionFromShapes(const ShapeBase* shape0,
FILE: src/narrowphase/support_functions.cpp
type coal (line 42) | namespace coal {
type details (line 43) | namespace details {
function Vec3s (line 51) | Vec3s getSupport(const ShapeBase* shape, const Vec3s& dir, int& hint) {
function getShapeSupport (line 112) | void getShapeSupport(const TriangleP* triangle, const Vec3s& dir,
function getShapeSupport (line 140) | void getShapeSupport(const Box* box, const Vec3s& dir, Vec3s& support,
function getShapeSupport (line 161) | void getShapeSupport(const Sphere* sphere, const Vec3s& dir, Vec3s& ...
function getShapeSupport (line 177) | void getShapeSupport(const Ellipsoid* ellipsoid, const Vec3s& dir,
function getShapeSupport (line 198) | void getShapeSupport(const Capsule* capsule, const Vec3s& dir, Vec3s...
function getShapeSupport (line 218) | void getShapeSupport(const Cone* cone, const Vec3s& dir, Vec3s& supp...
function getShapeSupport (line 268) | void getShapeSupport(const Cylinder* cylinder, const Vec3s& dir, Vec...
function getShapeSupportLog (line 308) | void getShapeSupportLog(const ConvexBaseTpl<IndexType>* convex,
function getShapeSupportLinear (line 387) | void getShapeSupportLinear(const ConvexBaseTpl<IndexType>* convex,
function getShapeSupport (line 411) | void getShapeSupport(const ConvexBaseTpl<IndexType>* convex, const V...
function getShapeSupport (line 431) | void getShapeSupport(const SmallConvex<IndexType>* convex, const Vec...
function getShapeSupport (line 443) | void getShapeSupport(const LargeConvex<IndexType>* convex, const Vec...
function getSupportSet (line 460) | void getSupportSet(const ShapeBase* shape, SupportSet& support_set, ...
function getShapeSupportSet (line 518) | void getShapeSupportSet(const TriangleP* triangle, SupportSet& suppo...
function getShapeSupportSet (line 565) | void getShapeSupportSet(const Box* box, SupportSet& support_set,
function getShapeSupportSet (line 607) | void getShapeSupportSet(const Sphere* sphere, SupportSet& support_set,
function getShapeSupportSet (line 623) | void getShapeSupportSet(const Ellipsoid* ellipsoid, SupportSet& supp...
function getShapeSupportSet (line 638) | void getShapeSupportSet(const Capsule* capsule, SupportSet& support_...
function getShapeSupportSet (line 682) | void getShapeSupportSet(const Cone* cone, SupportSet& support_set,
function getShapeSupportSet (line 753) | void getShapeSupportSet(const Cylinder* cylinder, SupportSet& suppor...
function getShapeSupportSetLinear (line 815) | void getShapeSupportSetLinear(const ConvexBaseTpl<IndexType>* convex,
function convexSupportSetRecurse (line 851) | void convexSupportSetRecurse(const ConvexBaseTpl<IndexType>* convex,
function getShapeSupportSetLog (line 892) | void getShapeSupportSetLog(const ConvexBaseTpl<IndexType>* convex,
function getShapeSupportSet (line 922) | void getShapeSupportSet(const ConvexBaseTpl<IndexType>* convex,
function getShapeSupportSet (line 941) | void getShapeSupportSet(const SmallConvex<IndexType>* convex,
function getShapeSupportSet (line 954) | void getShapeSupportSet(const LargeConvex<IndexType>* convex,
function COAL_DLLAPI (line 966) | COAL_DLLAPI void computeSupportSetConvexHull(const std::vector<Vec2s...
FILE: src/octree.cpp
type coal (line 39) | namespace coal {
type internal (line 40) | namespace internal {
type Neighbors (line 41) | struct Neighbors {
method Neighbors (line 43) | Neighbors() : value(0) {}
method minusX (line 44) | bool minusX() const { return value & 0x1; }
method plusX (line 45) | bool plusX() const { return value & 0x2; }
method minusY (line 46) | bool minusY() const { return value & 0x4; }
method plusY (line 47) | bool plusY() const { return value & 0x8; }
method minusZ (line 48) | bool minusZ() const { return value & 0x10; }
method plusZ (line 49) | bool plusZ() const { return value & 0x20; }
method hasNeighboordMinusX (line 50) | void hasNeighboordMinusX() { value |= 0x1; }
method hasNeighboordPlusX (line 51) | void hasNeighboordPlusX() { value |= 0x2; }
method hasNeighboordMinusY (line 52) | void hasNeighboordMinusY() { value |= 0x4; }
method hasNeighboordPlusY (line 53) | void hasNeighboordPlusY() { value |= 0x8; }
method hasNeighboordMinusZ (line 54) | void hasNeighboordMinusZ() { value |= 0x10; }
method hasNeighboordPlusZ (line 55) | void hasNeighboordPlusZ() { value |= 0x20; }
function computeNeighbors (line 58) | void computeNeighbors(const std::vector<Vec6s>& boxes,
function OcTreePtr_t (line 197) | OcTreePtr_t makeOctree(
FILE: src/shape/geometric_shapes.cpp
type coal (line 58) | namespace coal {
FILE: src/shape/geometric_shapes_utility.cpp
type coal (line 42) | namespace coal {
type details (line 44) | namespace details {
function getBoundVertices (line 46) | std::vector<Vec3s> getBoundVertices(const Box& box, const Transform3...
function getBoundVertices (line 64) | std::vector<Vec3s> getBoundVertices(const Sphere& sphere,
function getBoundVertices (line 89) | std::vector<Vec3s> getBoundVertices(const Ellipsoid& ellipsoid,
function getBoundVertices (line 123) | std::vector<Vec3s> getBoundVertices(const Capsule& capsule,
function getBoundVertices (line 179) | std::vector<Vec3s> getBoundVertices(const Cone& cone, const Transfor...
function getBoundVertices (line 199) | std::vector<Vec3s> getBoundVertices(const Cylinder& cylinder,
function getBoundVertices (line 225) | std::vector<Vec3s> getBoundVertices(const TriangleP& triangle,
function Halfspace (line 237) | Halfspace transform(const Halfspace& a, const Transform3s& tf) {
function Plane (line 252) | Plane transform(const Plane& a, const Transform3s& tf) {
function transformToHalfspaces (line 267) | std::array<Halfspace, 2> transformToHalfspaces(const Plane& a,
function computeAABBConvex (line 357) | void computeAABBConvex(const ConvexBaseTpl<IndexType>& s, const Transf...
function computeOBBConvex (line 529) | void computeOBBConvex(const ConvexBaseTpl<IndexType>& s, const Transfo...
function constructBox (line 1024) | void constructBox(const AABB& bv, Box& box, Transform3s& tf) {
function constructBox (line 1029) | void constructBox(const OBB& bv, Box& box, Transform3s& tf) {
function constructBox (line 1034) | void constructBox(const OBBRSS& bv, Box& box, Transform3s& tf) {
function constructBox (line 1039) | void constructBox(const kIOS& bv, Box& box, Transform3s& tf) {
function constructBox (line 1044) | void constructBox(const RSS& bv, Box& box, Transform3s& tf) {
function constructBox (line 1049) | void constructBox(const KDOP<16>& bv, Box& box, Transform3s& tf) {
function constructBox (line 1054) | void constructBox(const KDOP<18>& bv, Box& box, Transform3s& tf) {
function constructBox (line 1059) | void constructBox(const KDOP<24>& bv, Box& box, Transform3s& tf) {
function constructBox (line 1064) | void constructBox(const AABB& bv, const Transform3s& tf_bv, Box& box,
function constructBox (line 1070) | void constructBox(const OBB& bv, const Transform3s& tf_bv, Box& box,
function constructBox (line 1076) | void constructBox(const OBBRSS& bv, const Transform3s& tf_bv, Box& box,
function constructBox (line 1082) | void constructBox(const kIOS& bv, const Transform3s& tf_bv, Box& box,
function constructBox (line 1088) | void constructBox(const RSS& bv, const Transform3s& tf_bv, Box& box,
function constructBox (line 1094) | void constructBox(const KDOP<16>& bv, const Transform3s& tf_bv, Box& box,
function constructBox (line 1100) | void constructBox(const KDOP<18>& bv, const Transform3s& tf_bv, Box& box,
function constructBox (line 1106) | void constructBox(const KDOP<24>& bv, const Transform3s& tf_bv, Box& box,
FILE: src/traits_traversal.h
function namespace (line 16) | namespace coal {
FILE: src/traversal/traversal_recurse.cpp
type coal (line 42) | namespace coal {
function collisionRecurse (line 43) | void collisionRecurse(CollisionTraversalNodeBase* node, unsigned int b1,
function collisionNonRecurse (line 86) | void collisionNonRecurse(CollisionTraversalNodeBase* node,
function distanceRecurse (line 151) | void distanceRecurse(DistanceTraversalNodeBase* node, unsigned int b1,
function BVT (line 204) | struct COAL_LOCAL BVT {
function BVT_Comparer (line 213) | struct COAL_LOCAL BVT_Comparer {
function BVTQ (line 219) | struct COAL_LOCAL BVTQ {
function distanceQueueRecurse (line 240) | void distanceQueueRecurse(DistanceTraversalNodeBase* node, unsigned in...
function propagateBVHFrontListCollisionRecurse (line 306) | void propagateBVHFrontListCollisionRecurse(CollisionTraversalNodeBase*...
FILE: test/accelerated_gjk.cpp
function BOOST_AUTO_TEST_CASE (line 67) | BOOST_AUTO_TEST_CASE(set_gjk_variant) {
function BOOST_AUTO_TEST_CASE (line 91) | BOOST_AUTO_TEST_CASE(need_nesterov_normalize_support_direction) {
function test_accelerated_gjk (line 109) | void test_accelerated_gjk(const ShapeBase& shape0, const ShapeBase& shap...
function BOOST_AUTO_TEST_CASE (line 196) | BOOST_AUTO_TEST_CASE(ellipsoid_ellipsoid) {
function BOOST_AUTO_TEST_CASE (line 204) | BOOST_AUTO_TEST_CASE(ellipsoid_capsule) {
function BOOST_AUTO_TEST_CASE (line 216) | BOOST_AUTO_TEST_CASE(ellipsoid_box) {
function BOOST_AUTO_TEST_CASE (line 228) | BOOST_AUTO_TEST_CASE(ellipsoid_mesh) {
function BOOST_AUTO_TEST_CASE (line 240) | BOOST_AUTO_TEST_CASE(capsule_mesh) {
function BOOST_AUTO_TEST_CASE (line 254) | BOOST_AUTO_TEST_CASE(capsule_capsule) {
function BOOST_AUTO_TEST_CASE (line 263) | BOOST_AUTO_TEST_CASE(box_box) {
function BOOST_AUTO_TEST_CASE (line 271) | BOOST_AUTO_TEST_CASE(box_mesh) {
function BOOST_AUTO_TEST_CASE (line 285) | BOOST_AUTO_TEST_CASE(mesh_mesh) {
FILE: test/alloca.cpp
function BOOST_AUTO_TEST_CASE (line 13) | BOOST_AUTO_TEST_CASE(copy_std_vector) {
FILE: test/benchmark.cpp
type traits (line 54) | struct traits {}
type traits<RSS> (line 57) | struct traits<RSS> {
type traits<kIOS> (line 63) | struct traits<kIOS> {
type traits<OBB> (line 69) | struct traits<OBB> {
type traits<OBBRSS> (line 75) | struct traits<OBBRSS> {
function makeModel (line 81) | void makeModel(const std::vector<Vec3s>& vertices,
function distance (line 93) | double distance(const std::vector<Transform3s>& tf, const BVHModel<BV>& m1,
function collide (line 116) | double collide(const std::vector<Transform3s>& tf, const BVHModel<BV>& m1,
function run (line 142) | double run(const std::vector<Transform3s>& tf,
function main (line 166) | int main(int, char*[]) {
FILE: test/box_box_collision.cpp
function BOOST_AUTO_TEST_CASE (line 20) | BOOST_AUTO_TEST_CASE(box_box_collision) {
FILE: test/box_box_distance.cpp
function BOOST_AUTO_TEST_CASE (line 63) | BOOST_AUTO_TEST_CASE(distance_box_box_1) {
function BOOST_AUTO_TEST_CASE (line 104) | BOOST_AUTO_TEST_CASE(distance_box_box_2) {
function BOOST_AUTO_TEST_CASE (line 146) | BOOST_AUTO_TEST_CASE(distance_box_box_3) {
function BOOST_AUTO_TEST_CASE (line 221) | BOOST_AUTO_TEST_CASE(distance_box_box_4) {
FILE: test/broadphase.cpp
type GoogleSparseHashTable (line 82) | struct GoogleSparseHashTable
type GoogleDenseHashTable (line 87) | struct GoogleDenseHashTable
method GoogleDenseHashTable (line 90) | GoogleDenseHashTable()
function BOOST_AUTO_TEST_CASE (line 102) | BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_distance) {
function BOOST_AUTO_TEST_CASE (line 117) | BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_self_distance) {
function BOOST_AUTO_TEST_CASE (line 124) | BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_distance_mesh) {
function BOOST_AUTO_TEST_CASE (line 139) | BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_self_distance_mesh) {
function generateSelfDistanceEnvironments (line 145) | void generateSelfDistanceEnvironments(std::vector<CollisionObject*>& env,
function generateSelfDistanceEnvironmentsMesh (line 223) | void generateSelfDistanceEnvironmentsMesh(std::vector<CollisionObject*>&...
function broad_phase_self_distance_test (line 309) | void broad_phase_self_distance_test(Scalar env_scale, std::size_t env_size,
function broad_phase_distance_test (line 430) | void broad_phase_distance_test(Scalar env_scale, std::size_t env_size,
FILE: test/broadphase_collision_1.cpp
type GoogleSparseHashTable (line 80) | struct GoogleSparseHashTable
type GoogleDenseHashTable (line 85) | struct GoogleDenseHashTable
method GoogleDenseHashTable (line 88) | GoogleDenseHashTable()
function BOOST_AUTO_TEST_CASE (line 98) | BOOST_AUTO_TEST_CASE(test_broad_phase_dont_duplicate_check) {
function BOOST_AUTO_TEST_CASE (line 107) | BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_update_collision_binary) {
function BOOST_AUTO_TEST_CASE (line 118) | BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_update_collision) {
function BOOST_AUTO_TEST_CASE (line 129) | BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_update_collision_exhaustiv...
function BOOST_AUTO_TEST_CASE (line 140) | BOOST_AUTO_TEST_CASE(
function BOOST_AUTO_TEST_CASE (line 152) | BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_update_collision_mesh) {
function BOOST_AUTO_TEST_CASE (line 163) | BOOST_AUTO_TEST_CASE(
type CollisionDataForUniquenessChecking (line 175) | struct CollisionDataForUniquenessChecking {
method checkUniquenessAndAddPair (line 178) | bool checkUniquenessAndAddPair(CollisionObject* o1, CollisionObject* o...
type CollisionFunctionForUniquenessChecking (line 190) | struct CollisionFunctionForUniquenessChecking : CollisionCallBackBase {
method collide (line 191) | bool collide(CollisionObject* o1, CollisionObject* o2) {
function broad_phase_duplicate_check_test (line 200) | void broad_phase_duplicate_check_test(Scalar env_scale, std::size_t env_...
function broad_phase_update_collision_test (line 357) | void broad_phase_update_collision_test(Scalar env_scale, std::size_t env...
FILE: test/broadphase_collision_2.cpp
type GoogleSparseHashTable (line 72) | struct GoogleSparseHashTable
type GoogleDenseHashTable (line 77) | struct GoogleDenseHashTable
method GoogleDenseHashTable (line 80) | GoogleDenseHashTable()
function BOOST_AUTO_TEST_CASE (line 89) | BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_collision_empty) {
function BOOST_AUTO_TEST_CASE (line 126) | BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_collision_binary) {
function BOOST_AUTO_TEST_CASE (line 141) | BOOST_AUTO_TEST_CASE(test_core_bf_broad_phase_collision) {
function BOOST_AUTO_TEST_CASE (line 153) | BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_collision_mesh_binary) {
function BOOST_AUTO_TEST_CASE (line 164) | BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_collision_mesh) {
function BOOST_AUTO_TEST_CASE (line 175) | BOOST_AUTO_TEST_CASE(test_core_mesh_bf_broad_phase_collision_mesh_exhaus...
function broad_phase_collision_test (line 185) | void broad_phase_collision_test(Scalar env_scale, std::size_t env_size,
FILE: test/broadphase_dynamic_AABB_tree.cpp
type CallBackData (line 52) | struct CallBackData {
type DistanceCallBackDerived (line 64) | struct DistanceCallBackDerived : DistanceCallBackBase {
method distance (line 65) | bool distance(CollisionObject* o1, CollisionObject* o2, Scalar& dist) {
method distance_callback (line 69) | bool distance_callback(CollisionObject* a, CollisionObject*,
function BOOST_AUTO_TEST_CASE (line 99) | BOOST_AUTO_TEST_CASE(DynamicAABBTreeCollisionManager_class) {
FILE: test/bvh_models.cpp
function testBVHModelPointCloud (line 58) | void testBVHModelPointCloud() {
function testBVHModelTriangles (line 140) | void testBVHModelTriangles() {
function testBVHModelSubModel (line 231) | void testBVHModelSubModel() {
function testBVHModel (line 281) | void testBVHModel() {
function BOOST_AUTO_TEST_CASE (line 287) | BOOST_AUTO_TEST_CASE(building_bvh_models) {
function testLoadPolyhedron (line 299) | void testLoadPolyhedron() {
function testLoadGerardBauzil (line 327) | void testLoadGerardBauzil() {
function BOOST_AUTO_TEST_CASE (line 350) | BOOST_AUTO_TEST_CASE(load_polyhedron) {
function BOOST_AUTO_TEST_CASE (line 361) | BOOST_AUTO_TEST_CASE(gerard_bauzil) {
function BOOST_AUTO_TEST_CASE (line 368) | BOOST_AUTO_TEST_CASE(load_illformated_mesh) {
function BOOST_AUTO_TEST_CASE (line 376) | BOOST_AUTO_TEST_CASE(test_convex) {
FILE: test/capsule_box_1.cpp
function BOOST_AUTO_TEST_CASE (line 53) | BOOST_AUTO_TEST_CASE(distance_capsule_box) {
FILE: test/capsule_box_2.cpp
function BOOST_AUTO_TEST_CASE (line 53) | BOOST_AUTO_TEST_CASE(distance_capsule_box) {
FILE: test/capsule_capsule.cpp
function BOOST_AUTO_TEST_CASE (line 58) | BOOST_AUTO_TEST_CASE(collision_capsule_capsule_trivial) {
function BOOST_AUTO_TEST_CASE (line 110) | BOOST_AUTO_TEST_CASE(collision_capsule_capsule_aligned) {
function BOOST_AUTO_TEST_CASE (line 228) | BOOST_AUTO_TEST_CASE(distance_capsulecapsule_origin) {
function BOOST_AUTO_TEST_CASE (line 254) | BOOST_AUTO_TEST_CASE(distance_capsulecapsule_transformXY) {
function BOOST_AUTO_TEST_CASE (line 281) | BOOST_AUTO_TEST_CASE(distance_capsulecapsule_transformZ) {
function BOOST_AUTO_TEST_CASE (line 307) | BOOST_AUTO_TEST_CASE(distance_capsulecapsule_transformZ2) {
FILE: test/collision.cpp
function BOOST_AUTO_TEST_CASE (line 75) | BOOST_AUTO_TEST_CASE(OBB_Box_test) {
function BOOST_AUTO_TEST_CASE (line 125) | BOOST_AUTO_TEST_CASE(OBB_shape_test) {
function BOOST_AUTO_TEST_CASE (line 208) | BOOST_AUTO_TEST_CASE(OBB_AABB_test) {
type wrap (line 290) | struct wrap {}
type base_traits (line 292) | struct base_traits {
type traits (line 304) | struct traits : base_traits {}
type traits<KDOP<N>, Oriented, recursive> (line 307) | struct traits<KDOP<N>, Oriented, recursive> : base_traits {
function COAL_COMPILER_DIAGNOSTIC_PUSH (line 311) | COAL_COMPILER_DIAGNOSTIC_PUSH
function BOOST_AUTO_TEST_CASE (line 625) | BOOST_AUTO_TEST_CASE(mesh_mesh) {
FILE: test/collision_node_asserts.cpp
function Scalar (line 12) | Scalar DegToRad(const Scalar& deg) {
function BOOST_AUTO_TEST_CASE (line 19) | BOOST_AUTO_TEST_CASE(TestTriangles) {
FILE: test/contact_patch.cpp
function BOOST_AUTO_TEST_CASE (line 46) | BOOST_AUTO_TEST_CASE(box_box_no_collision) {
function BOOST_AUTO_TEST_CASE (line 73) | BOOST_AUTO_TEST_CASE(box_sphere) {
function BOOST_AUTO_TEST_CASE (line 111) | BOOST_AUTO_TEST_CASE(box_box) {
function BOOST_AUTO_TEST_CASE (line 169) | BOOST_AUTO_TEST_CASE(halfspace_box) {
function BOOST_AUTO_TEST_CASE (line 228) | BOOST_AUTO_TEST_CASE(cylinder_plane_simplification) {
function BOOST_AUTO_TEST_CASE (line 306) | BOOST_AUTO_TEST_CASE(halfspace_capsule) {
function BOOST_AUTO_TEST_CASE (line 418) | BOOST_AUTO_TEST_CASE(halfspace_cone) {
function BOOST_AUTO_TEST_CASE (line 542) | BOOST_AUTO_TEST_CASE(halfspace_cylinder) {
function BOOST_AUTO_TEST_CASE (line 651) | BOOST_AUTO_TEST_CASE(cylinder_box) {
function BOOST_AUTO_TEST_CASE (line 685) | BOOST_AUTO_TEST_CASE(cylinder_convex) {
function BOOST_AUTO_TEST_CASE (line 719) | BOOST_AUTO_TEST_CASE(convex_convex) {
function BOOST_AUTO_TEST_CASE (line 777) | BOOST_AUTO_TEST_CASE(edge_case_segment_segment) {
function BOOST_AUTO_TEST_CASE (line 945) | BOOST_AUTO_TEST_CASE(edge_case_vertex_vertex) {
function BOOST_AUTO_TEST_CASE (line 1106) | BOOST_AUTO_TEST_CASE(edge_case_segment_face) {
FILE: test/convex.cpp
function BOOST_AUTO_TEST_CASE (line 48) | BOOST_AUTO_TEST_CASE(convex) {
function compareShapeIntersection (line 130) | void compareShapeIntersection(const Sa& sa, const Sb& sb,
function compareShapeDistance (line 160) | void compareShapeDistance(const Sa& sa, const Sb& sb, const Transform3s&...
function BOOST_AUTO_TEST_CASE (line 191) | BOOST_AUTO_TEST_CASE(compare_convex_box) {
function BOOST_AUTO_TEST_CASE (line 216) | BOOST_AUTO_TEST_CASE(convex_hull_throw) {
function BOOST_AUTO_TEST_CASE (line 230) | BOOST_AUTO_TEST_CASE(convex_hull_quad) {
function BOOST_AUTO_TEST_CASE (line 247) | BOOST_AUTO_TEST_CASE(convex_hull_box_like) {
function BOOST_AUTO_TEST_CASE (line 290) | BOOST_AUTO_TEST_CASE(convex_copy_constructor) {
function BOOST_AUTO_TEST_CASE (line 315) | BOOST_AUTO_TEST_CASE(convex_clone) {
FILE: test/distance.cpp
function nearlyEqual (line 82) | inline bool nearlyEqual(const Vec3s& a, const Vec3s& b) {
function BOOST_AUTO_TEST_CASE (line 89) | BOOST_AUTO_TEST_CASE(mesh_distance) {
function distance_Test_Oriented (line 471) | void distance_Test_Oriented(const Transform3s& tf,
function distance_Test (line 519) | void distance_Test(const Transform3s& tf, const std::vector<Vec3s>& vert...
function collide_Test_OBB (line 568) | bool collide_Test_OBB(const Transform3s& tf,
FILE: test/distance_lower_bound.cpp
function testDistanceLowerBound (line 63) | bool testDistanceLowerBound(const Transform3s& tf,
function testCollide (line 81) | bool testCollide(const Transform3s& tf, const CollisionGeometryPtr_t& m1,
function testDistance (line 96) | bool testDistance(const Transform3s& tf, const CollisionGeometryPtr_t& m1,
function BOOST_AUTO_TEST_CASE (line 115) | BOOST_AUTO_TEST_CASE(mesh_mesh) {
function BOOST_AUTO_TEST_CASE (line 160) | BOOST_AUTO_TEST_CASE(box_sphere) {
function BOOST_AUTO_TEST_CASE (line 197) | BOOST_AUTO_TEST_CASE(sphere_sphere) {
function BOOST_AUTO_TEST_CASE (line 234) | BOOST_AUTO_TEST_CASE(box_mesh) {
FILE: test/frontlist.cpp
function BOOST_AUTO_TEST_CASE (line 80) | BOOST_AUTO_TEST_CASE(front_list) {
function collide_front_list_Test (line 273) | bool collide_front_list_Test(const Transform3s& tf1, const Transform3s& ...
function collide_front_list_Test_Oriented (line 339) | bool collide_front_list_Test_Oriented(const Transform3s& tf1,
function collide_Test (line 395) | bool collide_Test(const Transform3s& tf, const std::vector<Vec3s>& verti...
FILE: test/geometric_shapes.cpp
type coal (line 69) | namespace coal {
function printComparisonError (line 80) | void printComparisonError(const std::string& comparison_type, const S1& s1,
function printComparisonError (line 111) | void printComparisonError(const std::string& comparison_type, const S1& s1,
function compareContact (line 129) | void compareContact(const S1& s1, const Transform3s& tf1, const S2& s2,
function testShapeCollide (line 164) | void testShapeCollide(const S1& s1, const Transform3s& tf1, const S2& s2,
function BOOST_AUTO_TEST_CASE (line 209) | BOOST_AUTO_TEST_CASE(box_to_bvh) {
function BOOST_AUTO_TEST_CASE (line 215) | BOOST_AUTO_TEST_CASE(sphere_to_bvh) {
function BOOST_AUTO_TEST_CASE (line 222) | BOOST_AUTO_TEST_CASE(cylinder_to_bvh) {
function BOOST_AUTO_TEST_CASE (line 229) | BOOST_AUTO_TEST_CASE(cone_to_bvh) {
function BOOST_AUTO_TEST_CASE (line 236) | BOOST_AUTO_TEST_CASE(collide_spheresphere) {
function compareContactPoints (line 333) | bool compareContactPoints(const Vec3s& c1, const Vec3s& c2) {
function testBoxBoxContactPoints (line 337) | void testBoxBoxContactPoints(const Matrix3s& R) {
function BOOST_AUTO_TEST_CASE (line 383) | BOOST_AUTO_TEST_CASE(collide_boxbox) {
function BOOST_AUTO_TEST_CASE (line 454) | BOOST_AUTO_TEST_CASE(collide_spherebox) {
function BOOST_AUTO_TEST_CASE (line 506) | BOOST_AUTO_TEST_CASE(distance_spherebox) {
function BOOST_AUTO_TEST_CASE (line 529) | BOOST_AUTO_TEST_CASE(collide_spherecapsule) {
function BOOST_AUTO_TEST_CASE (line 594) | BOOST_AUTO_TEST_CASE(collide_cylindercylinder) {
function BOOST_AUTO_TEST_CASE (line 657) | BOOST_AUTO_TEST_CASE(collide_conecone) {
function BOOST_AUTO_TEST_CASE (line 735) | BOOST_AUTO_TEST_CASE(collide_conecylinder) {
function BOOST_AUTO_TEST_CASE (line 843) | BOOST_AUTO_TEST_CASE(collide_spheretriangle) {
function BOOST_AUTO_TEST_CASE (line 1031) | BOOST_AUTO_TEST_CASE(collide_halfspacetriangle) {
function BOOST_AUTO_TEST_CASE (line 1150) | BOOST_AUTO_TEST_CASE(collide_planetriangle) {
function BOOST_AUTO_TEST_CASE (line 1274) | BOOST_AUTO_TEST_CASE(collide_halfspacesphere) {
function BOOST_AUTO_TEST_CASE (line 1363) | BOOST_AUTO_TEST_CASE(collide_planesphere) {
function BOOST_AUTO_TEST_CASE (line 1472) | BOOST_AUTO_TEST_CASE(collide_halfspacebox) {
function BOOST_AUTO_TEST_CASE (line 1566) | BOOST_AUTO_TEST_CASE(collide_planebox) {
function BOOST_AUTO_TEST_CASE (line 1659) | BOOST_AUTO_TEST_CASE(collide_halfspacecapsule) {
function BOOST_AUTO_TEST_CASE (line 1900) | BOOST_AUTO_TEST_CASE(collide_planecapsule) {
function BOOST_AUTO_TEST_CASE (line 2123) | BOOST_AUTO_TEST_CASE(collide_halfspacecylinder) {
function BOOST_AUTO_TEST_CASE (line 2364) | BOOST_AUTO_TEST_CASE(collide_planecylinder) {
function BOOST_AUTO_TEST_CASE (line 2668) | BOOST_AUTO_TEST_CASE(collide_halfspacecone) {
function BOOST_AUTO_TEST_CASE (line 2909) | BOOST_AUTO_TEST_CASE(collide_planecone) {
function BOOST_AUTO_TEST_CASE (line 3213) | BOOST_AUTO_TEST_CASE(collide_planeplane) {
function BOOST_AUTO_TEST_CASE (line 3333) | BOOST_AUTO_TEST_CASE(collide_halfspacehalfspace) {
function BOOST_AUTO_TEST_CASE (line 3449) | BOOST_AUTO_TEST_CASE(collide_halfspaceplane) {
function BOOST_AUTO_TEST_CASE (line 3567) | BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_spheresphere) {
function BOOST_AUTO_TEST_CASE (line 3639) | BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_boxbox) {
function BOOST_AUTO_TEST_CASE (line 3716) | BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_cylinderbox) {
function BOOST_AUTO_TEST_CASE (line 3774) | BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_boxsphere) {
function BOOST_AUTO_TEST_CASE (line 3837) | BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_cylindercylinder) {
function BOOST_AUTO_TEST_CASE (line 3905) | BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_conecone) {
function BOOST_AUTO_TEST_CASE (line 3973) | BOOST_AUTO_TEST_CASE(GJKSolver_shapeDistance_conecylinder) {
function testReversibleShapeDistance (line 4042) | void testReversibleShapeDistance(const S1& s1, const S2& s2, Scalar dist...
function BOOST_AUTO_TEST_CASE (line 4082) | BOOST_AUTO_TEST_CASE(reversibleShapeDistance_allshapes) {
FILE: test/gjk.cpp
type Result (line 63) | struct Result {
function test_gjk_distance_triangle_triangle (line 71) | void test_gjk_distance_triangle_triangle(
function BOOST_AUTO_TEST_CASE (line 333) | BOOST_AUTO_TEST_CASE(distance_triangle_triangle) {
function BOOST_AUTO_TEST_CASE (line 337) | BOOST_AUTO_TEST_CASE(distance_triangle_triangle_nesterov) {
function test_gjk_unit_sphere (line 341) | void test_gjk_unit_sphere(Scalar center_distance, Vec3s ray,
function BOOST_AUTO_TEST_CASE (line 394) | BOOST_AUTO_TEST_CASE(sphere_sphere) {
function test_gjk_triangle_capsule (line 424) | void test_gjk_triangle_capsule(Vec3s T, bool expect_collision,
function BOOST_AUTO_TEST_CASE (line 481) | BOOST_AUTO_TEST_CASE(triangle_capsule) {
FILE: test/gjk_asserts.cpp
function Scalar (line 12) | Scalar DegToRad(const Scalar& deg) {
function CreateSphereMesh (line 19) | void CreateSphereMesh(BVHModel<OBBRSS>& model, const Scalar& radius) {
function BOOST_AUTO_TEST_CASE (line 56) | BOOST_AUTO_TEST_CASE(TestSpheres) {
FILE: test/gjk_convergence_criterion.cpp
function BOOST_AUTO_TEST_CASE (line 64) | BOOST_AUTO_TEST_CASE(set_cv_criterion) {
function test_gjk_cv_criterion (line 94) | void test_gjk_cv_criterion(const ShapeBase& shape0, const ShapeBase& sha...
function BOOST_AUTO_TEST_CASE (line 174) | BOOST_AUTO_TEST_CASE(cv_criterion_same_solution) {
FILE: test/hfields.cpp
function test_constant_hfields (line 60) | void test_constant_hfields(const Eigen::DenseIndex nx,
function BOOST_AUTO_TEST_CASE (line 262) | BOOST_AUTO_TEST_CASE(building_constant_hfields) {
function test_negative_security_margin (line 277) | void test_negative_security_margin(const Eigen::DenseIndex nx,
function BOOST_AUTO_TEST_CASE (line 415) | BOOST_AUTO_TEST_CASE(negative_security_margin) {
function BOOST_AUTO_TEST_CASE (line 423) | BOOST_AUTO_TEST_CASE(hfield_with_square_hole) {
function BOOST_AUTO_TEST_CASE (line 464) | BOOST_AUTO_TEST_CASE(hfield_with_circular_hole) {
function isApprox (line 525) | bool isApprox(const Scalar v1, const Scalar v2,
function Vec3s (line 530) | Vec3s computeFaceNormal(const Triangle32& triangle,
function BOOST_AUTO_TEST_CASE (line 539) | BOOST_AUTO_TEST_CASE(test_hfield_bin_face_normal_orientation) {
function BOOST_AUTO_TEST_CASE (line 685) | BOOST_AUTO_TEST_CASE(test_hfield_bin_active_faces) {
function BOOST_AUTO_TEST_CASE (line 723) | BOOST_AUTO_TEST_CASE(test_hfield_single_bin) {
FILE: test/math.cpp
function BOOST_AUTO_TEST_CASE (line 50) | BOOST_AUTO_TEST_CASE(vec_test_eigen_vec64) {
function Vec3s (line 108) | Vec3s rotate(Vec3s input, Scalar w, Vec3s vec) {
function BOOST_AUTO_TEST_CASE (line 113) | BOOST_AUTO_TEST_CASE(quaternion) {
function BOOST_AUTO_TEST_CASE (line 126) | BOOST_AUTO_TEST_CASE(transform) {
function BOOST_AUTO_TEST_CASE (line 143) | BOOST_AUTO_TEST_CASE(random_transform) {
FILE: test/normal_and_nearest_points.cpp
function test_normal_and_nearest_points (line 75) | void test_normal_and_nearest_points(
function generateRandomVector (line 241) | Eigen::Matrix<Scalar, VecSize, 1> generateRandomVector(Scalar min, Scala...
function Scalar (line 249) | Scalar generateRandomNumber(Scalar min, Scalar max) {
function BOOST_AUTO_TEST_CASE (line 256) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_sphere_sphere) {
function BOOST_AUTO_TEST_CASE (line 266) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_sphere_capsule) {
function BOOST_AUTO_TEST_CASE (line 278) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_sphere_box) {
function BOOST_AUTO_TEST_CASE (line 288) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_mesh_mesh) {
function BOOST_AUTO_TEST_CASE (line 309) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_mesh_box) {
function BOOST_AUTO_TEST_CASE (line 320) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_mesh_ellipsoid) {
function BOOST_AUTO_TEST_CASE (line 344) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_ellipsoid_ellipsoid) {
function BOOST_AUTO_TEST_CASE (line 370) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_box_plane) {
function BOOST_AUTO_TEST_CASE (line 384) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_box_halfspace) {
function BOOST_AUTO_TEST_CASE (line 397) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_capsule_halfspace) {
function BOOST_AUTO_TEST_CASE (line 413) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_sphere_halfspace) {
function BOOST_AUTO_TEST_CASE (line 427) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_sphere_plane) {
function BOOST_AUTO_TEST_CASE (line 441) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_mesh_halfspace) {
function BOOST_AUTO_TEST_CASE (line 458) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_cone_cylinder) {
function BOOST_AUTO_TEST_CASE (line 478) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_cylinder_ellipsoid) {
function BOOST_AUTO_TEST_CASE (line 499) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_cone_halfspace) {
function BOOST_AUTO_TEST_CASE (line 515) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_cylinder_halfspace) {
function BOOST_AUTO_TEST_CASE (line 531) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_cone_plane) {
function BOOST_AUTO_TEST_CASE (line 547) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_cylinder_plane) {
function BOOST_AUTO_TEST_CASE (line 563) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_capsule_plane) {
function BOOST_AUTO_TEST_CASE (line 579) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_capsule_capsule) {
function BOOST_AUTO_TEST_CASE (line 591) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_sphere_cylinder) {
function BOOST_AUTO_TEST_CASE (line 603) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_ellipsoid_halfspace) {
function BOOST_AUTO_TEST_CASE (line 617) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_ellipsoid_plane) {
function test_normal_and_nearest_points (line 631) | void test_normal_and_nearest_points(const BVHModel<OBBRSS>& o1,
function test_normal_and_nearest_points (line 690) | void test_normal_and_nearest_points(const Halfspace& o1,
function BOOST_AUTO_TEST_CASE (line 695) | BOOST_AUTO_TEST_CASE(test_normal_and_nearest_points_bvh_halfspace) {
FILE: test/obb.cpp
function randomOBBs (line 51) | void randomOBBs(Vec3s& a, Vec3s& b, Scalar extentNorm) {
function randomTransform (line 60) | void randomTransform(Matrix3s& B, Vec3s& T, const Vec3s& a, const Vec3s& b,
type obbDisjoint_impls (line 104) | namespace obbDisjoint_impls {
function distance (line 106) | bool distance(const Matrix3s& B, const Vec3s& T, const Vec3s& a, const...
function Scalar (line 119) | inline Scalar _computeDistanceForCase1(const Vec3s& T, const Vec3s& a,
function Scalar (line 138) | inline Scalar _computeDistanceForCase2(const Matrix3s& B, const Vec3s& T,
function separatingAxisId (line 162) | int separatingAxisId(const Matrix3s& B, const Vec3s& T, const Vec3s& a,
function withRuntimeLoop (line 218) | bool withRuntimeLoop(const Matrix3s& B, const Vec3s& T, const Vec3s& a,
function withManualLoopUnrolling_1 (line 269) | bool withManualLoopUnrolling_1(const Matrix3s& B, const Vec3s& T,
function withManualLoopUnrolling_2 (line 459) | bool withManualLoopUnrolling_2(const Matrix3s& B, const Vec3s& T,
type loop_case_1 (line 638) | struct loop_case_1 {
method run (line 639) | static inline bool run(const Matrix3s& B, const Vec3s& T, const Vec3...
function withTemplateLoopUnrolling_1 (line 670) | bool withTemplateLoopUnrolling_1(const Matrix3s& B, const Vec3s& T,
type loop_case_2 (line 718) | struct loop_case_2 {
method run (line 719) | static inline bool run(int ia, int ja, int ka, const Matrix3s& B,
function withPartialTemplateLoopUnrolling_1 (line 750) | bool withPartialTemplateLoopUnrolling_1(const Matrix3s& B, const Vec3s...
function originalWithLowerBound (line 783) | bool originalWithLowerBound(const Matrix3s& B, const Vec3s& T, const V...
function originalWithNoLowerBound (line 1004) | bool originalWithNoLowerBound(const Matrix3s& B, const Vec3s& T, const...
type BenchmarkResult (line 1135) | struct BenchmarkResult {
function BenchmarkResult (line 1174) | BenchmarkResult benchmark_obb_case(const Matrix3s& B, const Vec3s& T,
function obb_overlap_and_lower_bound_distance (line 1279) | std::size_t obb_overlap_and_lower_bound_distance(std::ostream* output) {
function main (line 1314) | int main(int argc, char** argv) {
FILE: test/octree.cpp
function makeMesh (line 58) | void makeMesh(const std::vector<Vec3s>& vertices,
function makeOctree (line 70) | coal::OcTree makeOctree(const BVHModel<OBBRSS>& mesh,
function BOOST_AUTO_TEST_CASE (line 106) | BOOST_AUTO_TEST_CASE(octree_aabb) {
function BOOST_AUTO_TEST_CASE (line 151) | BOOST_AUTO_TEST_CASE(octree_mesh) {
function BOOST_AUTO_TEST_CASE (line 225) | BOOST_AUTO_TEST_CASE(octree_height_field) {
FILE: test/patch_simplifier.cpp
function ContactPatch (line 16) | ContactPatch generateRandomPatch(std::size_t max_num_points = 20) {
function Vec2s (line 35) | Vec2s computeBarycenter(const ContactPatch& patch) {
function findFarthestPoint (line 45) | std::size_t findFarthestPoint(const ContactPatch& patch,
function BOOST_AUTO_TEST_CASE (line 59) | BOOST_AUTO_TEST_CASE(patch_simplifier_barycenter) {
function BOOST_AUTO_TEST_CASE (line 84) | BOOST_AUTO_TEST_CASE(patch_simplifier_two_points) {
function BOOST_AUTO_TEST_CASE (line 119) | BOOST_AUTO_TEST_CASE(patch_simplifier) {
FILE: test/polygon_convex_hull.cpp
function generateRandomCloud (line 48) | std::vector<Vec2s> generateRandomCloud(std::size_t n) {
function computePolygonConvexHullNaive (line 59) | void computePolygonConvexHullNaive(const std::vector<Vec2s>& cloud,
function BOOST_AUTO_TEST_CASE (line 104) | BOOST_AUTO_TEST_CASE(test_compute_polygon_convex_hull) {
FILE: test/profiling.cpp
function supportedPair (line 33) | bool supportedPair(const CollisionGeometry* o1, const CollisionGeometry*...
function CollisionGeometryPtr_t (line 46) | CollisionGeometryPtr_t objToGeom(const std::string& filename) {
function CollisionGeometryPtr_t (line 62) | CollisionGeometryPtr_t meshToGeom(const std::string& filename,
type Geometry (line 69) | struct Geometry {
method Geometry (line 73) | Geometry(const std::string& t, CollisionGeometry* ob) : type(t), o(ob) {}
method Geometry (line 74) | Geometry(const std::string& t, const CollisionGeometryPtr_t& ob)
type Results (line 78) | struct Results {
method Results (line 82) | Results(size_t i) : rs(i), times((Eigen::DenseIndex)i) {}
function collide (line 85) | void collide(const std::vector<Transform3s>& tf, const CollisionGeometry...
function printResultHeaders (line 101) | void printResultHeaders() {
function printResults (line 107) | void printResults(const Geometry& g1, const Geometry& g2, const Results&...
function handleParam (line 128) | void handleParam(int& iarg, const int& argc, char** argv,
function Geometry (line 158) | Geometry makeGeomFromParam(int& iarg, const int& argc, char** argv) {
method Geometry (line 73) | Geometry(const std::string& t, CollisionGeometry* ob) : type(t), o(ob) {}
method Geometry (line 74) | Geometry(const std::string& t, const CollisionGeometryPtr_t& ob)
function main (line 225) | int main(int argc, char** argv) {
FILE: test/python_unit/api.py
class TestMainAPI (line 8) | class TestMainAPI(TestCase):
method test_collision (line 9) | def test_collision(self):
method test_distance (line 19) | def test_distance(self):
FILE: test/python_unit/collision.py
function tetahedron (line 8) | def tetahedron():
class TestMainAPI (line 22) | class TestMainAPI(TestCase):
method test_convex_halfspace (line 23) | def test_convex_halfspace(self):
FILE: test/python_unit/geometric_shapes.py
class TestGeometricShapes (line 7) | class TestGeometricShapes(TestCase):
method test_capsule (line 8) | def test_capsule(self):
method test_box1 (line 49) | def test_box1(self):
method test_box2 (line 75) | def test_box2(self):
method test_sphere (line 85) | def test_sphere(self):
method test_cylinder (line 105) | def test_cylinder(self):
method test_cone (line 130) | def test_cone(self):
method test_BVH (line 157) | def test_BVH(self):
method test_convex (line 162) | def test_convex(self):
FILE: test/python_unit/pickling.py
function tetahedron (line 9) | def tetahedron():
class TestGeometryPickling (line 23) | class TestGeometryPickling(TestCase):
method pickling (line 24) | def pickling(self, obj):
method test_all_shapes (line 32) | def test_all_shapes(self):
FILE: test/python_unit/test_case.py
class TestCase (line 5) | class TestCase(unittest.TestCase):
method assertApprox (line 6) | def assertApprox(self, a, b, epsilon=1e-6):
FILE: test/scripts/collision-bench.py
function reorder (line 47) | def reorder(v):
FILE: test/scripts/geometric_shapes.py
function translate (line 6) | def translate(tr, t, d):
FILE: test/security_margin.cpp
function BOOST_AUTO_TEST_CASE (line 59) | BOOST_AUTO_TEST_CASE(aabb_aabb) {
function BOOST_AUTO_TEST_CASE (line 149) | BOOST_AUTO_TEST_CASE(aabb_aabb_degenerated_cases) {
function BOOST_AUTO_TEST_CASE (line 179) | BOOST_AUTO_TEST_CASE(sphere_sphere) {
function BOOST_AUTO_TEST_CASE (line 259) | BOOST_AUTO_TEST_CASE(capsule_capsule) {
function BOOST_AUTO_TEST_CASE (line 336) | BOOST_AUTO_TEST_CASE(box_box) {
function test_shape_shape (line 418) | void test_shape_shape(const ShapeType1& shape1, const Transform3s& tf1,
function BOOST_AUTO_TEST_CASE (line 496) | BOOST_AUTO_TEST_CASE(sphere_box) {
FILE: test/serialization.cpp
function check (line 77) | bool check(const T& value, const T& other) {
function check_ptr (line 82) | bool check_ptr(const T* value, const T* other) {
type SerializationMode (line 86) | enum SerializationMode { TXT = 1, XML = 2, BIN = 4, STREAM = 8 }
function test_serialization (line 89) | void test_serialization(const T* value, T& other_value,
type test_pointer_serialization_impl (line 96) | struct test_pointer_serialization_impl {
method run (line 97) | static void run(const T&, T&, const int) {}
type test_pointer_serialization_impl<T, true> (line 101) | struct test_pointer_serialization_impl<T, true> {
method run (line 102) | static void run(const T& value, T& other_value, const int mode) {
function test_pointer_serialization (line 140) | void test_pointer_serialization(const T& value, T& other_value,
function test_serialization (line 148) | void test_serialization(const T& value, T& other_value, Hook post_load_h...
function test_serialization (line 255) | void test_serialization(const T& value, T& other_value,
function test_serialization (line 263) | void test_serialization(const T& value, Hook post_load_hook,
function test_serialization (line 270) | void test_serialization(const T& value,
function BOOST_AUTO_TEST_CASE (line 276) | BOOST_AUTO_TEST_CASE(test_aabb) {
function BOOST_AUTO_TEST_CASE (line 281) | BOOST_AUTO_TEST_CASE(test_collision_data) {
function checkEqualStdVector (line 365) | void checkEqualStdVector(const std::vector<T>& v1, const std::vector<T>&...
function BOOST_AUTO_TEST_CASE (line 374) | BOOST_AUTO_TEST_CASE(test_BVHModel) {
function BOOST_AUTO_TEST_CASE (line 415) | BOOST_AUTO_TEST_CASE(test_Convex) {
function BOOST_AUTO_TEST_CASE (line 467) | BOOST_AUTO_TEST_CASE(test_HeightField) {
function BOOST_AUTO_TEST_CASE (line 486) | BOOST_AUTO_TEST_CASE(test_transform) {
function BOOST_AUTO_TEST_CASE (line 495) | BOOST_AUTO_TEST_CASE(test_shapes) {
function BOOST_AUTO_TEST_CASE (line 583) | BOOST_AUTO_TEST_CASE(test_octree) {
function BOOST_AUTO_TEST_CASE (line 621) | BOOST_AUTO_TEST_CASE(test_memory_footprint) {
FILE: test/shape_inflation.cpp
function isApprox (line 64) | bool isApprox(const Scalar& v1, const Scalar& v2, const Scalar tol) {
function isApprox (line 73) | bool isApprox(const Box& s1, const Box& s2, const Scalar tol) {
function isApprox (line 77) | bool isApprox(const Sphere& s1, const Sphere& s2, const Scalar tol) {
function isApprox (line 81) | bool isApprox(const Ellipsoid& s1, const Ellipsoid& s2, const Scalar tol) {
function isApprox (line 85) | bool isApprox(const Capsule& s1, const Capsule& s2, const Scalar tol) {
function isApprox (line 90) | bool isApprox(const Cylinder& s1, const Cylinder& s2, const Scalar tol) {
function isApprox (line 95) | bool isApprox(const Cone& s1, const Cone& s2, const Scalar tol) {
function isApprox (line 100) | bool isApprox(const TriangleP& s1, const TriangleP& s2, const Scalar tol) {
function isApprox (line 105) | bool isApprox(const Halfspace& s1, const Halfspace& s2, const Scalar tol) {
function test (line 110) | void test(const Shape& original_shape, const Scalar inflation,
function test_throw (line 157) | void test_throw(const Shape& shape, const Scalar inflation) {
function test_no_throw (line 162) | void test_no_throw(const Shape& shape, const Scalar inflation) {
function BOOST_AUTO_TEST_CASE (line 166) | BOOST_AUTO_TEST_CASE(test_inflate) {
FILE: test/shape_mesh_consistency.cpp
function BOOST_AUTO_TEST_CASE (line 53) | BOOST_AUTO_TEST_CASE(consistency_distance_spheresphere) {
function BOOST_AUTO_TEST_CASE (line 155) | BOOST_AUTO_TEST_CASE(consistency_distance_boxbox) {
function BOOST_AUTO_TEST_CASE (line 259) | BOOST_AUTO_TEST_CASE(consistency_distance_cylindercylinder) {
function BOOST_AUTO_TEST_CASE (line 364) | BOOST_AUTO_TEST_CASE(consistency_distance_conecone) {
function BOOST_AUTO_TEST_CASE (line 468) | BOOST_AUTO_TEST_CASE(consistency_distance_spheresphere_GJK) {
function BOOST_AUTO_TEST_CASE (line 571) | BOOST_AUTO_TEST_CASE(consistency_distance_boxbox_GJK) {
function BOOST_AUTO_TEST_CASE (line 675) | BOOST_AUTO_TEST_CASE(consistency_distance_cylindercylinder_GJK) {
function BOOST_AUTO_TEST_CASE (line 791) | BOOST_AUTO_TEST_CASE(consistency_distance_conecone_GJK) {
function BOOST_AUTO_TEST_CASE (line 895) | BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere) {
function BOOST_AUTO_TEST_CASE (line 1113) | BOOST_AUTO_TEST_CASE(consistency_collision_boxbox) {
function BOOST_AUTO_TEST_CASE (line 1232) | BOOST_AUTO_TEST_CASE(consistency_collision_spherebox) {
function BOOST_AUTO_TEST_CASE (line 1351) | BOOST_AUTO_TEST_CASE(consistency_collision_cylindercylinder) {
function BOOST_AUTO_TEST_CASE (line 1437) | BOOST_AUTO_TEST_CASE(consistency_collision_conecone) {
function BOOST_AUTO_TEST_CASE (line 1587) | BOOST_AUTO_TEST_CASE(consistency_collision_spheresphere_GJK) {
function BOOST_AUTO_TEST_CASE (line 1806) | BOOST_AUTO_TEST_CASE(consistency_collision_boxbox_GJK) {
function BOOST_AUTO_TEST_CASE (line 1926) | BOOST_AUTO_TEST_CASE(consistency_collision_spherebox_GJK) {
function BOOST_AUTO_TEST_CASE (line 2046) | BOOST_AUTO_TEST_CASE(consistency_collision_cylindercylinder_GJK) {
function BOOST_AUTO_TEST_CASE (line 2133) | BOOST_AUTO_TEST_CASE(consistency_collision_conecone_GJK) {
FILE: test/simple.cpp
function approx (line 14) | static bool approx(Scalar x, Scalar y) { return std::abs(x - y) < epsilo...
function BOOST_AUTO_TEST_CASE (line 16) | BOOST_AUTO_TEST_CASE(projection_test_line) {
function BOOST_AUTO_TEST_CASE (line 42) | BOOST_AUTO_TEST_CASE(projection_test_triangle) {
function BOOST_AUTO_TEST_CASE (line 105) | BOOST_AUTO_TEST_CASE(projection_test_tetrahedron) {
FILE: test/swept_sphere_radius.cpp
type SweptSphereGJKSolver (line 114) | struct SweptSphereGJKSolver : public GJKSolver {
method Scalar (line 116) | Scalar shapeDistance(
function test_gjksolver_swept_sphere_radius (line 136) | void test_gjksolver_swept_sphere_radius(S1& shape1, S2& shape2) {
function BOOST_AUTO_TEST_CASE (line 209) | BOOST_AUTO_TEST_CASE(ssr_mesh_mesh) {
function BOOST_AUTO_TEST_CASE (line 217) | BOOST_AUTO_TEST_CASE(ssr_mesh_ellipsoid) {
function BOOST_AUTO_TEST_CASE (line 224) | BOOST_AUTO_TEST_CASE(ssr_box_box) {
function BOOST_AUTO_TEST_CASE (line 230) | BOOST_AUTO_TEST_CASE(ssr_ellipsoid_ellipsoid) {
function BOOST_AUTO_TEST_CASE (line 236) | BOOST_AUTO_TEST_CASE(ssr_ellipsoid_box) {
function BOOST_AUTO_TEST_CASE (line 242) | BOOST_AUTO_TEST_CASE(ssr_cone_cone) {
function BOOST_AUTO_TEST_CASE (line 250) | BOOST_AUTO_TEST_CASE(ssr_cone_ellipsoid) {
function BOOST_AUTO_TEST_CASE (line 257) | BOOST_AUTO_TEST_CASE(ssr_capsule_capsule) {
function BOOST_AUTO_TEST_CASE (line 265) | BOOST_AUTO_TEST_CASE(ssr_capsule_cone) {
function BOOST_AUTO_TEST_CASE (line 273) | BOOST_AUTO_TEST_CASE(ssr_cylinder_cylinder) {
function test_collide_swept_sphere_radius (line 282) | void test_collide_swept_sphere_radius(S1& shape1, S2& shape2) {
function BOOST_AUTO_TEST_CASE (line 370) | BOOST_AUTO_TEST_CASE(ssr_geom_geom) {
FILE: test/utility.cpp
type coal (line 17) | namespace coal {
function Scalar (line 43) | Scalar rand_interval(Scalar rmin, Scalar rmax) {
function loadOBJFile (line 48) | void loadOBJFile(const char* filename, std::vector<Vec3s>& points,
function saveOBJFile (line 114) | void saveOBJFile(const char* filename, std::vector<Vec3s>& points,
function OcTree (line 136) | OcTree loadOctreeFile(const std::string& filename, const Scalar& resol...
function eulerToMatrix (line 148) | void eulerToMatrix(Scalar a, Scalar b, Scalar c, Matrix3s& R) {
function generateRandomTransform (line 160) | void generateRandomTransform(Scalar extents[6], Transform3s& transform) {
function generateRandomTransforms (line 176) | void generateRandomTransforms(Scalar extents[6],
function generateRandomTransforms (line 199) | void generateRandomTransforms(Scalar extents[6], Scalar delta_trans[3],
function defaultCollisionFunction (line 240) | bool defaultCollisionFunction(CollisionObject* o1, CollisionObject* o2,
function defaultDistanceFunction (line 257) | bool defaultDistanceFunction(CollisionObject* o1, CollisionObject* o2,
function getNodeTypeName (line 277) | std::string getNodeTypeName(NODE_TYPE node_type) {
function Quats (line 320) | Quats makeQuat(Scalar w, Scalar x, Scalar y, Scalar z) {
function getNbRun (line 329) | std::size_t getNbRun(const int& argc, char const* const* argv,
function generateEnvironments (line 337) | void generateEnvironments(std::vector<CollisionObject*>& env, Scalar e...
function generateEnvironmentsMesh (line 368) | void generateEnvironmentsMesh(std::vector<CollisionObject*>& env,
function buildBox (line 405) | ConvexTpl<Quadrilateral32> buildBox(Scalar l, Scalar w, Scalar d) {
function toSphere (line 428) | void toSphere(Vec3s& point) {
function toEllipsoid (line 439) | void toEllipsoid(Vec3s& point, const Ellipsoid& ellipsoid) {
function constructPolytopeFromEllipsoid (line 446) | ConvexTpl<Triangle32> constructPolytopeFromEllipsoid(
function Box (line 506) | Box makeRandomBox(Scalar min_size, Scalar max_size) {
function Sphere (line 512) | Sphere makeRandomSphere(Scalar min_size, Scalar max_size) {
function Ellipsoid (line 516) | Ellipsoid makeRandomEllipsoid(Scalar min_size, Scalar max_size) {
function Capsule (line 522) | Capsule makeRandomCapsule(std::array<Scalar, 2> min_size,
function Cone (line 528) | Cone makeRandomCone(std::array<Scalar, 2> min_size,
function Cylinder (line 534) | Cylinder makeRandomCylinder(std::array<Scalar, 2> min_size,
function makeRandomConvex (line 540) | ConvexTpl<Triangle32> makeRandomConvex(Scalar min_size, Scalar max_siz...
function Plane (line 545) | Plane makeRandomPlane(Scalar min_size, Scalar max_size) {
function Halfspace (line 549) | Halfspace makeRandomHalfspace(Scalar min_size, Scalar max_size) {
function makeRandomGeometry (line 554) | std::shared_ptr<ShapeBase> makeRandomGeometry(NODE_TYPE node_type) {
FILE: test/utility.h
function namespace (line 73) | namespace octomap {
function namespace (line 78) | namespace coal {
Condensed preview — 500 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (4,665K chars).
[
{
"path": ".clang-format",
"chars": 41,
"preview": "BasedOnStyle: Google\nSortIncludes: false\n"
},
{
"path": ".gersemirc",
"chars": 123,
"preview": "definitions: [./CMakeLists.txt,./cmake,./python,./src,./test]\nline_length: 80\nindent: 2\nwarn_about_unknown_commands: fal"
},
{
"path": ".git-blame-ignore-revs",
"chars": 500,
"preview": "0067c8aa66aac548601e2a3fd029aa264cc59f2a\n76b68f785df31b00e153290b45ec290a9c5f7963\n# ruff --fix . (Guilhem Saurel, 2023-1"
},
{
"path": ".gitattributes",
"chars": 83,
"preview": "# SCM syntax highlighting\npixi.lock linguist-language=YAML linguist-generated=true\n"
},
{
"path": ".github/dependabot.yml",
"chars": 138,
"preview": "version: 2\nupdates:\n - package-ecosystem: github-actions\n directory: /\n target-branch: devel\n schedule:\n "
},
{
"path": ".github/workflows/check-changelog.yml",
"chars": 335,
"preview": "name: Check-changelog\non:\n pull_request:\n types: [assigned, opened, synchronize, reopened, labeled, unlabeled]\n b"
},
{
"path": ".github/workflows/dockgen.yml",
"chars": 1448,
"preview": "name: \"Publish docker image\"\n\non:\n push:\n branches:\n - devel\n tags:\n - \"v*\"\n\njobs:\n dockgen:\n runs-"
},
{
"path": ".github/workflows/macos-linux-pip.yml",
"chars": 1548,
"preview": "name: CI - MacOS/Linux via pip\n\non:\n push:\n branches:\n - devel\n paths-ignore:\n - .gitlab-ci.yml\n -"
},
{
"path": ".github/workflows/macos-linux-windows-pixi.yml",
"chars": 6677,
"preview": "name: CI - MacOS/Linux/Windows via Pixi\n\non:\n push:\n branches:\n - devel\n paths-ignore:\n - .gitlab-ci.ym"
},
{
"path": ".github/workflows/nix.yml",
"chars": 860,
"preview": "name: \"CI - Nix\"\non:\n push:\n branches:\n - devel\n pull_request:\nconcurrency:\n group: ${{ github.workflow }}-${"
},
{
"path": ".github/workflows/ros_ci.yml",
"chars": 2176,
"preview": "# This config uses industrial_ci (https://github.com/ros-industrial/industrial_ci.git).\n# For troubleshooting, see readm"
},
{
"path": ".github/workflows/update-flake-lock.yml",
"chars": 962,
"preview": "name: update-flake-lock\non:\n workflow_dispatch:\n schedule:\n - cron: '0 11 12 * *'\njobs:\n update-flake-inputs:\n "
},
{
"path": ".github/workflows/update_pixi_lockfile.yml",
"chars": 1363,
"preview": "name: CI - Update Pixi lockfile\npermissions:\n contents: write\n pull-requests: write\n\non:\n workflow_dispatch:\n schedu"
},
{
"path": ".gitignore",
"chars": 84,
"preview": "build*/\nXcode/*\n*~\n*.pyc\n.cache/\n__pycache__/\n\n# pixi environments\n.pixi\n*.egg-info\n"
},
{
"path": ".gitlab-ci.yml",
"chars": 63,
"preview": "include: https://rainboard.laas.fr/project/coal/.gitlab-ci.yml\n"
},
{
"path": ".gitmodules",
"chars": 110,
"preview": "[submodule \"cmake\"]\n\tbranch = master\n\tpath = cmake\n\turl = https://github.com/jrl-umi3218/jrl-cmakemodules.git\n"
},
{
"path": ".pre-commit-config.yaml",
"chars": 570,
"preview": "ci:\n autoupdate_branch: devel\n autofix_prs: false\n autoupdate_schedule: quarterly\n submodules: true\nrepos:\n- repo: h"
},
{
"path": "CHANGELOG.md",
"chars": 44796,
"preview": "# Changelog\n\nAll notable changes to this project will be documented in this file.\n\nThe format is based on [Keep a Change"
},
{
"path": "CITATION.bib",
"chars": 316,
"preview": "@misc{coalweb,\n author = {Jia Pan and Sachin Chitta and Dinesh Manocha and Florent Lamiraux and Joseph Mirabel and Jus"
},
{
"path": "CITATION.cff",
"chars": 703,
"preview": "cff-version: 1.2.0\nmessage: \"Thanks for using Coal. Please use the following metadata to cite us in your documents.\"\naut"
},
{
"path": "CMakeLists.txt",
"chars": 21880,
"preview": "#\n# Software License Agreement (BSD License)\n#\n# Copyright (c) 2014-2025 CNRS-LAAS, INRIA Author: Florent Lamiraux, Jose"
},
{
"path": "LICENSE",
"chars": 1710,
"preview": "Software License Agreement (BSD License)\n\n Copyright (c) 2008-2014, Willow Garage, Inc.\n Copyright (c) 2014-2015, Open S"
},
{
"path": "README.md",
"chars": 13345,
"preview": "# Coal — An extension of the Flexible Collision Library\n\n<p align=\"center\">\n <a href=\"https://gitlab.laas.fr/coal-libra"
},
{
"path": "colcon.pkg",
"chars": 121,
"preview": "{\n \"hooks\": [\n \"share/hpp-fcl/hook/ament_prefix_path.dsv\",\n \"share/hpp-fcl/hook/python_path.dsv\"\n ]\n"
},
{
"path": "development/build.md",
"chars": 636,
"preview": "# Build and install from source with Pixi\n\nTo build Coal from source the easiest way is to use [Pixi](https://pixi.sh/la"
},
{
"path": "development/release.md",
"chars": 857,
"preview": "# Release with Pixi\n\nTo create a release with Pixi run the following commands on the **devel** branch:\n\n```bash\nCOAL_VER"
},
{
"path": "development/scripts/pixi/activation.bat",
"chars": 462,
"preview": ":: Find Python executable path for nanobind and Boost.Python\nfor /f \"tokens=*\" %%i in ('python -c \"import sys; print(sys"
},
{
"path": "development/scripts/pixi/activation.sh",
"chars": 1437,
"preview": "#! /bin/bash\n# Activation script\n\n# Remove flags setup from cxx-compiler\nunset CFLAGS\nunset CPPFLAGS\nunset CXXFLAGS\nunse"
},
{
"path": "doc/CMakeLists.txt",
"chars": 1027,
"preview": "set(DOXYGEN_XML_OUTPUT \"doxygen-xml\" PARENT_SCOPE)\nset(DOXYGEN_FILE_PATTERNS \"*.h *.hh *.hxx\" PARENT_SCOPE)\nset(DOXYGE"
},
{
"path": "doc/Doxyfile.extra.in",
"chars": 17,
"preview": "USE_MATHJAX= YES\n"
},
{
"path": "doc/generate_distance_plot.py",
"chars": 1528,
"preview": "import matplotlib.pyplot as plt\nimport numpy as np\n\ninteractive = False\n\nm = 1.0\nb = 1.2\n\nmb = m + b\n\nX = np.array([-mb "
},
{
"path": "doc/gjk.py",
"chars": 18025,
"preview": "#!/usr/bin/env python3\nimport pdb\nimport sys\n\n# ABC = AB^AC\n# (ABC^AJ).a = (j.c - j.b) a.a + (j.a - j.c) b.a + (j.b - j."
},
{
"path": "doc/mesh-mesh-collision-call.dot",
"chars": 6814,
"preview": "digraph CD {\n\n\trankdir = BT\n\tcompound=true\n size = 11.7\n\n \"std::size_t BVHCollide(const CollisionGeometry"
},
{
"path": "doc/notes",
"chars": 2522,
"preview": "In include/hpp/fcl/traversal:\n\n - some initialize method compute the position of all triangles in\n global frame befo"
},
{
"path": "doc/python/doxygen-boost.hh",
"chars": 5176,
"preview": "#ifndef DOXYGEN_BOOST_DOC_HH\n#define DOXYGEN_BOOST_DOC_HH\n\n#ifndef DOXYGEN_DOC_HH\n#error \"You should have included doxyg"
},
{
"path": "doc/python/doxygen.hh",
"chars": 2597,
"preview": "#ifndef DOXYGEN_DOC_HH\n#define DOXYGEN_DOC_HH\n\n#include <boost/preprocessor/repetition.hpp>\n#include <boost/preprocessor"
},
{
"path": "doc/python/doxygen_xml_parser.py",
"chars": 31157,
"preview": "#!/usr/bin/python3\n# ruff: noqa: E501\n\nfrom __future__ import print_function\nfrom lxml import etree\nfrom os import path\n"
},
{
"path": "doc/python/xml_docstring.py",
"chars": 5090,
"preview": "class XmlDocString(object):\n def __init__(self, index):\n self.index = index\n self.tags = {\n "
},
{
"path": "doc/shape-mesh-collision-call.dot",
"chars": 9103,
"preview": "digraph CD {\n\n\trankdir = BT\n\tcompound=true\n size = 11.7\n\n \"BVHShapeCollider<OBBRSS, Shape, NarrowPhaseSol"
},
{
"path": "doc/shape-shape-collision-call.dot",
"chars": 3052,
"preview": "digraph CD {\n\n\trankdir = BT\n\tcompound=true\n size = 11.7\n\n \"template<typename T_SH1, typename T_SH2, typen"
},
{
"path": "dockgen.toml",
"chars": 128,
"preview": "[eigenpy]\nurl = \"github:stack-of-tasks\"\n\n[coal]\nurl = \".\"\napt_deps = [\"libassimp-dev\", \"liboctomap-dev\"]\nsrc_deps = [\"ei"
},
{
"path": "flake.nix",
"chars": 2459,
"preview": "{\n description = \"An extension of the Flexible Collision Library\";\n\n inputs = {\n gepetto.url = \"github:gepetto/nix\""
},
{
"path": "hpp-fclConfig.cmake",
"chars": 1081,
"preview": "# This file provide bacward compatiblity for `find_package(hpp-fcl)`.\n\nif(NOT COAL_DISABLE_HPP_FCL_WARNINGS)\n message(\n"
},
{
"path": "include/coal/BV/AABB.h",
"chars": 8855,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/BV/BV.h",
"chars": 9265,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/BV/BV_node.h",
"chars": 6104,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/BV/OBB.h",
"chars": 5645,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/BV/OBBRSS.h",
"chars": 5637,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/BV/RSS.h",
"chars": 6431,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/BV/kDOP.h",
"chars": 6955,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/BV/kIOS.h",
"chars": 6197,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/BVH/BVH_front.h",
"chars": 2945,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/BVH/BVH_internal.h",
"chars": 3735,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/BVH/BVH_model.h",
"chars": 17033,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/BVH/BVH_utility.h",
"chars": 5502,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/alloca.h",
"chars": 3854,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2026, Inria\n * All rights reserved.\n *\n * Redistri"
},
{
"path": "include/coal/broadphase/broadphase.h",
"chars": 2217,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2022, Inria\n * All rights reserved.\n *\n * Redistri"
},
{
"path": "include/coal/broadphase/broadphase_SSaP.h",
"chars": 5621,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/broadphase_SaP.h",
"chars": 6926,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/broadphase_bruteforce.h",
"chars": 4201,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/broadphase_callbacks.h",
"chars": 3920,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2022, INRIA\n * All rights reserved.\n *\n * Redistri"
},
{
"path": "include/coal/broadphase/broadphase_collision_manager.h",
"chars": 6543,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/broadphase_continuous_collision_manager-inl.h",
"chars": 3180,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/broadphase_continuous_collision_manager.h",
"chars": 5999,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/broadphase_dynamic_AABB_tree-inl.h",
"chars": 8487,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/broadphase_dynamic_AABB_tree.h",
"chars": 5371,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/broadphase_dynamic_AABB_tree_array-inl.h",
"chars": 8616,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/broadphase_dynamic_AABB_tree_array.h",
"chars": 5328,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/broadphase_interval_tree.h",
"chars": 6050,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/broadphase_spatialhash-inl.h",
"chars": 17662,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/broadphase_spatialhash.h",
"chars": 6480,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/default_broadphase_callbacks.h",
"chars": 10212,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2020, Toyota Research Institute\n * Copyright (c) 20"
},
{
"path": "include/coal/broadphase/detail/hierarchy_tree-inl.h",
"chars": 33697,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/hierarchy_tree.h",
"chars": 11103,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/hierarchy_tree_array-inl.h",
"chars": 31456,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/hierarchy_tree_array.h",
"chars": 10139,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/interval_tree.h",
"chars": 4175,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/interval_tree_node-inl.h",
"chars": 3330,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/interval_tree_node.h",
"chars": 2843,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/morton-inl.h",
"chars": 5533,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/morton.h",
"chars": 3817,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/node_base-inl.h",
"chars": 2956,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/node_base.h",
"chars": 2525,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/node_base_array-inl.h",
"chars": 2439,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/node_base_array.h",
"chars": 2346,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/simple_hash_table-inl.h",
"chars": 4273,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/simple_hash_table.h",
"chars": 2890,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/simple_interval-inl.h",
"chars": 2306,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/simple_interval.h",
"chars": 2334,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/sparse_hash_table-inl.h",
"chars": 4428,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/sparse_hash_table.h",
"chars": 3106,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/spatial_hash-inl.h",
"chars": 3371,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/broadphase/detail/spatial_hash.h",
"chars": 2295,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/collision.h",
"chars": 5460,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/collision_data.h",
"chars": 68991,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/collision_func_matrix.h",
"chars": 3338,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/collision_object.h",
"chars": 11860,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/collision_utility.h",
"chars": 2079,
"preview": "// Copyright (c) 2017 CNRS\n// Copyright (c) 2022 INRIA\n// Authors: Joseph Mirabel (joseph.mirabel@laas.fr)\n//\n// This fi"
},
{
"path": "include/coal/contact_patch/contact_patch_simplifier.h",
"chars": 4382,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2025, INRIA\n * All rights reserved.\n * Redistribut"
},
{
"path": "include/coal/contact_patch/contact_patch_solver.h",
"chars": 10071,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2024, INRIA\n * All rights reserved.\n * Redistribut"
},
{
"path": "include/coal/contact_patch/contact_patch_solver.hxx",
"chars": 17592,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2024, INRIA\n * All rights reserved.\n *\n * Redistri"
},
{
"path": "include/coal/contact_patch/polygon_convex_hull.h",
"chars": 949,
"preview": "//\n// Copyright (c) 2026 INRIA\n//\n\n#ifndef COAL_CONTACT_PATCH_POLYGON_CONVEX_HULL_H\n#define COAL_CONTACT_PATCH_POLYGON_C"
},
{
"path": "include/coal/contact_patch.h",
"chars": 5771,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2024, INRIA\n * All rights reserved.\n *\n * Redistri"
},
{
"path": "include/coal/contact_patch_func_matrix.h",
"chars": 3874,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2024, INRIA\n * All rights reserved.\n *\n * Redistri"
},
{
"path": "include/coal/data_types.h",
"chars": 10239,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/distance.h",
"chars": 5017,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/distance_func_matrix.h",
"chars": 3197,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/doc.hh",
"chars": 3493,
"preview": "//\n// Software License Agreement (BSD License)\n//\n// Copyright (c) 2014 CNRS-LAAS\n// Author: Florent Lamiraux\n// All "
},
{
"path": "include/coal/fwd.hh",
"chars": 6290,
"preview": "//\n// Software License Agreement (BSD License)\n//\n// Copyright (c) 2014, CNRS-LAAS\n// Copyright (c) 2022-2024, Inria\n/"
},
{
"path": "include/coal/hfield.h",
"chars": 19012,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2021-2024, INRIA\n * All rights reserved.\n *\n * Red"
},
{
"path": "include/coal/internal/BV_fitter.h",
"chars": 7445,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/internal/BV_splitter.h",
"chars": 9230,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/internal/intersect.h",
"chars": 8577,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/internal/intersect.hxx",
"chars": 11875,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/internal/shape_shape_contact_patch_func.h",
"chars": 15837,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2024, INRIA\n * All rights reserved.\n *\n * Redistri"
},
{
"path": "include/coal/internal/shape_shape_func.h",
"chars": 17664,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2014, CNRS-LAAS\n * Copyright (c) 2024, INRIA\n * Al"
},
{
"path": "include/coal/internal/tools.h",
"chars": 7130,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/internal/traversal.h",
"chars": 2484,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2019, LAAS CNRS\n * All rights reserved.\n *\n * Redi"
},
{
"path": "include/coal/internal/traversal_node_base.h",
"chars": 6002,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/internal/traversal_node_bvh_hfield.h",
"chars": 18764,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2021, INRIA\n * All rights reserved.\n *\n * Redistri"
},
{
"path": "include/coal/internal/traversal_node_bvh_shape.h",
"chars": 16682,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/internal/traversal_node_bvhs.h",
"chars": 18928,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/internal/traversal_node_hfield_shape.h",
"chars": 27223,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2021-2024, INRIA.\n * All rights reserved.\n *\n * Re"
},
{
"path": "include/coal/internal/traversal_node_octree.h",
"chars": 48673,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/internal/traversal_node_setup.h",
"chars": 26778,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/internal/traversal_node_shapes.h",
"chars": 3935,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/internal/traversal_recurse.h",
"chars": 3395,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/logging.h",
"chars": 2367,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2024, INRIA\n * All rights reserved.\n *\n * Redistri"
},
{
"path": "include/coal/math/matrix_3f.h",
"chars": 1965,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/math/transform.h",
"chars": 9868,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/math/types.h",
"chars": 1974,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/math/vec_3f.h",
"chars": 1959,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/mesh_loader/assimp.h",
"chars": 4264,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/mesh_loader/loader.h",
"chars": 3613,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/narrowphase/gjk.h",
"chars": 17353,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/narrowphase/minkowski_difference.h",
"chars": 8555,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/narrowphase/narrowphase.h",
"chars": 34099,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/narrowphase/narrowphase_defaults.h",
"chars": 2700,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2024, INRIA\n * All rights reserved.\n *\n * Redistri"
},
{
"path": "include/coal/narrowphase/support_data.h",
"chars": 3176,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/narrowphase/support_functions.h",
"chars": 15498,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/octree.h",
"chars": 11664,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/serialization/AABB.h",
"chars": 487,
"preview": "//\n// Copyright (c) 2021 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_AABB_H\n#define COAL_SERIALIZATION_AABB_H\n\n#include \"coal/B"
},
{
"path": "include/coal/serialization/BVH_model.h",
"chars": 8023,
"preview": "//\n// Copyright (c) 2021-2022 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_BVH_MODEL_H\n#define COAL_SERIALIZATION_BVH_MODEL_H\n\n#"
},
{
"path": "include/coal/serialization/BV_node.h",
"chars": 922,
"preview": "//\n// Copyright (c) 2021 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_BV_NODE_H\n#define COAL_SERIALIZATION_BV_NODE_H\n\n#include \""
},
{
"path": "include/coal/serialization/BV_splitter.h",
"chars": 1842,
"preview": "//\n// Copyright (c) 2021 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_BV_SPLITTER_H\n#define COAL_SERIALIZATION_BV_SPLITTER_H\n\n#i"
},
{
"path": "include/coal/serialization/OBB.h",
"chars": 510,
"preview": "//\n// Copyright (c) 2021 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_OBB_H\n#define COAL_SERIALIZATION_OBB_H\n\n#include \"coal/BV/"
},
{
"path": "include/coal/serialization/OBBRSS.h",
"chars": 560,
"preview": "//\n// Copyright (c) 2021 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_OBBRSS_H\n#define COAL_SERIALIZATION_OBBRSS_H\n\n#include \"co"
},
{
"path": "include/coal/serialization/RSS.h",
"chars": 562,
"preview": "//\n// Copyright (c) 2021 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_RSS_H\n#define COAL_SERIALIZATION_RSS_H\n\n#include \"coal/BV/"
},
{
"path": "include/coal/serialization/archive.h",
"chars": 8963,
"preview": "//\n// Copyright (c) 2017-2024 CNRS INRIA\n// This file was borrowed from the Pinocchio library:\n// https://github.com/sta"
},
{
"path": "include/coal/serialization/collision_data.h",
"chars": 7473,
"preview": "//\n// Copyright (c) 2021 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_COLLISION_DATA_H\n#define COAL_SERIALIZATION_COLLISION_DATA"
},
{
"path": "include/coal/serialization/collision_object.h",
"chars": 2750,
"preview": "//\n// Copyright (c) 2021 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_COLLISION_OBJECT_H\n#define COAL_SERIALIZATION_COLLISION_OB"
},
{
"path": "include/coal/serialization/contact_patch.h",
"chars": 2623,
"preview": "//\n// Copyright (c) 2024 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_CONTACT_PATCH_H\n#define COAL_SERIALIZATION_CONTACT_PATCH_H"
},
{
"path": "include/coal/serialization/convex.h",
"chars": 5925,
"preview": "//\n// Copyright (c) 2022-2024 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_CONVEX_H\n#define COAL_SERIALIZATION_CONVEX_H\n\n#includ"
},
{
"path": "include/coal/serialization/eigen.h",
"chars": 4830,
"preview": "//\n// Copyright (c) 2017-2021 CNRS INRIA\n//\n\n/*\n Code adapted from Pinocchio and\n https://gist.githubusercontent.com/mta"
},
{
"path": "include/coal/serialization/fwd.h",
"chars": 4446,
"preview": "//\n// Copyright (c) 2021-2024 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_FWD_H\n#define COAL_SERIALIZATION_FWD_H\n\n#include <typ"
},
{
"path": "include/coal/serialization/geometric_shapes.h",
"chars": 4055,
"preview": "//\n// Copyright (c) 2021-2024 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_GEOMETRIC_SHAPES_H\n#define COAL_SERIALIZATION_GEOMETR"
},
{
"path": "include/coal/serialization/hfield.h",
"chars": 2399,
"preview": "//\n// Copyright (c) 2021-2024 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_HFIELD_H\n#define COAL_SERIALIZATION_HFIELD_H\n\n#includ"
},
{
"path": "include/coal/serialization/kDOP.h",
"chars": 761,
"preview": "//\n// Copyright (c) 2024 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_kDOP_H\n#define COAL_SERIALIZATION_kDOP_H\n\n#include \"coal/B"
},
{
"path": "include/coal/serialization/kIOS.h",
"chars": 1727,
"preview": "//\n// Copyright (c) 2024 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_kIOS_H\n#define COAL_SERIALIZATION_kIOS_H\n\n#include \"coal/B"
},
{
"path": "include/coal/serialization/memory.h",
"chars": 749,
"preview": "//\n// Copyright (c) 2021 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_MEMORY_H\n#define COAL_SERIALIZATION_MEMORY_H\n\nnamespace co"
},
{
"path": "include/coal/serialization/octree.h",
"chars": 3314,
"preview": "//\n// Copyright (c) 2023-2024 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_OCTREE_H\n#define COAL_SERIALIZATION_OCTREE_H\n\n#includ"
},
{
"path": "include/coal/serialization/quadrilateral.h",
"chars": 670,
"preview": "//\n// Copyright (c) 2022 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_QUADRILATERAL_H\n#define COAL_SERIALIZATION_QUADRILATERAL_H"
},
{
"path": "include/coal/serialization/serializer.h",
"chars": 2947,
"preview": "//\n// Copyright (c) 2024 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_SERIALIZER_H\n#define COAL_SERIALIZATION_SERIALIZER_H\n\n#inc"
},
{
"path": "include/coal/serialization/transform.h",
"chars": 527,
"preview": "//\n// Copyright (c) 2024 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_TRANSFORM_H\n#define COAL_SERIALIZATION_TRANSFORM_H\n\n#inclu"
},
{
"path": "include/coal/serialization/triangle.h",
"chars": 595,
"preview": "//\n// Copyright (c) 2021-2022 INRIA\n//\n\n#ifndef COAL_SERIALIZATION_TRIANGLE_H\n#define COAL_SERIALIZATION_TRIANGLE_H\n\n#in"
},
{
"path": "include/coal/shape/convex.h",
"chars": 6213,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/shape/convex.hxx",
"chars": 11096,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2019, CNRS - LAAS\n * All rights reserved.\n *\n * Re"
},
{
"path": "include/coal/shape/geometric_shape_to_BVH_model.h",
"chars": 12187,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/shape/geometric_shapes.h",
"chars": 37731,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/shape/geometric_shapes.hxx",
"chars": 8120,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/shape/geometric_shapes_traits.h",
"chars": 4564,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/shape/geometric_shapes_utility.h",
"chars": 11284,
"preview": "/*\n * Software License Agreement (BSD License)\n *\n * Copyright (c) 2011-2014, Willow Garage, Inc.\n * Copyright (c) 201"
},
{
"path": "include/coal/shared_ptr_comparison.h",
"chars": 2294,
"preview": "//\n// Software License Agreement (BSD License)\n//\n// Copyright (c) 2026, Inria\n// All rights reserved.\n//\n// Redistri"
},
{
"path": "include/coal/third_party/boost/core/data.hpp",
"chars": 1279,
"preview": "/*\nCopyright 2023 Glen Joseph Fernandes\n(glenjofe@gmail.com)\n\nDistributed under the Boost Software License, Version 1.0."
},
{
"path": "include/coal/third_party/boost/core/detail/assert.hpp",
"chars": 441,
"preview": "/*\nCopyright 2025 Glen Joseph Fernandes\n(glenjofe@gmail.com)\n\nDistributed under the Boost Software License, Version 1.0."
},
{
"path": "include/coal/third_party/boost/core/make_span.hpp",
"chars": 1096,
"preview": "/*\nCopyright 2023 Glen Joseph Fernandes\n(glenjofe@gmail.com)\n\nDistributed under the Boost Software License, Version 1.0."
},
{
"path": "include/coal/third_party/boost/core/span.hpp",
"chars": 12262,
"preview": "/*\nCopyright 2019-2023 Glen Joseph Fernandes\n(glenjofe@gmail.com)\n\nDistributed under the Boost Software License, Version"
},
{
"path": "include/coal/timings.h",
"chars": 2837,
"preview": "//\n// Copyright (c) 2021-2025 INRIA\n//\n\n#ifndef COAL_TIMINGS_FWD_H\n#define COAL_TIMINGS_FWD_H\n\n#include \"coal/fwd.hh\"\n\n#"
},
{
"path": "include/hpp/fcl/BV/AABB.h",
"chars": 54,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/BV/AABB.h>\n"
},
{
"path": "include/hpp/fcl/BV/BV.h",
"chars": 52,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/BV/BV.h>\n"
},
{
"path": "include/hpp/fcl/BV/BV_node.h",
"chars": 57,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/BV/BV_node.h>\n"
},
{
"path": "include/hpp/fcl/BV/OBB.h",
"chars": 53,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/BV/OBB.h>\n"
},
{
"path": "include/hpp/fcl/BV/OBBRSS.h",
"chars": 56,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/BV/OBBRSS.h>\n"
},
{
"path": "include/hpp/fcl/BV/RSS.h",
"chars": 53,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/BV/RSS.h>\n"
},
{
"path": "include/hpp/fcl/BV/kDOP.h",
"chars": 54,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/BV/kDOP.h>\n"
},
{
"path": "include/hpp/fcl/BV/kIOS.h",
"chars": 54,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/BV/kIOS.h>\n"
},
{
"path": "include/hpp/fcl/BVH/BVH_front.h",
"chars": 60,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/BVH/BVH_front.h>\n"
},
{
"path": "include/hpp/fcl/BVH/BVH_internal.h",
"chars": 63,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/BVH/BVH_internal.h>\n"
},
{
"path": "include/hpp/fcl/BVH/BVH_model.h",
"chars": 60,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/BVH/BVH_model.h>\n"
},
{
"path": "include/hpp/fcl/BVH/BVH_utility.h",
"chars": 62,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/BVH/BVH_utility.h>\n"
},
{
"path": "include/hpp/fcl/broadphase/broadphase.h",
"chars": 68,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/broadphase/broadphase.h>\n"
},
{
"path": "include/hpp/fcl/broadphase/broadphase_SSaP.h",
"chars": 73,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/broadphase/broadphase_SSaP.h>\n"
},
{
"path": "include/hpp/fcl/broadphase/broadphase_SaP.h",
"chars": 72,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/broadphase/broadphase_SaP.h>\n"
},
{
"path": "include/hpp/fcl/broadphase/broadphase_bruteforce.h",
"chars": 79,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/broadphase/broadphase_bruteforce.h>\n"
},
{
"path": "include/hpp/fcl/broadphase/broadphase_callbacks.h",
"chars": 78,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/broadphase/broadphase_callbacks.h>\n"
},
{
"path": "include/hpp/fcl/broadphase/broadphase_collision_manager.h",
"chars": 86,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/broadphase/broadphase_collision_manager.h>\n"
},
{
"path": "include/hpp/fcl/broadphase/broadphase_continuous_collision_manager-inl.h",
"chars": 101,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/broadphase/broadphase_continuous_collision_manager-inl.h>\n"
},
{
"path": "include/hpp/fcl/broadphase/broadphase_continuous_collision_manager.h",
"chars": 97,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/broadphase/broadphase_continuous_collision_manager.h>\n"
},
{
"path": "include/hpp/fcl/broadphase/broadphase_dynamic_AABB_tree-inl.h",
"chars": 90,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/broadphase/broadphase_dynamic_AABB_tree-inl.h>\n"
},
{
"path": "include/hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h",
"chars": 86,
"preview": "#include <hpp/fcl/coal.hpp>\n#include <coal/broadphase/broadphase_dynamic_AABB_tree.h>\n"
}
]
// ... and 300 more files (download for full content)
About this extraction
This page contains the full source code of the coal-library/coal GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 500 files (4.3 MB), approximately 1.2M tokens, and a symbol index with 1677 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.
Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.