Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[workspace] Better hide ccd and fcl externals #18678

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions geometry/proximity/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -145,6 +145,7 @@ drake_cc_library(
deps = [
":collision_filter",
":proximity_utilities",
"//common:drake_export",
"//geometry:geometry_ids",
"@fcl_internal//:fcl",
],
Expand Down Expand Up @@ -230,6 +231,7 @@ drake_cc_library(
deps = [
":proximity_utilities",
"//common:default_scalars",
"//common:drake_export",
"//common:essential",
"//geometry:geometry_ids",
"//geometry/query_results:signed_distance_to_point",
Expand All @@ -251,6 +253,7 @@ drake_cc_library(
":distance_to_point_callback",
":proximity_utilities",
"//common:default_scalars",
"//common:drake_export",
"//common:nice_type_name",
"//geometry/query_results:signed_distance_pair",
],
Expand Down Expand Up @@ -284,6 +287,7 @@ drake_cc_library(
deps = [
":collision_filter",
":proximity_utilities",
"//common:drake_export",
"//common:sorted_pair",
"@fcl_internal//:fcl",
"@fmt",
Expand All @@ -308,6 +312,7 @@ drake_cc_library(
":proximity_utilities",
":triangle_surface_mesh",
":volume_mesh",
"//common:drake_export",
"//common:hash",
"//geometry:proximity_properties",
"//geometry/query_results:contact_surface",
Expand Down Expand Up @@ -680,6 +685,7 @@ drake_cc_library(
":collision_filter",
":distance_to_point_callback",
"//common:default_scalars",
"//common:drake_export",
"//common:nice_type_name",
"//geometry/query_results:penetration_as_point_pair",
"//geometry/query_results:signed_distance_to_point",
Expand Down Expand Up @@ -731,6 +737,7 @@ drake_cc_library(
deps = [
":sorted_triplet",
":volume_mesh",
"//common:drake_export",
"//common:sorted_pair",
"//geometry:geometry_ids",
"//geometry:shape_specification",
Expand Down Expand Up @@ -863,6 +870,7 @@ drake_cc_library(
visibility = ["//visibility:private"],
deps = [
":collision_filter",
"//common:drake_export",
"//common:temp_directory",
"//common/test_utilities:eigen_matrix_compare",
"//common/test_utilities:expect_throws_message",
Expand Down
5 changes: 3 additions & 2 deletions geometry/proximity/collisions_exist_callback.h
Original file line number Diff line number Diff line change
@@ -1,15 +1,16 @@
#pragma once

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>

#include "drake/common/drake_assert.h"
#include "drake/common/drake_export.h"
#include "drake/geometry/geometry_ids.h"
#include "drake/geometry/proximity/collision_filter.h"

namespace drake {
namespace geometry {
namespace internal {
namespace has_collisions {
namespace has_collisions DRAKE_NO_EXPORT {

/* Supporting data for the collisions exist callback (see Callback below).
It includes:
Expand Down
5 changes: 3 additions & 2 deletions geometry/proximity/distance_to_point_callback.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,10 @@
#include <unordered_map>
#include <vector>

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>

#include "drake/common/drake_assert.h"
#include "drake/common/drake_export.h"
#include "drake/common/eigen_types.h"
#include "drake/geometry/geometry_ids.h"
#include "drake/geometry/proximity/proximity_utilities.h"
Expand All @@ -18,7 +19,7 @@
namespace drake {
namespace geometry {
namespace internal {
namespace point_distance {
namespace point_distance DRAKE_NO_EXPORT {

/* Supporting data for the distance-to-point callback (see Callback below).
It includes:
Expand Down
5 changes: 3 additions & 2 deletions geometry/proximity/distance_to_shape_callback.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,9 @@
#include <unordered_map>
#include <vector>

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>

#include "drake/common/drake_export.h"
#include "drake/common/eigen_types.h"
#include "drake/common/nice_type_name.h"
#include "drake/geometry/geometry_ids.h"
Expand All @@ -19,7 +20,7 @@
namespace drake {
namespace geometry {
namespace internal {
namespace shape_distance {
namespace shape_distance DRAKE_NO_EXPORT {

/* Supporting data for the shape-to-shape signed distance callback (see
Callback below). It includes:
Expand Down
5 changes: 3 additions & 2 deletions geometry/proximity/find_collision_candidates_callback.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,18 @@
#include <utility>
#include <vector>

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>
#include <fmt/format.h>

#include "drake/common/drake_export.h"
#include "drake/common/sorted_pair.h"
#include "drake/geometry/geometry_ids.h"
#include "drake/geometry/proximity/collision_filter.h"

namespace drake {
namespace geometry {
namespace internal {
namespace find_collision_candidates {
namespace find_collision_candidates DRAKE_NO_EXPORT {

/* Supporting data for the collision candidates callback (see Callback below).
It includes:
Expand Down
5 changes: 3 additions & 2 deletions geometry/proximity/hydroelastic_callback.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,10 @@
#include <utility>
#include <vector>

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>
#include <fmt/format.h>

#include "drake/common/drake_export.h"
#include "drake/common/eigen_types.h"
#include "drake/geometry/geometry_ids.h"
#include "drake/geometry/proximity/collision_filter.h"
Expand All @@ -26,7 +27,7 @@
namespace drake {
namespace geometry {
namespace internal {
namespace hydroelastic {
namespace hydroelastic DRAKE_NO_EXPORT {

/* Supporting data for the shape-to-shape hydroelastic contact callback (see
Callback below). It includes:
Expand Down
5 changes: 3 additions & 2 deletions geometry/proximity/penetration_as_point_pair_callback.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,16 +3,17 @@
#include <unordered_map>
#include <vector>

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>

#include "drake/common/drake_export.h"
#include "drake/geometry/proximity/collision_filter.h"
#include "drake/geometry/query_results/penetration_as_point_pair.h"
#include "drake/math/rigid_transform.h"

namespace drake {
namespace geometry {
namespace internal {
namespace penetration_as_point_pair {
namespace penetration_as_point_pair DRAKE_NO_EXPORT {

/* Supporting data for the detecting collision between geometries and reporting
them as a pair of points (see PenetrationAsPointPair). It includes:
Expand Down
5 changes: 3 additions & 2 deletions geometry/proximity/proximity_utilities.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,16 +5,17 @@
#include <string>
#include <vector>

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>
#include <fmt/format.h>

#include "drake/common/drake_export.h"
#include "drake/geometry/geometry_ids.h"
#include "drake/geometry/proximity/volume_mesh.h"
#include "drake/geometry/shape_specification.h"

namespace drake {
namespace geometry {
namespace internal {
namespace internal DRAKE_NO_EXPORT {

// TODO(SeanCurtis-TRI): Given the dependencies on fcl for this file, the name
// should reflect it so that it doesn't get included in files that will
Expand Down
5 changes: 3 additions & 2 deletions geometry/proximity/test/characterization_utilities.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,11 @@
#include <utility>
#include <vector>

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>
#include <gtest/gtest.h>

#include "drake/common/default_scalars.h"
#include "drake/common/drake_export.h"
#include "drake/common/unused.h"
#include "drake/geometry/proximity/collision_filter.h"
#include "drake/geometry/shape_specification.h"
Expand Down Expand Up @@ -217,7 +218,7 @@ class ShapeConfigurations : public ShapeReifier {
};

/* @name Fcl geometry from drake shape specifications. */
class MakeFclShape : public ShapeReifier {
class DRAKE_NO_EXPORT MakeFclShape : public ShapeReifier {
public:
explicit MakeFclShape(const Shape& shape);

Expand Down
2 changes: 1 addition & 1 deletion geometry/proximity/test/collisions_exist_callback_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include <utility>

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>
#include <gtest/gtest.h>

#include "drake/geometry/proximity/proximity_utilities.h"
Expand Down
2 changes: 1 addition & 1 deletion geometry/proximity/test/distance_sphere_to_shape_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <utility>
#include <vector>

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>
#include <fmt/format.h>
#include <gtest/gtest.h>

Expand Down
2 changes: 1 addition & 1 deletion geometry/proximity/test/distance_to_point_callback_test.cc
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "drake/geometry/proximity/distance_to_point_callback.h"

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>
#include <gtest/gtest.h>

#include "drake/common/test_utilities/eigen_matrix_compare.h"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#include <utility>
#include <vector>

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>
#include <gtest/gtest.h>

#include "drake/geometry/proximity/proximity_utilities.h"
Expand Down
2 changes: 1 addition & 1 deletion geometry/proximity/test/hydroelastic_callback_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#include <utility>
#include <vector>

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>
#include <gtest/gtest.h>

#include "drake/common/test_utilities/expect_no_throw.h"
Expand Down
2 changes: 1 addition & 1 deletion geometry/proximity/test/proximity_utilities_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#include <memory>
#include <sstream>

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>
#include <gtest/gtest.h>

namespace drake {
Expand Down
20 changes: 15 additions & 5 deletions geometry/proximity_engine.cc
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#include <utility>
#include <vector>

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>
#include <fmt/format.h>

#include "drake/common/default_scalars.h"
Expand Down Expand Up @@ -52,6 +52,16 @@ using symbolic::Expression;

namespace {

// Drake compiles FCL using hidden symbol visibility. To avoid visibility
// complaints from the compiler, we need to use hidden subclasses for any
// FCL data types used as member fields of ProximityEngine::Impl. Note
// that FCL Objects on the stack are fine without worrying about hidden;
// it's only Impl member fields that cause trouble.
class FclDynamicAABBTreeCollisionManager
: public fcl::DynamicAABBTreeCollisionManager<double> {};
class MapGeometryIdToFclCollisionObject
: public unordered_map<GeometryId, unique_ptr<CollisionObjectd>> {};

// Returns a copy of the given fcl collision geometry; throws an exception for
// unsupported collision geometry types. This supplements the *missing* cloning
// functionality in FCL. Issue has been submitted to FCL:
Expand Down Expand Up @@ -907,16 +917,16 @@ class ProximityEngine<T>::Impl : public ShapeReifier {

// The BVH of all dynamic geometries; this depends on *all* inputs.
// TODO(SeanCurtis-TRI): Ultimately, this should probably be a cache entry.
fcl::DynamicAABBTreeCollisionManager<double> dynamic_tree_;
FclDynamicAABBTreeCollisionManager dynamic_tree_;

// All of the *dynamic* collision elements (spanning all sources).
unordered_map<GeometryId, unique_ptr<CollisionObjectd>> dynamic_objects_;
MapGeometryIdToFclCollisionObject dynamic_objects_;

// The tree containing all of the anchored geometry.
fcl::DynamicAABBTreeCollisionManager<double> anchored_tree_;
FclDynamicAABBTreeCollisionManager anchored_tree_;

// All of the *anchored* collision elements (spanning *all* sources).
unordered_map<GeometryId, unique_ptr<CollisionObjectd>> anchored_objects_;
MapGeometryIdToFclCollisionObject anchored_objects_;

// The mechanism for dictating collision filtering.
CollisionFilter collision_filter_;
Expand Down
2 changes: 1 addition & 1 deletion geometry/test/proximity_engine_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
#include <utility>
#include <vector>

#include <fcl/fcl.h>
#include <drake_vendor/fcl/fcl.h>
#include <gtest/gtest.h>

#include "drake/common/find_resource.h"
Expand Down
1 change: 1 addition & 0 deletions tools/workspace/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ drake_py_binary(
srcs = ["vendor_cxx.py"],
visibility = [
# These should all be of the form "@foo_internal//:__pkg__".
"@fcl_internal//:__pkg__",
"@gz_math_internal//:__pkg__",
"@gz_utils_internal//:__pkg__",
"@msgpack_internal//:__pkg__",
Expand Down
2 changes: 2 additions & 0 deletions tools/workspace/ccd/package.BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@ CCD_PUBLIC_HEADERS = [
# Options used when building the ccd code. Handled by cmake in upstream code
CCD_COPTS = [
"-Wno-all",
# N.B. Because ccd is C code (not C++ code), we can set hidden visibility
# globally, rather than laundering it though our vendor_cxx tool.
"-fvisibility=hidden",
]

Expand Down
Loading