From 2ec5d3fad5d98e0431af4511d5956d5fcccbea12 Mon Sep 17 00:00:00 2001 From: Shameek Ganguly Date: Tue, 19 Nov 2024 08:50:14 -0800 Subject: [PATCH 1/4] Backport bazel changes partially to harmonic Signed-off-by: Shameek Ganguly --- BUILD.bazel | 776 +++++++++++++++++++++++++++++++++++++++++++++++++++- 1 file changed, 771 insertions(+), 5 deletions(-) diff --git a/BUILD.bazel b/BUILD.bazel index 968198e9..73938be9 100644 --- a/BUILD.bazel +++ b/BUILD.bazel @@ -1,3 +1,7 @@ +load( + "@gz//bazel/lint:lint.bzl", + "add_lint_tests", +) load( "@gz//bazel/skylark:build_defs.bzl", "GZ_FEATURES", @@ -7,10 +11,6 @@ load( "gz_export_header", "gz_include_header", ) -load( - "@gz//bazel/lint:lint.bzl", - "add_lint_tests", -) load( "@rules_license//rules:license.bzl", "license", @@ -62,8 +62,8 @@ gz_include_header( name = "mathhh_genrule", out = "include/gz/math.hh", hdrs = public_headers_no_gen + [ - "include/gz/math/config.hh", "include/gz/math/Export.hh", + "include/gz/math/config.hh", ], ) @@ -100,4 +100,770 @@ test_sources = glob( ], ) for src in test_sources] +cc_library( + name = "AdditivelySeparableScalarField3", + hdrs = ["include/gz/math/AdditivelySeparableScalarField3.hh"], + includes = ["include"], + deps = [ + ":Region3", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "Angle", + srcs = ["src/Angle.cc"], + hdrs = ["include/gz/math/Angle.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":config", + ], +) + +cc_library( + name = "AxisAlignedBox", + srcs = ["src/AxisAlignedBox.cc"], + hdrs = ["include/gz/math/AxisAlignedBox.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":Line3", + ":MassMatrix3", + ":Material", + ":Vector3", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "Box", + hdrs = [ + "include/gz/math/Box.hh", + "include/gz/math/detail/Box.hh", + "include/gz/math/detail/WellOrderedVector.hh", + ], + includes = ["include"], + deps = [ + ":Line2", + ":MassMatrix3", + ":Material", + ":Plane", + ":Triangle3", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "Capsule", + hdrs = [ + "include/gz/math/Capsule.hh", + "include/gz/math/detail/Capsule.hh", + ], + includes = ["include"], + deps = [ + ":Helpers", + ":Inertial", + ":MassMatrix3", + ":Material", + ], +) + +cc_library( + name = "Color", + srcs = ["src/Color.cc"], + hdrs = [ + "include/gz/math/Color.hh", + ], + includes = ["include"], + deps = [ + ":Helpers", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "Cone", + hdrs = [ + "include/gz/math/Cone.hh", + "include/gz/math/detail/Cone.hh", + ], + includes = ["include"], + deps = [ + ":MassMatrix3", + ":Material", + ":Quaternion", + ], +) + +cc_library( + name = "CoordinateVector3", + srcs = ["src/CoordinateVector3.cc"], + hdrs = ["include/gz/math/CoordinateVector3.hh"], + includes = ["include"], + deps = [ + ":Angle", + ":Helpers", + ":Vector3", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "Cylinder", + hdrs = [ + "include/gz/math/Cylinder.hh", + "include/gz/math/detail/Cylinder.hh", + ], + includes = ["include"], + deps = [ + ":MassMatrix3", + ":Material", + ":Quaternion", + ], +) + +cc_library( + name = "DiffDriveOdometry", + srcs = ["src/DiffDriveOdometry.cc"], + hdrs = [ + "include/gz/math/DiffDriveOdometry.hh", + ], + includes = ["include"], + deps = [ + ":Angle", + ":Export", + ":RollingMean", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "Ellipsoid", + hdrs = [ + "include/gz/math/Ellipsoid.hh", + "include/gz/math/detail/Ellipsoid.hh", + ], + includes = ["include"], + deps = [ + ":Helpers", + ":Inertial", + ":MassMatrix3", + ":Material", + ], +) + +cc_library( + name = "Filter", + hdrs = ["include/gz/math/Filter.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":Quaternion", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "Frustum", + srcs = ["src/Frustum.cc"], + hdrs = ["include/gz/math/Frustum.hh"], + includes = ["include"], + deps = [ + ":Angle", + ":AxisAlignedBox", + ":Matrix4", + ":Plane", + ":Pose3", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "GaussMarkovProcess", + srcs = ["src/GaussMarkovProcess.cc"], + hdrs = ["include/gz/math/GaussMarkovProcess.hh"], + includes = ["include"], + deps = [ + ":Export", + ":Rand", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "Graph", + hdrs = [ + "include/gz/math/graph/Edge.hh", + "include/gz/math/graph/Graph.hh", + "include/gz/math/graph/Vertex.hh", + ], + includes = ["include"], + deps = [ + ":Helpers", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "GraphAlgorithms", + hdrs = [ + "include/gz/math/graph/GraphAlgorithms.hh", + ], + includes = ["include"], + deps = [ + ":Graph", + ":Helpers", + ":config", + ], +) + +cc_library( + name = "Helpers", + srcs = ["src/Helpers.cc"], + hdrs = ["include/gz/math/Helpers.hh"], + includes = ["include"], + deps = [ + ":Export", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "Inertial", + hdrs = ["include/gz/math/Inertial.hh"], + includes = ["include"], + deps = [ + ":MassMatrix3", + ":Matrix3", + ":Matrix6", + ":Pose3", + ":config", + ], +) + +cc_library( + name = "InterpolationPoint", + hdrs = [ + "include/gz/math/detail/AxisIndex.hh", + "include/gz/math/detail/InterpolationPoint.hh", + ], + includes = ["include"], + deps = [ + ":Vector2", + ":Vector3", + ], +) + +cc_library( + name = "Interval", + hdrs = ["include/gz/math/Interval.hh"], + includes = ["include"], + deps = [ + ":config", + ], +) + +cc_library( + name = "Kmeans", + srcs = [ + "src/Kmeans.cc", + "src/KmeansPrivate.hh", + ], + hdrs = ["include/gz/math/Kmeans.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":Rand", + ":Vector3", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "Line2", + hdrs = ["include/gz/math/Line2.hh"], + includes = ["include"], + deps = [ + ":Vector2", + ":config", + ], +) + +cc_library( + name = "Line3", + hdrs = ["include/gz/math/Line3.hh"], + includes = ["include"], + deps = [ + ":Vector3", + ":config", + ], +) + +cc_library( + name = "MassMatrix3", + hdrs = ["include/gz/math/MassMatrix3.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":Material", + ":Matrix3", + ":Quaternion", + ":Vector2", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "MaterialType", + hdrs = ["include/gz/math/MaterialType.hh"], + includes = ["include"], + deps = [ + ":Export", + ":config", + ], +) + +cc_library( + name = "Material", + srcs = [ + "src/Material.cc", + "src/MaterialType.hh", + ], + hdrs = ["include/gz/math/Material.hh"], + includes = ["include"], + deps = [ + ":Export", + ":Helpers", + ":MaterialType", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "Matrix3", + hdrs = ["include/gz/math/Matrix3.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "Matrix4", + hdrs = ["include/gz/math/Matrix4.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":Matrix3", + ":Pose3", + ":Quaternion", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "Matrix6", + hdrs = ["include/gz/math/Matrix6.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":Matrix3", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "MecanumDriveOdometry", + srcs = ["src/MecanumDriveOdometry.cc"], + hdrs = ["include/gz/math/MecanumDriveOdometry.hh"], + includes = ["include"], + deps = [ + ":Angle", + ":Export", + ":RollingMean", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "MovingWindowFilter", + hdrs = ["include/gz/math/MovingWindowFilter.hh"], + includes = ["include"], + deps = [ + ":Export", + ":Vector3", + ":config", + "@googletest//:gtest", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "OrientedBox", + hdrs = ["include/gz/math/OrientedBox.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":MassMatrix3", + ":Material", + ":Matrix4", + ":Pose3", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "PID", + srcs = ["src/PID.cc"], + hdrs = ["include/gz/math/PID.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "PiecewiseScalarField3", + hdrs = ["include/gz/math/PiecewiseScalarField3.hh"], + includes = ["include"], + deps = [ + ":Region3", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "Plane", + hdrs = ["include/gz/math/Plane.hh"], + includes = ["include"], + deps = [ + ":AxisAlignedBox", + ":Line2", + ":Quaternion", + ":Vector2", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "Polynomial3", + hdrs = ["include/gz/math/Polynomial3.hh"], + includes = ["include"], + deps = [ + ":Interval", + ":Vector4", + ":config", + ], +) + +cc_library( + name = "Pose3", + hdrs = ["include/gz/math/Pose3.hh"], + includes = ["include"], + deps = [ + ":Quaternion", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "Quaternion", + hdrs = ["include/gz/math/Quaternion.hh"], + includes = ["include"], + deps = [ + ":Angle", + ":Helpers", + ":Matrix3", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "Rand", + srcs = ["src/Rand.cc"], + hdrs = ["include/gz/math/Rand.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":config", + ], +) + +cc_library( + name = "Region3", + hdrs = ["include/gz/math/Region3.hh"], + includes = ["include"], + deps = [ + ":Interval", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "RollingMean", + srcs = ["src/RollingMean.cc"], + hdrs = ["include/gz/math/RollingMean.hh"], + includes = ["include"], + deps = [ + ":Export", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "RotationSpline", + srcs = ["src/RotationSpline.cc"], + hdrs = ["include/gz/math/RotationSpline.hh"], + includes = ["include"], + deps = [ + ":Quaternion", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "SemanticVersion", + srcs = ["src/SemanticVersion.cc"], + hdrs = ["include/gz/math/SemanticVersion.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "SignalStats", + srcs = ["src/SignalStats.cc"], + hdrs = ["include/gz/math/SignalStats.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "SpeedLimiter", + srcs = ["src/SpeedLimiter.cc"], + hdrs = ["include/gz/math/SpeedLimiter.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "Sphere", + hdrs = [ + "include/gz/math/Sphere.hh", + "include/gz/math/detail/Sphere.hh", + ], + includes = ["include"], + deps = [ + ":MassMatrix3", + ":Material", + ":Plane", + ":Quaternion", + ], +) + +cc_library( + name = "SphericalCoordinates", + srcs = ["src/SphericalCoordinates.cc"], + hdrs = ["include/gz/math/SphericalCoordinates.hh"], + includes = ["include"], + deps = [ + ":Angle", + ":CoordinateVector3", + ":Helpers", + ":Matrix3", + ":Vector3", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "Spline", + srcs = [ + "src/Spline.cc", + "src/SplinePrivate.cc", + "src/SplinePrivate.hh", + ], + hdrs = ["include/gz/math/Spline.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":Matrix4", + ":Vector3", + ":Vector4", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "Stopwatch", + srcs = [ + "src/Stopwatch.cc", + ], + hdrs = ["include/gz/math/Stopwatch.hh"], + includes = ["include"], + deps = [ + ":Export", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "Temperature", + srcs = [ + "src/Temperature.cc", + ], + hdrs = ["include/gz/math/Temperature.hh"], + includes = ["include"], + deps = [ + ":Export", + ":Helpers", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "TimeVaryingVolumetricGrid", + hdrs = ["include/gz/math/TimeVaryingVolumetricGrid.hh"], + includes = ["include"], + deps = [ + ":TimeVaryingVolumetricGridLookupField", + ":Vector3", + ], +) + +cc_library( + name = "TimeVaryingVolumetricGridLookupField", + hdrs = ["include/gz/math/TimeVaryingVolumetricGridLookupField.hh"], + includes = ["include"], + deps = [ + ":InterpolationPoint", + ":VolumetricGridLookupField", + ], +) + +cc_library( + name = "Triangle", + hdrs = ["include/gz/math/Triangle.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":Line2", + ":Vector2", + ":config", + ], +) + +cc_library( + name = "Triangle3", + hdrs = ["include/gz/math/Triangle3.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":Line3", + ":Plane", + ":Vector3", + ":config", + ], +) + +cc_library( + name = "Vector2", + hdrs = ["include/gz/math/Vector2.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":config", + ], +) + +cc_library( + name = "Vector3", + hdrs = ["include/gz/math/Vector3.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":config", + ], +) + +cc_library( + name = "Vector3Stats", + srcs = ["src/Vector3Stats.cc"], + hdrs = ["include/gz/math/Vector3Stats.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":SignalStats", + ":Vector3", + ":config", + GZ_ROOT + "utils", + ], +) + +cc_library( + name = "Vector4", + hdrs = ["include/gz/math/Vector4.hh"], + includes = ["include"], + deps = [ + ":Helpers", + ":Matrix4", + ":config", + ], +) + +cc_library( + name = "VolumetricGridLookupField", + hdrs = ["include/gz/math/VolumetricGridLookupField.hh"], + includes = ["include"], + deps = [ + ":InterpolationPoint", + ":Vector3", + ], +) + add_lint_tests() From 38ecf69f857127db5ea2d27469b802bd98e1f1f1 Mon Sep 17 00:00:00 2001 From: Shameek Ganguly Date: Tue, 19 Nov 2024 12:48:35 -0800 Subject: [PATCH 2/4] Update BUILD rules Signed-off-by: Shameek Ganguly --- BUILD.bazel | 207 +++++++++++++++++++++++++++------------------ eigen3/BUILD.bazel | 38 ++++++++- 2 files changed, 160 insertions(+), 85 deletions(-) diff --git a/BUILD.bazel b/BUILD.bazel index 73938be9..9aa68dfc 100644 --- a/BUILD.bazel +++ b/BUILD.bazel @@ -51,13 +51,6 @@ public_headers_no_gen = glob([ "include/gz/math/graph/*.hh", ]) -private_headers = glob(["src/*.hh"]) - -sources = glob( - ["src/*.cc"], - exclude = ["src/*_TEST.cc"], -) - gz_include_header( name = "mathhh_genrule", out = "include/gz/math.hh", @@ -67,18 +60,69 @@ gz_include_header( ], ) -public_headers = public_headers_no_gen + [ - "include/gz/math/config.hh", - "include/gz/math/Export.hh", - "include/gz/math.hh", -] - cc_library( name = "math", - srcs = sources + private_headers, - hdrs = public_headers, + hdrs = ["include/gz/math.hh"], includes = ["include"], deps = [ + ":AdditivelySeparableScalarField3", + ":Angle", + ":AxisAlignedBox", + ":Box", + ":Capsule", + ":Color", + ":Cone", + ":Cylinder", + ":DiffDriveOdometry", + ":Ellipsoid", + ":Filter", + ":Frustum", + ":GaussMarkovProcess", + ":Graph", + ":GraphAlgorithms", + ":Helpers", + ":Inertial", + ":InterpolationPoint", + ":Interval", + ":Kmeans", + ":Line2", + ":Line3", + ":MassMatrix3", + ":Material", + ":MaterialType", + ":Matrix3", + ":Matrix4", + ":Matrix6", + ":MecanumDriveOdometry", + ":MovingWindowFilter", + ":OrientedBox", + ":PID", + ":PiecewiseScalarField3", + ":Plane", + ":Polynomial3", + ":Pose3", + ":Quaternion", + ":Rand", + ":Region3", + ":RollingMean", + ":RotationSpline", + ":SemanticVersion", + ":SignalStats", + ":SpeedLimiter", + ":Sphere", + ":SphericalCoordinates", + ":Spline", + ":Stopwatch", + ":Temperature", + ":TimeVaryingVolumetricGrid", + ":TimeVaryingVolumetricGridLookupField", + ":Triangle", + ":Triangle3", + ":Vector2", + ":Vector3", + ":Vector3Stats", + ":Vector4", + ":VolumetricGridLookupField", GZ_ROOT + "utils", ], ) @@ -100,14 +144,26 @@ test_sources = glob( ], ) for src in test_sources] +cc_library( + name = "Config", + hdrs = ["include/gz/math/config.hh"], + includes = ["include"], +) + +cc_library( + name = "Export", + hdrs = ["include/gz/math/Export.hh"], + includes = ["include"], +) + cc_library( name = "AdditivelySeparableScalarField3", hdrs = ["include/gz/math/AdditivelySeparableScalarField3.hh"], includes = ["include"], deps = [ + ":Config", ":Region3", ":Vector3", - ":config", ], ) @@ -117,8 +173,8 @@ cc_library( hdrs = ["include/gz/math/Angle.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", - ":config", ], ) @@ -128,12 +184,12 @@ cc_library( hdrs = ["include/gz/math/AxisAlignedBox.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", ":Line3", ":MassMatrix3", ":Material", ":Vector3", - ":config", GZ_ROOT + "utils", ], ) @@ -147,13 +203,13 @@ cc_library( ], includes = ["include"], deps = [ + ":Config", ":Line2", ":MassMatrix3", ":Material", ":Plane", ":Triangle3", ":Vector3", - ":config", ], ) @@ -180,9 +236,9 @@ cc_library( ], includes = ["include"], deps = [ + ":Config", ":Helpers", ":Vector3", - ":config", ], ) @@ -200,20 +256,6 @@ cc_library( ], ) -cc_library( - name = "CoordinateVector3", - srcs = ["src/CoordinateVector3.cc"], - hdrs = ["include/gz/math/CoordinateVector3.hh"], - includes = ["include"], - deps = [ - ":Angle", - ":Helpers", - ":Vector3", - ":config", - GZ_ROOT + "utils", - ], -) - cc_library( name = "Cylinder", hdrs = [ @@ -237,9 +279,9 @@ cc_library( includes = ["include"], deps = [ ":Angle", + ":Config", ":Export", ":RollingMean", - ":config", GZ_ROOT + "utils", ], ) @@ -264,10 +306,10 @@ cc_library( hdrs = ["include/gz/math/Filter.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", ":Quaternion", ":Vector3", - ":config", ], ) @@ -279,10 +321,10 @@ cc_library( deps = [ ":Angle", ":AxisAlignedBox", + ":Config", ":Matrix4", ":Plane", ":Pose3", - ":config", GZ_ROOT + "utils", ], ) @@ -293,9 +335,9 @@ cc_library( hdrs = ["include/gz/math/GaussMarkovProcess.hh"], includes = ["include"], deps = [ + ":Config", ":Export", ":Rand", - ":config", GZ_ROOT + "utils", ], ) @@ -309,8 +351,8 @@ cc_library( ], includes = ["include"], deps = [ + ":Config", ":Helpers", - ":config", GZ_ROOT + "utils", ], ) @@ -322,9 +364,9 @@ cc_library( ], includes = ["include"], deps = [ + ":Config", ":Graph", ":Helpers", - ":config", ], ) @@ -334,8 +376,8 @@ cc_library( hdrs = ["include/gz/math/Helpers.hh"], includes = ["include"], deps = [ + ":Config", ":Export", - ":config", GZ_ROOT + "utils", ], ) @@ -345,11 +387,11 @@ cc_library( hdrs = ["include/gz/math/Inertial.hh"], includes = ["include"], deps = [ + ":Config", ":MassMatrix3", ":Matrix3", ":Matrix6", ":Pose3", - ":config", ], ) @@ -371,7 +413,7 @@ cc_library( hdrs = ["include/gz/math/Interval.hh"], includes = ["include"], deps = [ - ":config", + ":Config", ], ) @@ -384,10 +426,10 @@ cc_library( hdrs = ["include/gz/math/Kmeans.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", ":Rand", ":Vector3", - ":config", GZ_ROOT + "utils", ], ) @@ -397,8 +439,8 @@ cc_library( hdrs = ["include/gz/math/Line2.hh"], includes = ["include"], deps = [ + ":Config", ":Vector2", - ":config", ], ) @@ -407,8 +449,8 @@ cc_library( hdrs = ["include/gz/math/Line3.hh"], includes = ["include"], deps = [ + ":Config", ":Vector3", - ":config", ], ) @@ -417,13 +459,13 @@ cc_library( hdrs = ["include/gz/math/MassMatrix3.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", ":Material", ":Matrix3", ":Quaternion", ":Vector2", ":Vector3", - ":config", ], ) @@ -432,8 +474,8 @@ cc_library( hdrs = ["include/gz/math/MaterialType.hh"], includes = ["include"], deps = [ + ":Config", ":Export", - ":config", ], ) @@ -446,10 +488,10 @@ cc_library( hdrs = ["include/gz/math/Material.hh"], includes = ["include"], deps = [ + ":Config", ":Export", ":Helpers", ":MaterialType", - ":config", GZ_ROOT + "utils", ], ) @@ -459,9 +501,9 @@ cc_library( hdrs = ["include/gz/math/Matrix3.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", ":Vector3", - ":config", ], ) @@ -470,12 +512,12 @@ cc_library( hdrs = ["include/gz/math/Matrix4.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", ":Matrix3", ":Pose3", ":Quaternion", ":Vector3", - ":config", ], ) @@ -484,10 +526,10 @@ cc_library( hdrs = ["include/gz/math/Matrix6.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", ":Matrix3", ":Vector3", - ":config", ], ) @@ -498,22 +540,22 @@ cc_library( includes = ["include"], deps = [ ":Angle", + ":Config", ":Export", ":RollingMean", - ":config", GZ_ROOT + "utils", ], ) cc_library( name = "MovingWindowFilter", + srcs = ["src/MovingWindowFilter.cc"], hdrs = ["include/gz/math/MovingWindowFilter.hh"], includes = ["include"], deps = [ + ":Config", ":Export", ":Vector3", - ":config", - "@googletest//:gtest", GZ_ROOT + "utils", ], ) @@ -523,13 +565,13 @@ cc_library( hdrs = ["include/gz/math/OrientedBox.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", ":MassMatrix3", ":Material", ":Matrix4", ":Pose3", ":Vector3", - ":config", ], ) @@ -539,8 +581,8 @@ cc_library( hdrs = ["include/gz/math/PID.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", - ":config", GZ_ROOT + "utils", ], ) @@ -550,9 +592,9 @@ cc_library( hdrs = ["include/gz/math/PiecewiseScalarField3.hh"], includes = ["include"], deps = [ + ":Config", ":Region3", ":Vector3", - ":config", ], ) @@ -562,11 +604,11 @@ cc_library( includes = ["include"], deps = [ ":AxisAlignedBox", + ":Config", ":Line2", ":Quaternion", ":Vector2", ":Vector3", - ":config", ], ) @@ -575,9 +617,9 @@ cc_library( hdrs = ["include/gz/math/Polynomial3.hh"], includes = ["include"], deps = [ + ":Config", ":Interval", ":Vector4", - ":config", ], ) @@ -586,9 +628,9 @@ cc_library( hdrs = ["include/gz/math/Pose3.hh"], includes = ["include"], deps = [ + ":Config", ":Quaternion", ":Vector3", - ":config", ], ) @@ -598,10 +640,10 @@ cc_library( includes = ["include"], deps = [ ":Angle", + ":Config", ":Helpers", ":Matrix3", ":Vector3", - ":config", ], ) @@ -611,8 +653,8 @@ cc_library( hdrs = ["include/gz/math/Rand.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", - ":config", ], ) @@ -621,9 +663,9 @@ cc_library( hdrs = ["include/gz/math/Region3.hh"], includes = ["include"], deps = [ + ":Config", ":Interval", ":Vector3", - ":config", ], ) @@ -633,8 +675,8 @@ cc_library( hdrs = ["include/gz/math/RollingMean.hh"], includes = ["include"], deps = [ + ":Config", ":Export", - ":config", GZ_ROOT + "utils", ], ) @@ -645,8 +687,8 @@ cc_library( hdrs = ["include/gz/math/RotationSpline.hh"], includes = ["include"], deps = [ + ":Config", ":Quaternion", - ":config", GZ_ROOT + "utils", ], ) @@ -657,20 +699,23 @@ cc_library( hdrs = ["include/gz/math/SemanticVersion.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", - ":config", GZ_ROOT + "utils", ], ) cc_library( name = "SignalStats", - srcs = ["src/SignalStats.cc"], + srcs = [ + "src/SignalStats.cc", + "src/SignalStatsPrivate.hh", + ], hdrs = ["include/gz/math/SignalStats.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", - ":config", GZ_ROOT + "utils", ], ) @@ -681,8 +726,8 @@ cc_library( hdrs = ["include/gz/math/SpeedLimiter.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", - ":config", GZ_ROOT + "utils", ], ) @@ -709,11 +754,11 @@ cc_library( includes = ["include"], deps = [ ":Angle", - ":CoordinateVector3", + ":Config", ":Helpers", ":Matrix3", + ":Quaternion", ":Vector3", - ":config", GZ_ROOT + "utils", ], ) @@ -728,11 +773,11 @@ cc_library( hdrs = ["include/gz/math/Spline.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", ":Matrix4", ":Vector3", ":Vector4", - ":config", GZ_ROOT + "utils", ], ) @@ -745,8 +790,8 @@ cc_library( hdrs = ["include/gz/math/Stopwatch.hh"], includes = ["include"], deps = [ + ":Config", ":Export", - ":config", GZ_ROOT + "utils", ], ) @@ -759,9 +804,9 @@ cc_library( hdrs = ["include/gz/math/Temperature.hh"], includes = ["include"], deps = [ + ":Config", ":Export", ":Helpers", - ":config", GZ_ROOT + "utils", ], ) @@ -791,10 +836,10 @@ cc_library( hdrs = ["include/gz/math/Triangle.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", ":Line2", ":Vector2", - ":config", ], ) @@ -803,11 +848,11 @@ cc_library( hdrs = ["include/gz/math/Triangle3.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", ":Line3", ":Plane", ":Vector3", - ":config", ], ) @@ -816,8 +861,8 @@ cc_library( hdrs = ["include/gz/math/Vector2.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", - ":config", ], ) @@ -826,8 +871,8 @@ cc_library( hdrs = ["include/gz/math/Vector3.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", - ":config", ], ) @@ -837,10 +882,10 @@ cc_library( hdrs = ["include/gz/math/Vector3Stats.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", ":SignalStats", ":Vector3", - ":config", GZ_ROOT + "utils", ], ) @@ -850,9 +895,9 @@ cc_library( hdrs = ["include/gz/math/Vector4.hh"], includes = ["include"], deps = [ + ":Config", ":Helpers", ":Matrix4", - ":config", ], ) diff --git a/eigen3/BUILD.bazel b/eigen3/BUILD.bazel index 4107f59b..564e35e5 100644 --- a/eigen3/BUILD.bazel +++ b/eigen3/BUILD.bazel @@ -19,13 +19,12 @@ gz_include_header( cc_library( name = "eigen3", - srcs = public_headers, - hdrs = public_headers + [ - "include/gz/math/eigen3.hh", - ], + hdrs = ["include/gz/math/eigen3.hh"], includes = ["include"], visibility = GZ_VISIBILITY, deps = [ + ":Conversions", + ":Util", GZ_ROOT + "math", "@eigen3", ], @@ -46,3 +45,34 @@ test_sources = glob( "@gtest//:gtest_main", ], ) for src in test_sources] + +cc_library( + name = "Conversions", + hdrs = ["include/gz/math/eigen3/Conversions.hh"], + includes = ["include"], + deps = [ + GZ_ROOT + "math:AxisAlignedBox", + GZ_ROOT + "math:Matrix3", + GZ_ROOT + "math:Matrix6", + GZ_ROOT + "math:Pose3", + GZ_ROOT + "math:Quaternion", + GZ_ROOT + "math:Vector3", + "@eigen3", + ], +) + +cc_library( + name = "Util", + hdrs = ["include/gz/math/eigen3/Util.hh"], + includes = ["include"], + deps = [ + ":Conversions", + GZ_ROOT + "math:AxisAlignedBox", + GZ_ROOT + "math:Matrix3", + GZ_ROOT + "math:OrientedBox", + GZ_ROOT + "math:Pose3", + GZ_ROOT + "math:Quaternion", + GZ_ROOT + "math:Vector3", + "@eigen3", + ], +) From 4669bf23136cba19a8d23388839acf38d487f155 Mon Sep 17 00:00:00 2001 From: Shameek Ganguly Date: Tue, 19 Nov 2024 14:00:10 -0800 Subject: [PATCH 3/4] Add eigen3 test targets to satisfy layering checks Signed-off-by: Shameek Ganguly --- eigen3/BUILD.bazel | 36 ++++++++++++++++++++---------------- 1 file changed, 20 insertions(+), 16 deletions(-) diff --git a/eigen3/BUILD.bazel b/eigen3/BUILD.bazel index 564e35e5..f76afce3 100644 --- a/eigen3/BUILD.bazel +++ b/eigen3/BUILD.bazel @@ -30,22 +30,6 @@ cc_library( ], ) -test_sources = glob( - [ - "src/*_TEST.cc", - ], -) - -[cc_test( - name = src.replace("/", "_").replace(".cc", "").replace("src_", ""), - srcs = [src], - deps = [ - ":eigen3", - "@gtest", - "@gtest//:gtest_main", - ], -) for src in test_sources] - cc_library( name = "Conversions", hdrs = ["include/gz/math/eigen3/Conversions.hh"], @@ -61,6 +45,16 @@ cc_library( ], ) +cc_test( + name = "Conversions_TEST", + srcs = ["src/Conversions_TEST.cc"], + deps = [ + ":Conversions", + "@gtest", + "@gtest//:gtest_main", + ], +) + cc_library( name = "Util", hdrs = ["include/gz/math/eigen3/Util.hh"], @@ -76,3 +70,13 @@ cc_library( "@eigen3", ], ) + +cc_test( + name = "Util_TEST", + srcs = ["src/Util_TEST.cc"], + deps = [ + ":Util", + "@gtest", + "@gtest//:gtest_main", + ], +) From 4c1ba079cfcfb51485583900370929d0c670fe0f Mon Sep 17 00:00:00 2001 From: Shameek Ganguly Date: Tue, 19 Nov 2024 15:20:24 -0800 Subject: [PATCH 4/4] Add default visibility for math/eigen3 Signed-off-by: Shameek Ganguly --- eigen3/BUILD.bazel | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/eigen3/BUILD.bazel b/eigen3/BUILD.bazel index f76afce3..5443c24f 100644 --- a/eigen3/BUILD.bazel +++ b/eigen3/BUILD.bazel @@ -5,7 +5,10 @@ load( "gz_include_header", ) -package(default_applicable_licenses = [GZ_ROOT + "math:license"]) +package( + default_applicable_licenses = [GZ_ROOT + "math:license"], + default_visibility = GZ_VISIBILITY, +) public_headers = glob([ "include/gz/math/eigen3/*.hh", @@ -21,7 +24,6 @@ cc_library( name = "eigen3", hdrs = ["include/gz/math/eigen3.hh"], includes = ["include"], - visibility = GZ_VISIBILITY, deps = [ ":Conversions", ":Util",