Skip to content

Commit

Permalink
Remove deprecated code 2023-07 (#19714)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Jul 1, 2023
1 parent 6d95db8 commit 444ef41
Show file tree
Hide file tree
Showing 21 changed files with 4 additions and 246 deletions.
10 changes: 3 additions & 7 deletions bindings/pydrake/geometry/geometry_py_render.cc
Original file line number Diff line number Diff line change
Expand Up @@ -348,9 +348,7 @@ void DoScalarIndependentDefinitions(py::module m) {
doc_geometry.MakeRenderEngineVtk.doc);

{
// TODO(zachfang): During the 2023-07-01 deprecation removals also
// remove the spurious `geometry::` qualifier on this typename.
using Class = geometry::RenderEngineGlParams;
using Class = RenderEngineGlParams;
constexpr auto& cls_doc = doc_geometry.RenderEngineGlParams;
py::class_<Class> cls(m, "RenderEngineGlParams", cls_doc.doc);
cls // BR
Expand All @@ -360,10 +358,8 @@ void DoScalarIndependentDefinitions(py::module m) {
DefCopyAndDeepCopy(&cls);
}

// TODO(zachfang): During the 2023-07-01 deprecation removals also
// remove the spurious `geometry::` qualifier on this typename.
m.def("MakeRenderEngineGl", &geometry::MakeRenderEngineGl,
py::arg("params") = geometry::RenderEngineGlParams(),
m.def("MakeRenderEngineGl", &MakeRenderEngineGl,
py::arg("params") = RenderEngineGlParams(),
doc_geometry.MakeRenderEngineGl.doc);

{
Expand Down
1 change: 0 additions & 1 deletion bindings/pydrake/multibody/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,6 @@ drake_pybind_library(
name = "parsing_py",
cc_deps = [
"//bindings/pydrake:documentation_pybind",
"//bindings/pydrake/common:deprecation_pybind",
"//bindings/pydrake/common:serialize_pybind",
],
cc_srcs = ["parsing_py.cc"],
Expand Down
10 changes: 0 additions & 10 deletions bindings/pydrake/multibody/parsing_py.cc
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
#include "drake/bindings/pydrake/common/deprecation_pybind.h"
#include "drake/bindings/pydrake/common/serialize_pybind.h"
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/pydrake_pybind.h"
Expand Down Expand Up @@ -254,15 +253,6 @@ PYBIND11_MODULE(parsing, m) {
py::return_value_policy::reference,
py::keep_alive<0, 1>(), // `return` keeps `plant` alive.
doc.parsing.GetScopedFrameByName.doc);

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
m.def("GetScopedFrameName",
WrapDeprecated(doc.parsing.GetScopedFrameName.doc_deprecated,
&parsing::GetScopedFrameName),
py::arg("plant"), py::arg("frame"),
doc.parsing.GetScopedFrameName.doc_deprecated);
#pragma GCC diagnostic push
}

} // namespace pydrake
Expand Down
6 changes: 1 addition & 5 deletions bindings/pydrake/multibody/test/parsing_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
AddModelInstance,
AddWeld,
GetScopedFrameByName,
GetScopedFrameName,
LoadModelDirectives,
LoadModelDirectivesFromString,
ModelDirective,
Expand All @@ -25,7 +24,6 @@
import unittest

from pydrake.common import FindResourceOrThrow
from pydrake.common.test_utilities.deprecation import catch_drake_warnings
from pydrake.geometry import SceneGraph
from pydrake.multibody.tree import (
ModelInstanceIndex,
Expand Down Expand Up @@ -227,9 +225,7 @@ def test_model_instance_info(self):

def test_scoped_frame_names(self):
plant = MultibodyPlant(time_step=0.01)
frame = GetScopedFrameByName(plant, "world")
with catch_drake_warnings(expected_count=1):
self.assertIsNotNone(GetScopedFrameName(plant, frame))
GetScopedFrameByName(plant, "world")

def _make_plant_parser_directives(self):
"""Returns a tuple (plant, parser, directives) for later testing."""
Expand Down
20 changes: 0 additions & 20 deletions bindings/pydrake/planning/planning_py_collision_checker.cc
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
#include "drake/bindings/pydrake/common/deprecation_pybind.h"
#include "drake/bindings/pydrake/common/wrap_pybind.h"
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/planning/planning_py.h"
Expand Down Expand Up @@ -250,25 +249,6 @@ void DefinePlanningCollisionChecker(py::module m) {
.def("SupportsParallelChecking", &Class::SupportsParallelChecking,
cls_doc.SupportsParallelChecking.doc);
DefClone(&cls);

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
cls // BR
.def("GetScopedName",
WrapDeprecated(
cls_doc.GetScopedName.doc_deprecated_deprecated_1args_frame,
overload_cast_explicit<std::string, const Frame<double>&>(
&Class::GetScopedName)),
py::arg("frame"),
cls_doc.GetScopedName.doc_deprecated_deprecated_1args_frame)
.def("GetScopedName",
WrapDeprecated(
cls_doc.GetScopedName.doc_deprecated_deprecated_1args_body,
overload_cast_explicit<std::string, const Body<double>&>(
&Class::GetScopedName)),
py::arg("body"),
cls_doc.GetScopedName.doc_deprecated_deprecated_1args_body);
#pragma GCC diagnostic pop
}

{
Expand Down
5 changes: 0 additions & 5 deletions bindings/pydrake/planning/test/collision_checker_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
import numpy as np

from pydrake.common.test_utilities import numpy_compare
from pydrake.common.test_utilities.deprecation import catch_drake_warnings
from pydrake.geometry import Sphere
from pydrake.math import RigidTransform
from pydrake.multibody.plant import MultibodyPlant
Expand Down Expand Up @@ -243,10 +242,6 @@ def _test_collision_checker_base_class(self, dut):
self.assertEqual(len(dut.robot_model_instances()), 1)
self.assertTrue(dut.IsPartOfRobot(body=body))
self.assertTrue(dut.IsPartOfRobot(body_index=body.index()))
with catch_drake_warnings(expected_count=1):
self.assertEqual(dut.GetScopedName(frame=frame), "box::box")
with catch_drake_warnings(expected_count=1):
self.assertEqual(dut.GetScopedName(body=body), "box::box")

self.assertGreater(len(dut.GetZeroConfiguration()), 0)
self.assertGreater(dut.num_allocated_contexts(), 0)
Expand Down
1 change: 0 additions & 1 deletion bindings/pydrake/visualization/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,6 @@ drake_py_unittest(
],
deps = [
":model_visualizer",
"//bindings/pydrake/common/test_utilities:deprecation_py",
],
)

Expand Down
18 changes: 0 additions & 18 deletions bindings/pydrake/visualization/_model_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@

import numpy as np

from pydrake.common.deprecation import deprecated
from pydrake.geometry import (
Box,
Cylinder,
Expand Down Expand Up @@ -39,14 +38,6 @@
)


class RunResult(Enum):
"""This class is deprecated and will be removed on or after 2023-07-01."""
KEEP_GOING = 0 # Note that this is never returned but is used internally.
LOOP_ONCE = 1
STOPPED = 2
RELOAD = 3


class ModelVisualizer:
"""
Visualizes models from a file or string buffer in Drake Visualizer,
Expand Down Expand Up @@ -544,15 +535,6 @@ def has_clicks(button_name):
self._meshcat.DeleteButton(self._reload_button_name)
self._reload_button_name = None

return RunResult.STOPPED

@deprecated("Use Run() instead.", date="2023-07-01")
def RunWithReload(self, *args, **kwargs):
"""
(Deprecated.) The reload feature is enabled by default during Run().
"""
return self.Run(*args, **kwargs)

def _raise_if_invalid_positions(self, position):
"""
Validate the position argument.
Expand Down
1 change: 0 additions & 1 deletion bindings/pydrake/visualization/meldis.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,6 @@
import webbrowser

from pydrake.common import configure_logging as _configure_logging
from pydrake.common.deprecation import _warn_deprecated
from pydrake.visualization._meldis import Meldis as _Meldis


Expand Down
7 changes: 0 additions & 7 deletions bindings/pydrake/visualization/test/model_visualizer_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
import unittest

from pydrake.common import FindResourceOrThrow
from pydrake.common.test_utilities.deprecation import catch_drake_warnings
from pydrake.geometry import Meshcat
import pydrake.visualization as mut
import pydrake.visualization._model_visualizer as mut_private
Expand Down Expand Up @@ -281,12 +280,6 @@ def test_webbrowser(self):
self.assertIn("localhost", kwargs["url"])
self.assertEqual(len(kwargs), 2)

def test_deprecated_run_with_reload(self):
dut = mut.ModelVisualizer()
dut.parser().AddModelsFromString(self.SAMPLE_OBJ, "sdf")
with catch_drake_warnings(expected_count=1):
dut.RunWithReload(loop_once=True)

def test_triad_defaults(self):
# Cross-check the default triad parameters.
expected = inspect.signature(mut.AddFrameTriadIllustration).parameters
Expand Down
15 changes: 0 additions & 15 deletions geometry/render_gl/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -245,21 +245,6 @@ drake_cc_googletest(
],
)

# TODO(zachfang): Remove this along with deprecation on 2023-07-01.
drake_cc_googletest(
name = "deprecation_test",
copts = [
"-Wno-cpp",
"-Wno-deprecated-declarations",
],
tags = vtk_test_tags(),
deps = [
":factory",
":render_engine_gl_params",
"//common/test_utilities:expect_throws_message",
],
)

drake_cc_googletest_ubuntu_only(
name = "internal_shape_meshes_test",
data = [
Expand Down
5 changes: 0 additions & 5 deletions geometry/render_gl/factory.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,5 @@ std::unique_ptr<render::RenderEngine> MakeRenderEngineGl(
std::move(params));
}

namespace render {
DRAKE_DEPRECATED("2023-07-01", "Use the geometry namespace instead.")
const bool kHasRenderEngineGl = true;
} // namespace render

} // namespace geometry
} // namespace drake
11 changes: 0 additions & 11 deletions geometry/render_gl/factory.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

#include <memory>

#include "drake/common/drake_deprecated.h"
#include "drake/geometry/render/render_engine.h"
#include "drake/geometry/render_gl/render_engine_gl_params.h"

Expand Down Expand Up @@ -47,15 +46,5 @@ extern const bool kHasRenderEngineGl;
std::unique_ptr<render::RenderEngine> MakeRenderEngineGl(
RenderEngineGlParams params = {});

namespace render {

DRAKE_DEPRECATED("2023-07-01", "Use the geometry namespace instead.")
extern const bool kHasRenderEngineGl;

DRAKE_DEPRECATED("2023-07-01", "Use the geometry namespace instead.")
constexpr auto MakeRenderEngineGl = &geometry::MakeRenderEngineGl;

} // namespace render

} // namespace geometry
} // namespace drake
5 changes: 0 additions & 5 deletions geometry/render_gl/no_factory.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,5 @@ std::unique_ptr<render::RenderEngine> MakeRenderEngineGl(RenderEngineGlParams) {
"engine.");
}

