From c0f66f60c34aa0f0055d40e3db61c4570d60ea11 Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Wed, 1 Jan 2025 09:52:34 -0800 Subject: [PATCH] Remove deprecated code 2025-01 (#22368) --- bindings/pydrake/systems/BUILD.bazel | 1 - bindings/pydrake/systems/sensors_py_rgbd.cc | 28 --------------- bindings/pydrake/systems/test/sensors_test.py | 13 ------- geometry/proximity/obj_to_surface_mesh.cc | 16 --------- geometry/proximity/obj_to_surface_mesh.h | 12 ------- .../test/obj_to_surface_mesh_test.cc | 14 -------- manipulation/util/BUILD.bazel | 12 ------- manipulation/util/meshlab_to_sdf.py | 9 ----- manipulation/util/show_model.py | 10 ------ multibody/tree/BUILD.bazel | 2 -- multibody/tree/frame.h | 8 +++-- multibody/tree/frame_base.cc | 15 -------- multibody/tree/frame_base.h | 26 -------------- systems/sensors/rgbd_sensor.cc | 32 ----------------- systems/sensors/rgbd_sensor.h | 35 ------------------- systems/sensors/test/rgbd_sensor_test.cc | 18 ---------- 16 files changed, 5 insertions(+), 246 deletions(-) delete mode 100644 manipulation/util/meshlab_to_sdf.py delete mode 100644 manipulation/util/show_model.py delete mode 100644 multibody/tree/frame_base.cc delete mode 100644 multibody/tree/frame_base.h diff --git a/bindings/pydrake/systems/BUILD.bazel b/bindings/pydrake/systems/BUILD.bazel index 681c42207365..cb3d44f8c687 100644 --- a/bindings/pydrake/systems/BUILD.bazel +++ b/bindings/pydrake/systems/BUILD.bazel @@ -170,7 +170,6 @@ drake_pybind_library( "//bindings/pydrake:documentation_pybind", "//bindings/pydrake/common:cpp_template_pybind", "//bindings/pydrake/common:default_scalars_pybind", - "//bindings/pydrake/common:deprecation_pybind", "//bindings/pydrake/common:eigen_pybind", "//bindings/pydrake/common:serialize_pybind", "//bindings/pydrake/common:type_pack", diff --git a/bindings/pydrake/systems/sensors_py_rgbd.cc b/bindings/pydrake/systems/sensors_py_rgbd.cc index 15d17b54dc77..d231e111fbb3 100644 --- a/bindings/pydrake/systems/sensors_py_rgbd.cc +++ b/bindings/pydrake/systems/sensors_py_rgbd.cc @@ -1,4 +1,3 @@ -#include "drake/bindings/pydrake/common/deprecation_pybind.h" #include "drake/bindings/pydrake/documentation_pybind.h" #include "drake/bindings/pydrake/systems/sensors_py.h" #include "drake/systems/sensors/camera_info.h" @@ -136,33 +135,6 @@ void DefineSensorsRgbd(py::module m) { .def("SetParentFrameId", &RgbdSensor::SetParentFrameId, py::arg("context"), py::arg("id"), doc.RgbdSensor.SetParentFrameId.doc); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - rgbd_sensor - .def("parent_frame_id", - WrapDeprecated(doc.RgbdSensor.parent_frame_id.doc_deprecated, - &RgbdSensor::parent_frame_id), - doc.RgbdSensor.parent_frame_id.doc_deprecated) - .def("X_PB", - WrapDeprecated(doc.RgbdSensor.X_PB.doc_deprecated, &RgbdSensor::X_PB), - doc.RgbdSensor.X_PB.doc_deprecated) - .def("X_BC", - WrapDeprecated(doc.RgbdSensor.X_BC.doc_deprecated, &RgbdSensor::X_BC), - doc.RgbdSensor.X_BC.doc_deprecated) - .def("X_BD", - WrapDeprecated(doc.RgbdSensor.X_BD.doc_deprecated, &RgbdSensor::X_BD), - doc.RgbdSensor.X_BD.doc_deprecated) - .def("color_camera_info", - WrapDeprecated(doc.RgbdSensor.color_camera_info.doc_deprecated, - &RgbdSensor::color_camera_info), - py_rvp::reference_internal, - doc.RgbdSensor.color_camera_info.doc_deprecated) - .def("depth_camera_info", - WrapDeprecated(doc.RgbdSensor.depth_camera_info.doc_deprecated, - &RgbdSensor::depth_camera_info), - py_rvp::reference_internal, - doc.RgbdSensor.depth_camera_info.doc_deprecated); -#pragma GCC diagnostic pop def_camera_ports(&rgbd_sensor, doc.RgbdSensor); py::class_> rgbd_camera_discrete( diff --git a/bindings/pydrake/systems/test/sensors_test.py b/bindings/pydrake/systems/test/sensors_test.py index 07d376ef995b..7ba7b144f6bb 100644 --- a/bindings/pydrake/systems/test/sensors_test.py +++ b/bindings/pydrake/systems/test/sensors_test.py @@ -8,7 +8,6 @@ import numpy as np from pydrake.common import FindResourceOrThrow from pydrake.common.test_utilities import numpy_compare -from pydrake.common.test_utilities.deprecation import catch_drake_warnings from pydrake.common.test_utilities.pickle_compare import assert_pickle from pydrake.common.value import AbstractValue, Value from pydrake.geometry import ( @@ -474,18 +473,6 @@ def check_info(camera_info): self.assertEqual(sensor.default_parent_frame_id(), parent_id) sensor.set_default_parent_frame_id(parent_id) - with catch_drake_warnings(expected_count=1): - check_info(sensor.color_camera_info()) - with catch_drake_warnings(expected_count=1): - check_info(sensor.depth_camera_info()) - with catch_drake_warnings(expected_count=1): - self.assertIsInstance(sensor.X_PB(), RigidTransform) - with catch_drake_warnings(expected_count=1): - self.assertIsInstance(sensor.X_BC(), RigidTransform) - with catch_drake_warnings(expected_count=1): - self.assertIsInstance(sensor.X_BD(), RigidTransform) - with catch_drake_warnings(expected_count=1): - self.assertEqual(sensor.parent_frame_id(), parent_id) check_ports(sensor) # Check parameter API. context = sensor.CreateDefaultContext() diff --git a/geometry/proximity/obj_to_surface_mesh.cc b/geometry/proximity/obj_to_surface_mesh.cc index 3d62303e9922..6de2d1baec0d 100644 --- a/geometry/proximity/obj_to_surface_mesh.cc +++ b/geometry/proximity/obj_to_surface_mesh.cc @@ -57,22 +57,6 @@ TriangleSurfaceMesh ReadObjToTriangleSurfaceMesh( return ReadObjToTriangleSurfaceMesh(MeshSource(filename), scale, on_warning); } -TriangleSurfaceMesh ReadObjToTriangleSurfaceMesh( - std::istream* input_stream, const double scale, - std::function on_warning, - std::string_view description) { - DRAKE_THROW_UNLESS(input_stream != nullptr); - DRAKE_THROW_UNLESS(input_stream->good()); - std::stringstream content; - content << input_stream->rdbuf(); - - // We will either throw or return a mesh here (courtesy of ReadObj). - return ReadObjToTriangleSurfaceMesh( - InMemoryMesh{MemoryFile(std::move(content).str(), ".obj", - std::string(description))}, - scale, on_warning); -} - TriangleSurfaceMesh ReadObjToTriangleSurfaceMesh( const MeshSource& mesh_source, double scale, std::function on_warning) { diff --git a/geometry/proximity/obj_to_surface_mesh.h b/geometry/proximity/obj_to_surface_mesh.h index 82b472ae3e80..e515caa37881 100644 --- a/geometry/proximity/obj_to_surface_mesh.h +++ b/geometry/proximity/obj_to_surface_mesh.h @@ -2,14 +2,12 @@ #include #include -#include #include #include #include #include #include "drake/common/diagnostic_policy.h" -#include "drake/common/drake_deprecated.h" #include "drake/geometry/mesh_source.h" #include "drake/geometry/proximity/triangle_surface_mesh.h" @@ -49,16 +47,6 @@ TriangleSurfaceMesh ReadObjToTriangleSurfaceMesh( const std::filesystem::path& filename, double scale = 1.0, std::function on_warning = {}); -/** Overload of @ref ReadObjToTriangleSurfaceMesh(const std::string&, double) - with the Wavefront .obj file given in std::istream. */ -DRAKE_DEPRECATED( - "2025-01-01", - "Please use ReadObjToTriangleSurfaceMesh(const MeshSource&) instead.") -TriangleSurfaceMesh ReadObjToTriangleSurfaceMesh( - std::istream* input_stream, double scale = 1.0, - std::function on_warning = {}, - std::string_view description = "from_stream"); - /** Overload of @ref ReadObjToTriangleSurfaceMesh(const std::filesystem::path&, double) with the Wavefront .obj in a Mesh shape specification. */ TriangleSurfaceMesh ReadObjToTriangleSurfaceMesh( diff --git a/geometry/proximity/test/obj_to_surface_mesh_test.cc b/geometry/proximity/test/obj_to_surface_mesh_test.cc index 54d6c63f4d5f..6cf8dde7a2f0 100644 --- a/geometry/proximity/test/obj_to_surface_mesh_test.cc +++ b/geometry/proximity/test/obj_to_surface_mesh_test.cc @@ -78,20 +78,6 @@ GTEST_TEST(ObjToSurfaceMeshTest, FromPath) { EXPECT_TRUE(surface.Equal(MeshForQuadCube())); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -GTEST_TEST(ObjToSurfaceMeshTest, FromStream) { - const fs::path filename = - FindResourceOrThrow("drake/geometry/test/quad_cube.obj"); - std::ifstream stream(filename); - DRAKE_DEMAND(stream.is_open()); - const TriangleSurfaceMesh surface = - ReadObjToTriangleSurfaceMesh(&stream); - - EXPECT_TRUE(surface.Equal(MeshForQuadCube())); -} -#pragma GCC diagnostic pop - // Tests the MeshSource-based overload. GTEST_TEST(ObjToSurfaceMeshTest, MeshSource) { constexpr double kUnitScale = 1.0; diff --git a/manipulation/util/BUILD.bazel b/manipulation/util/BUILD.bazel index 8bab143084ac..c528bdcb84a0 100644 --- a/manipulation/util/BUILD.bazel +++ b/manipulation/util/BUILD.bazel @@ -6,7 +6,6 @@ load( "drake_cc_library", "drake_cc_package_library", ) -load("//tools/skylark:drake_py.bzl", "drake_py_binary") package(default_visibility = ["//visibility:public"]) @@ -117,17 +116,6 @@ drake_cc_library( ], ) -drake_py_binary( - name = "show_model", - srcs = ["show_model.py"], - deps = ["//bindings/pydrake"], -) - -drake_py_binary( - name = "meshlab_to_sdf", - srcs = ["meshlab_to_sdf.py"], -) - drake_cc_binary( name = "stl2obj", srcs = ["stl2obj.cc"], diff --git a/manipulation/util/meshlab_to_sdf.py b/manipulation/util/meshlab_to_sdf.py deleted file mode 100644 index bce0d0f629f5..000000000000 --- a/manipulation/util/meshlab_to_sdf.py +++ /dev/null @@ -1,9 +0,0 @@ -# Prints a message pointing the user to our replacement tool. -# TODO(jwnimmer-tri) Remove this stub on or around 2025-01-01. - -import sys - -if __name__ == '__main__': - print("** Error: This script has been removed. **") - print("Instead, please use pydrake.multibody.mesh_to_model or pydrake.multibody.fix_inertia.") # noqa - sys.exit(1) diff --git a/manipulation/util/show_model.py b/manipulation/util/show_model.py deleted file mode 100644 index ec7e09729f3f..000000000000 --- a/manipulation/util/show_model.py +++ /dev/null @@ -1,10 +0,0 @@ -# Prints a deprecation notice and forwards to the equivalent pydrake script. -# TODO(jwnimmer-tri) Remove this stub on or around 2025-01-01. - -from pydrake.visualization.model_visualizer import _main - - -if __name__ == '__main__': - print("** Note: This script is deprecated. **") - print("Please switch to //tools:model_visualizer when convenient.") - _main() diff --git a/multibody/tree/BUILD.bazel b/multibody/tree/BUILD.bazel index 1c9354a1fccb..f12d860e27c7 100644 --- a/multibody/tree/BUILD.bazel +++ b/multibody/tree/BUILD.bazel @@ -92,7 +92,6 @@ drake_cc_library( "fixed_offset_frame.cc", "force_element.cc", "frame.cc", - "frame_base.cc", "joint.cc", "joint_actuator.cc", "linear_bushing_roll_pitch_yaw.cc", @@ -136,7 +135,6 @@ drake_cc_library( "fixed_offset_frame.h", "force_element.h", "frame.h", - "frame_base.h", "joint.h", "joint_actuator.h", "linear_bushing_roll_pitch_yaw.h", diff --git a/multibody/tree/frame.h b/multibody/tree/frame.h index 8ed626df37c9..b873ea2a9eb5 100644 --- a/multibody/tree/frame.h +++ b/multibody/tree/frame.h @@ -6,7 +6,6 @@ #include "drake/common/autodiff.h" #include "drake/common/nice_type_name.h" -#include "drake/multibody/tree/frame_base.h" #include "drake/multibody/tree/frame_body_pose_cache.h" #include "drake/multibody/tree/multibody_element.h" #include "drake/multibody/tree/multibody_tree_indexes.h" @@ -51,12 +50,15 @@ class RigidBody; /// /// @tparam_default_scalar template -class Frame : public FrameBase { +class Frame : public MultibodyElement { public: DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Frame); ~Frame() override; + /// Returns this element's unique index. + FrameIndex index() const { return this->template index_impl(); } + /// Returns a const reference to the body associated to this %Frame. const RigidBody& body() const { return body_; } @@ -548,7 +550,7 @@ class Frame : public FrameBase { /// instance. explicit Frame(const std::string& name, const RigidBody& body, std::optional model_instance = {}) - : FrameBase(model_instance.value_or(body.model_instance())), + : MultibodyElement(model_instance.value_or(body.model_instance())), name_(internal::DeprecateWhenEmptyName(name, "Frame")), body_(body) {} diff --git a/multibody/tree/frame_base.cc b/multibody/tree/frame_base.cc deleted file mode 100644 index 2414bf160119..000000000000 --- a/multibody/tree/frame_base.cc +++ /dev/null @@ -1,15 +0,0 @@ -#include "drake/multibody/tree/frame_base.h" - -#include "drake/common/default_scalars.h" - -namespace drake { -namespace multibody { - -template -FrameBase::~FrameBase() = default; - -} // namespace multibody -} // namespace drake - -DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS( - class drake::multibody::FrameBase); diff --git a/multibody/tree/frame_base.h b/multibody/tree/frame_base.h deleted file mode 100644 index 113969d52ae9..000000000000 --- a/multibody/tree/frame_base.h +++ /dev/null @@ -1,26 +0,0 @@ -#pragma once - -#include "drake/multibody/tree/multibody_element.h" -#include "drake/multibody/tree/multibody_tree_indexes.h" - -namespace drake { -namespace multibody { - -/// %FrameBase is deprecated and will be removed on or after 2025-01-01. -/// @tparam_default_scalar -template -class FrameBase : public MultibodyElement { - public: - // TODO(jwnimmer-tri) On 2025-01-01 move this into `class Frame`. - /// Returns this element's unique index. - FrameIndex index() const { return this->template index_impl(); } - - ~FrameBase() override; - - protected: - explicit FrameBase(ModelInstanceIndex model_instance) - : MultibodyElement(model_instance) {} -}; - -} // namespace multibody -} // namespace drake diff --git a/systems/sensors/rgbd_sensor.cc b/systems/sensors/rgbd_sensor.cc index 38a44ff4d008..a74080b359d2 100644 --- a/systems/sensors/rgbd_sensor.cc +++ b/systems/sensors/rgbd_sensor.cc @@ -218,38 +218,6 @@ const OutputPort& RgbdSensor::image_time_output_port() const { return *image_time_output_port_; } -const CameraInfo& RgbdSensor::color_camera_info() const { - return defaults_.color_camera.core().intrinsics(); -} - -const CameraInfo& RgbdSensor::depth_camera_info() const { - return defaults_.depth_camera.core().intrinsics(); -} - -const ColorRenderCamera& RgbdSensor::color_render_camera() const { - return default_color_render_camera(); -} - -const DepthRenderCamera& RgbdSensor::depth_render_camera() const { - return default_depth_render_camera(); -} - -const RigidTransformd& RgbdSensor::X_PB() const { - return default_X_PB(); -} - -const RigidTransformd& RgbdSensor::X_BC() const { - return defaults_.color_camera.core().sensor_pose_in_camera_body(); -} - -const RigidTransformd& RgbdSensor::X_BD() const { - return defaults_.depth_camera.core().sensor_pose_in_camera_body(); -} - -FrameId RgbdSensor::parent_frame_id() const { - return default_parent_frame_id(); -} - namespace { // If the size of `image` already matches `camera`, then does nothing. // Otherwise, resizes the `image` to match `camera`. diff --git a/systems/sensors/rgbd_sensor.h b/systems/sensors/rgbd_sensor.h index c492fd485363..d9de9a664ff4 100644 --- a/systems/sensors/rgbd_sensor.h +++ b/systems/sensors/rgbd_sensor.h @@ -1,7 +1,6 @@ #pragma once #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/geometry/geometry_ids.h" #include "drake/geometry/query_object.h" #include "drake/geometry/render/render_camera.h" @@ -219,40 +218,6 @@ class RgbdSensor final : public LeafSystem { the current time). */ const OutputPort& image_time_output_port() const; - DRAKE_DEPRECATED( - "2025-01-01", - "Use default_color_render_camera().core().intrinsics() instead.") - const CameraInfo& color_camera_info() const; - - DRAKE_DEPRECATED( - "2025-01-01", - "Use default_depth_render_camera().core().intrinsics() instead.") - const CameraInfo& depth_camera_info() const; - - DRAKE_DEPRECATED("2025-01-01", "Use default_color_render_camera() instead.") - const geometry::render::ColorRenderCamera& color_render_camera() const; - - DRAKE_DEPRECATED("2025-01-01", "Use default_depth_render_camera() instead.") - const geometry::render::DepthRenderCamera& depth_render_camera() const; - - DRAKE_DEPRECATED("2025-01-01", "Use default_X_PB() instead.") - const math::RigidTransformd& X_PB() const; - - DRAKE_DEPRECATED( - "2025-01-01", - "Use default_color_render_camera().core().sensor_pose_in_camera_body() " - "instead.") - const math::RigidTransformd& X_BC() const; - - DRAKE_DEPRECATED( - "2025-01-01", - "Use default_depth_render_camera().core().sensor_pose_in_camera_body() " - "instead.") - const math::RigidTransformd& X_BD() const; - - DRAKE_DEPRECATED("2025-01-01", "Use default_parent_frame_id() instead.") - geometry::FrameId parent_frame_id() const; - private: // The calculator methods for the four output ports. void CalcColorImage(const Context& context, diff --git a/systems/sensors/test/rgbd_sensor_test.cc b/systems/sensors/test/rgbd_sensor_test.cc index 8c53b332d2bf..da0e47dffe2a 100644 --- a/systems/sensors/test/rgbd_sensor_test.cc +++ b/systems/sensors/test/rgbd_sensor_test.cc @@ -539,24 +539,6 @@ TEST_F(RgbdSensorTest, ConstructCameraWithNonTrivialOffsetsDeprecated) { X_BD.GetAsMatrix4())); } -TEST_F(RgbdSensorTest, DeprecatedMethods) { - RgbdSensor sensor(SceneGraph::world_frame_id(), - RigidTransformd::Identity(), depth_camera_); - // Just test that deprecated methods can be called and are vaguely - // sane. These tests will be deleted when the deprecated methods are removed. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - EXPECT_GT(sensor.color_camera_info().width(), 0); - EXPECT_GT(sensor.depth_camera_info().width(), 0); - EXPECT_FALSE(sensor.color_render_camera().show_window()); - EXPECT_GT(sensor.depth_render_camera().depth_range().min_depth(), 0); - EXPECT_EQ(sensor.X_PB().translation().size(), 3); - EXPECT_EQ(sensor.X_BC().translation().size(), 3); - EXPECT_EQ(sensor.X_BD().translation().size(), 3); - EXPECT_TRUE(sensor.parent_frame_id().is_valid()); -#pragma GCC diagnostic pop -} - // We don't explicitly test any of the image outputs (other than their size). // The image outputs simply wrap the corresponding QueryObject call; the only // calculations they do is to produce the X_PC matrix (which is implicitly