Skip to content

Commit

Permalink
[workspace] Use sdformat and ignition hidden visibility
Browse files Browse the repository at this point in the history
When building C++ code, we should not use -fvisibility=hidden because
it infects all #included code, even the standard library. Instead, we
should wrap the third-party C++ code in a inline hidden namespace.
That way, only the third-party code itself is hidden.
  • Loading branch information
jwnimmer-tri committed Jun 7, 2022
1 parent d95656f commit 017d25b
Show file tree
Hide file tree
Showing 15 changed files with 264 additions and 219 deletions.
2 changes: 1 addition & 1 deletion multibody/parsing/detail_common.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include <string>
#include <variant>

#include <sdf/Element.hh>
#include <drake_vendor/sdf/Element.hh>
#include <tinyxml2.h>

#include "drake/common/diagnostic_policy.h"
Expand Down
2 changes: 1 addition & 1 deletion multibody/parsing/detail_ignition.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#pragma once

#include <ignition/math/Pose3.hh>
#include <drake_vendor/ignition/math/Pose3.hh>

#include "drake/common/eigen_types.h"
#include "drake/math/rigid_transform.h"
Expand Down
2 changes: 1 addition & 1 deletion multibody/parsing/detail_sdf_diagnostic.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#include <set>
#include <string>

#include <sdf/Element.hh>
#include <drake_vendor/sdf/Element.hh>

#include "drake/common/diagnostic_policy.h"

Expand Down
14 changes: 7 additions & 7 deletions multibody/parsing/detail_sdf_geometry.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,13 @@
#include <string>
#include <utility>

#include <sdf/Box.hh>
#include <sdf/Capsule.hh>
#include <sdf/Cylinder.hh>
#include <sdf/Element.hh>
#include <sdf/Ellipsoid.hh>
#include <sdf/Plane.hh>
#include <sdf/Sphere.hh>
#include <drake_vendor/sdf/Box.hh>
#include <drake_vendor/sdf/Capsule.hh>
#include <drake_vendor/sdf/Cylinder.hh>
#include <drake_vendor/sdf/Element.hh>
#include <drake_vendor/sdf/Ellipsoid.hh>
#include <drake_vendor/sdf/Plane.hh>
#include <drake_vendor/sdf/Sphere.hh>

#include "drake/geometry/geometry_instance.h"
#include "drake/geometry/proximity_properties.h"
Expand Down
6 changes: 3 additions & 3 deletions multibody/parsing/detail_sdf_geometry.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,9 @@
#include <memory>
#include <string>

#include <sdf/Collision.hh>
#include <sdf/Geometry.hh>
#include <sdf/Visual.hh>
#include <drake_vendor/sdf/Collision.hh>
#include <drake_vendor/sdf/Geometry.hh>
#include <drake_vendor/sdf/Visual.hh>

#include "drake/common/diagnostic_policy.h"
#include "drake/geometry/geometry_instance.h"
Expand Down
18 changes: 9 additions & 9 deletions multibody/parsing/detail_sdf_parser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -10,15 +10,15 @@
#include <variant>
#include <vector>

#include <sdf/Error.hh>
#include <sdf/Frame.hh>
#include <sdf/Joint.hh>
#include <sdf/JointAxis.hh>
#include <sdf/Link.hh>
#include <sdf/Model.hh>
#include <sdf/ParserConfig.hh>
#include <sdf/Root.hh>
#include <sdf/World.hh>
#include <drake_vendor/sdf/Error.hh>
#include <drake_vendor/sdf/Frame.hh>
#include <drake_vendor/sdf/Joint.hh>
#include <drake_vendor/sdf/JointAxis.hh>
#include <drake_vendor/sdf/Link.hh>
#include <drake_vendor/sdf/Model.hh>
#include <drake_vendor/sdf/ParserConfig.hh>
#include <drake_vendor/sdf/Root.hh>
#include <drake_vendor/sdf/World.hh>