namespace render {
DRAKE_DEPRECATED("2023-07-01", "Use the geometry namespace instead.")
const bool kHasRenderEngineGl = false;
} // namespace render

} // namespace geometry
} // namespace drake
9 changes: 0 additions & 9 deletions geometry/render_gl/render_engine_gl_params.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
#pragma once

#include "drake/common/drake_deprecated.h"
#include "drake/common/name_value.h"
#include "drake/geometry/render/render_label.h"
#include "drake/geometry/rgba.h"
Expand Down Expand Up @@ -31,13 +30,5 @@ struct RenderEngineGlParams {
Rgba default_clear_color{204 / 255., 229 / 255., 255 / 255., 1.0};
};

namespace render {

using RenderEngineGlParams
DRAKE_DEPRECATED("2023-07-01", "Use the geometry namespace instead.")
= geometry::RenderEngineGlParams;

} // namespace render

} // namespace geometry
} // namespace drake
28 changes: 0 additions & 28 deletions geometry/render_gl/test/deprecation_test.cc

This file was deleted.

1 change: 0 additions & 1 deletion manipulation/util/make_arm_controller_model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@ using multibody::MultibodyPlant;
using multibody::Parser;
using multibody::RigidBody;
using multibody::SpatialInertia;
using multibody::parsing::GetScopedFrameName;
using multibody::parsing::ModelInstanceInfo;
using systems::Context;