#include "drake/geometry/geometry_instance.h"
#include "drake/math/rigid_transform.h"
Expand Down
4 changes: 2 additions & 2 deletions multibody/parsing/test/detail_sdf_geometry_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,10 @@
#include <vector>

#include "fmt/ostream.h"
#include <drake_vendor/sdf/Root.hh>
#include <drake_vendor/sdf/parser.hh>
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include <sdf/Root.hh>
#include <sdf/parser.hh>

#include "drake/common/filesystem.h"
#include "drake/common/find_resource.h"
Expand Down
2 changes: 1 addition & 1 deletion multibody/parsing/test/detail_sdf_parser_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,9 @@
#include <sstream>
#include <stdexcept>

#include <drake_vendor/sdf/parser.hh>
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include <sdf/parser.hh>

#include "drake/common/filesystem.h"
#include "drake/common/find_resource.h"
Expand Down
3 changes: 3 additions & 0 deletions tools/workspace/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,10 @@ drake_py_binary(
srcs = ["vendor_cxx.py"],
visibility = [
# These should all be of the form "@foo_internal//:__pkg__".
"@gz_math_internal//:__pkg__",
"@gz_utils_internal//:__pkg__",
"@qhull_internal//:__pkg__",
"@sdformat_internal//:__pkg__",
"@yaml_cpp_internal//:__pkg__",
],
deps = [":module_py"],
Expand Down
114 changes: 60 additions & 54 deletions tools/workspace/gz_math_internal/package.BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@ load(
"@drake//tools/workspace:check_lists_consistency.bzl",
"check_lists_consistency",
)
load(
"@drake//third_party:com_github_bazelbuild_rules_cc/whole_archive.bzl",
"cc_whole_archive_library",
)
load(
"@drake//tools/install:install.bzl",
"install",
)
load(
"@drake//tools/workspace:vendor_cxx.bzl",
"cc_library_vendored",
)
load("@drake//tools/workspace:generate_file.bzl", "generate_file")

licenses(["notice"]) # Apache-2.0
Expand All @@ -31,12 +31,6 @@ config_setting(
values = {"cpu": "k8"},
)

PROJECT_MAJOR = 6

PROJECT_MINOR = 10

PROJECT_PATCH = 0

# Generates config.hh based on the version numbers in CMake code.
cmake_configure_file(
name = "config",
Expand All @@ -45,11 +39,11 @@ cmake_configure_file(
cmakelists = ["CMakeLists.txt"],
defines = [
"IGN_DESIGNATION=math",
"PROJECT_VERSION_MAJOR=%d" % (PROJECT_MAJOR),
"PROJECT_VERSION_MINOR=%d" % (PROJECT_MINOR),
"PROJECT_VERSION_PATCH=%d" % (PROJECT_PATCH),
"PROJECT_VERSION=%d.%d" % (PROJECT_MAJOR, PROJECT_MINOR),
"PROJECT_VERSION_FULL=%d.%d.%d" % (PROJECT_MAJOR, PROJECT_MINOR, PROJECT_PATCH), # noqa
"PROJECT_VERSION_MAJOR=0",
"PROJECT_VERSION_MINOR=%0",
"PROJECT_VERSION_PATCH=0",
"PROJECT_VERSION=0.0",
"PROJECT_VERSION_FULL=0.0.0",
"PROJECT_NAME_NO_VERSION=ignition-math",
],
)
Expand All @@ -59,12 +53,12 @@ generate_file(
content = """
#pragma once
// Simplified version of visibility and deprecation macros.
#define IGNITION_MATH_VISIBLE __attribute__ ((visibility("default")))
#define IGNITION_MATH_VISIBLE
#define IGN_DEPRECATED(version) __attribute__ ((__deprecated__))
""",
)

public_headers_no_gen = [
_MOST_HDRS = [
"include/ignition/math/Angle.hh",
"include/ignition/math/AxisAlignedBox.hh",
"include/ignition/math/Box.hh",
Expand Down Expand Up @@ -135,63 +129,75 @@ private_headers = [
# public headers in the library. The first line is
# '#include <ignition/math/config.hh>' followed by one line like
# '#include <ignition/math/Angle.hh>' for each non-generated header.
# TODO(jwnimmer-tri) The "include all headers" header file is fine for
# prototyping but has no business being used for production code. Burn
# this with fire once we fix sdformat to stop using it.
drake_generate_include_header(
name = "mathhh_genrule",
out = "include/ignition/math.hh",
hdrs = public_headers_no_gen + [
hdrs = _MOST_HDRS + [
"include/ignition/math/config.hh",
"include/ignition/math/Export.hh",
],
)

check_lists_consistency(
files = private_headers + public_headers_no_gen,
files = private_headers + _MOST_HDRS,
glob_include = ["include/**/*.hh"],
)

public_headers = public_headers_no_gen + [
_HDRS = _MOST_HDRS + [
"include/ignition/math/config.hh",
"include/ignition/math/Export.hh",
"include/ignition/math.hh",
]

# Generates the library. The explicitly listed srcs= matches upstream's
# explicitly listed sources plus private headers. The explicitly listed
# hdrs= matches upstream's public headers.
cc_library(
# The explicitly listed srcs= matches upstream's explicitly listed sources plus
# private headers.
_SRCS = [
"src/Angle.cc",
"src/AxisAlignedBox.cc",
"src/Color.cc",
"src/DiffDriveOdometry.cc",
"src/Frustum.cc",
"src/GaussMarkovProcess.cc",
"src/Helpers.cc",
"src/Kmeans.cc",
"src/Material.cc",
"src/PID.cc",
"src/Rand.cc",
"src/RollingMean.cc",
"src/RotationSpline.cc",
"src/RotationSplinePrivate.cc",
"src/SemanticVersion.cc",
"src/SignalStats.cc",
"src/SpeedLimiter.cc",
"src/SphericalCoordinates.cc",
"src/Spline.cc",
"src/SplinePrivate.cc",
"src/Stopwatch.cc",
"src/Temperature.cc",
"src/Vector3Stats.cc",
] + private_headers

cc_library_vendored(
name = "gz_math",
srcs = [
"src/Angle.cc",
"src/AxisAlignedBox.cc",
"src/Color.cc",
"src/DiffDriveOdometry.cc",
"src/Frustum.cc",
"src/GaussMarkovProcess.cc",
"src/Helpers.cc",
"src/Kmeans.cc",
"src/Material.cc",
"src/PID.cc",
"src/Rand.cc",
"src/RollingMean.cc",
"src/RotationSpline.cc",
"src/RotationSplinePrivate.cc",
"src/SemanticVersion.cc",
"src/SignalStats.cc",
"src/SpeedLimiter.cc",
"src/SphericalCoordinates.cc",
"src/Spline.cc",
"src/SplinePrivate.cc",
"src/Stopwatch.cc",
"src/Temperature.cc",
"src/Vector3Stats.cc",
] + private_headers + public_headers,
copts = [
# TODO(jwnimmer-tri) Ideally, we should use hidden visibility for the
# private builds of our dependencies.
"-w",
srcs = _SRCS,
srcs_vendored = [
x.replace("src/", "drake_src/src/")
for x in _SRCS
],
hdrs = _HDRS,
hdrs_vendored = [
x.replace("include/ignition/", "drake_src/drake_vendor/ignition/")
for x in _HDRS
],
edit_include = {
"ignition/": "drake_vendor/ignition/",
},
copts = ["-w"],
linkstatic = True,
includes = ["include"],
includes = ["drake_src"],
visibility = ["//visibility:public"],
)

Expand Down
2 changes: 0 additions & 2 deletions tools/workspace/gz_math_internal/repository.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,6 @@ load("//tools/workspace:github.bzl", "github_archive")
def gz_math_internal_repository(
name,
mirrors = None):
# When updating this commit, also remember to adjust the PROJECT_*
# constants in ./package.BUILD.bazel to match the new version number.
github_archive(
name = name,
repository = "gazebosim/gz-math",
Expand Down
Loading

0 comments on commit 017d25b

Please sign in to comment.