Expand Down
54 changes: 0 additions & 54 deletions multibody/parsing/scoped_names.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,6 @@ namespace drake {
namespace multibody {
namespace parsing {

namespace {
// TODO(jwnimmer-tri) Remove me 2023-07-01 as part of deprecation.
constexpr char kScopedNameDelim[] = "::";
} // namespace

const drake::multibody::Frame<double>*
GetScopedFrameByNameMaybe(
const drake::multibody::MultibodyPlant<double>& plant,
Expand Down Expand Up @@ -45,55 +40,6 @@ const drake::multibody::Frame<double>& GetScopedFrameByName(
}
}

#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#pragma GCC diagnostic push
// Remove 2023-07-01 with deprecation.
std::string GetScopedFrameName(
const drake::multibody::MultibodyPlant<double>& plant,
const drake::multibody::Frame<double>& frame) {
if (&frame == &plant.world_frame())
return "world";
return PrefixName(GetInstanceScopeName(
plant, frame.model_instance()), frame.name());
}
#pragma GCC diagnostic pop

// Remove 2023-07-01 with deprecation.
ScopedNameIsDeprecated ParseScopedName(const std::string& full_name) {
size_t pos = full_name.rfind(kScopedNameDelim);
ScopedNameIsDeprecated result;
if (pos == std::string::npos) {
result.name = full_name;
} else {
result.instance_name = full_name.substr(0, pos);
// "Global scope" (e.g. "::my_frame") not supported.
DRAKE_DEMAND(!result.instance_name.empty());
result.name = full_name.substr(pos + std::string(kScopedNameDelim).size());
}
return result;
}

// Remove 2023-07-01 with deprecation.
std::string PrefixName(const std::string& namespace_, const std::string& name) {
if (namespace_.empty())
return name;
else if (name.empty())
return namespace_;
else
return namespace_ + kScopedNameDelim + name;
}

// Remove 2023-07-01 with deprecation.
std::string GetInstanceScopeName(
const MultibodyPlant<double>& plant,
ModelInstanceIndex instance) {
if (instance != plant.world_body().model_instance()) {
return plant.GetModelInstanceName(instance);
} else {
return "";
}
}

} // namespace parsing
} // namespace multibody
} // namespace drake
Loading

0 comments on commit 444ef41

Please sign in to comment.