Skip to content

Commit

Permalink
[misc] Remove deprecated code 2022-09 (RobotLocomotion#17813)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Sep 2, 2022
1 parent b5cfb10 commit 7daf84d
Show file tree
Hide file tree
Showing 27 changed files with 9 additions and 1,670 deletions.
3 changes: 1 addition & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -108,9 +108,8 @@ endif()

# The minimum compiler versions should match those listed in both
# doc/_pages/from_source.md and tools/workspace/cc/repository.bzl.
# TODO(jwnimmer-tri) Set MINIMUM_CLANG_VERSION=12 on 2022-09-01.
set(MINIMUM_APPLE_CLANG_VERSION 12)
set(MINIMUM_CLANG_VERSION 9)
set(MINIMUM_CLANG_VERSION 12)
set(MINIMUM_GNU_VERSION 9.3)

if(CMAKE_C_COMPILER_ID STREQUAL AppleClang)
Expand Down
2 changes: 0 additions & 2 deletions bindings/pydrake/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -250,7 +250,6 @@ drake_pybind_library(
cc_deps = [
":symbolic_types_pybind",
"//bindings/pydrake:documentation_pybind",
"//bindings/pydrake/common:deprecation_pybind",
"//bindings/pydrake/common:eigen_pybind",
],
cc_srcs = [
Expand All @@ -262,7 +261,6 @@ drake_pybind_library(
py_deps = [
":module_py",
"//bindings/pydrake/common:compatibility_py",
"//bindings/pydrake/common:deprecation_py",
],
py_srcs = ["_symbolic_extra.py"],
)
Expand Down
1 change: 0 additions & 1 deletion bindings/pydrake/common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,6 @@ drake_pybind_library(
cc_deps = [
"//bindings/pydrake:autodiff_types_pybind",
"//bindings/pydrake:documentation_pybind",
"//bindings/pydrake/common:deprecation_pybind",
"//bindings/pydrake/common:value_pybind",
"//common:nice_type_name_override_header",
],
Expand Down
11 changes: 0 additions & 11 deletions bindings/pydrake/common/module_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
#include "pybind11/stl.h"

#include "drake/bindings/pydrake/autodiff_types_pybind.h"
#include "drake/bindings/pydrake/common/deprecation_pybind.h"
#include "drake/bindings/pydrake/common/text_logging_pybind.h"
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/pydrake_pybind.h"
Expand Down Expand Up @@ -104,16 +103,6 @@ PYBIND11_MODULE(_module_py, m) {
// Python users should not touch the C++ level; thus, we bind this privately.
m.def("_set_log_level", &logging::set_log_level, py::arg("level"),
doc.logging.set_log_level.doc);
{
const char* doc_deprecated =
"Deprecated:\n"
" Do not use ``pydrake.common.set_log_level(...)``.\n"
" Instead, use ``logging.getLogger('drake').setLevel(...)``.\n"
" This function will be removed from Drake on or after 2022-09-01";
m.def("set_log_level",
WrapDeprecated(doc_deprecated, &logging::set_log_level),
py::arg("level"), doc_deprecated);
}

internal::MaybeRedirectPythonLogging();

Expand Down
5 changes: 2 additions & 3 deletions bindings/pydrake/common/test/module_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,9 +54,8 @@ def test_random_distribution(self):

def test_logging(self):
self.assertTrue(mut._module_py._HAVE_SPDLOG)
with catch_drake_warnings(expected_count=1) as w:
self.assertIsInstance(
mut.set_log_level(level="unchanged"), str)
self.assertIsInstance(
mut._set_log_level(level="unchanged"), str)

def test_random_generator(self):
g1 = mut.RandomGenerator()
Expand Down
1 change: 0 additions & 1 deletion bindings/pydrake/solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,6 @@ drake_pybind_library(
"//bindings/pydrake:symbolic_types_pybind",
"//bindings/pydrake/common:cpp_param_pybind",
"//bindings/pydrake/common:cpp_template_pybind",
"//bindings/pydrake/common:deprecation_pybind",
"//bindings/pydrake/common:eigen_pybind",
"//bindings/pydrake/common:value_pybind",
],
Expand Down
8 changes: 0 additions & 8 deletions bindings/pydrake/solvers/solvers_py_csdp.cc
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#include "pybind11/eigen.h"
#include "pybind11/pybind11.h"

#include "drake/bindings/pydrake/common/deprecation_pybind.h"
#include "drake/bindings/pydrake/common/value_pybind.h"
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/pydrake_pybind.h"
Expand All @@ -23,13 +22,6 @@ void DefineSolversCsdp(py::module m) {
csdp_cls.def(py::init<>(), doc.CsdpSolver.ctor.doc)
.def_static("id", &CsdpSolver::id, doc.CsdpSolver.id.doc);

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
csdp_cls.def(py_init_deprecated<CsdpSolver, RemoveFreeVariableMethod>(
doc.CsdpSolver.ctor.doc_deprecated),
py::arg("method"), doc.CsdpSolver.ctor.doc_deprecated);
#pragma GCC diagnostic pop

py::class_<CsdpSolverDetails>(
m, "CsdpSolverDetails", doc.CsdpSolverDetails.doc)
.def_readonly("return_code", &CsdpSolverDetails::return_code,
Expand Down
2 changes: 0 additions & 2 deletions bindings/pydrake/solvers/test/augmented_lagrangian_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,6 @@
from pydrake.solvers import augmented_lagrangian as al
from pydrake.autodiffutils import InitializeAutoDiff, AutoDiffXd

from pydrake.common.test_utilities.deprecation import catch_drake_warnings


class TestAugmentedLagrangian(unittest.TestCase):
def setUp(self):
Expand Down
5 changes: 0 additions & 5 deletions bindings/pydrake/solvers/test/csdp_solver_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
from pydrake.solvers import mathematicalprogram as mp
from pydrake.solvers.csdp import CsdpSolver
import pydrake.solvers.sdpa_free_format as sdpa_free_format
from pydrake.common.test_utilities.deprecation import catch_drake_warnings


class TestCsdpSolver(unittest.TestCase):
Expand Down Expand Up @@ -66,10 +65,6 @@ def test_csdp_solver(self):
sdpa_free_format.RemoveFreeVariableMethod.kLorentzConeSlack)
result = solver.Solve(prog, None, solver_options)
self.assertTrue(result.is_success())
with catch_drake_warnings(expected_count=1):
CsdpSolver(
method=sdpa_free_format.RemoveFreeVariableMethod.
kLorentzConeSlack)

def unavailable(self):
"""Per the BUILD file, this test is only run when CSDP is disabled."""
Expand Down
9 changes: 0 additions & 9 deletions bindings/pydrake/symbolic_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
#include "pybind11/pybind11.h"
#include "pybind11/stl.h"

#include "drake/bindings/pydrake/common/deprecation_pybind.h"
#include "drake/bindings/pydrake/common/eigen_pybind.h"
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/pydrake_pybind.h"
Expand Down Expand Up @@ -996,14 +995,6 @@ PYBIND11_MODULE(symbolic, m) {
.def(py::self == py::self)
.def(py::self != py::self);

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
polynomial_cls.def("EqualToAfterExpansion",
WrapDeprecated(doc.Polynomial.EqualToAfterExpansion.doc_deprecated,
&Polynomial::EqualToAfterExpansion),
doc.Polynomial.EqualToAfterExpansion.doc_deprecated);
#pragma GCC diagnostic pop

m.def(
"Evaluate",
[](const MatrixX<Polynomial>& M, const Environment::map& env) {
Expand Down
44 changes: 0 additions & 44 deletions bindings/pydrake/systems/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -246,22 +246,6 @@ drake_py_unittest(
],
)

drake_py_library(
name = "meshcat_visualizer_py",
srcs = ["meshcat_visualizer.py"],
imports = PACKAGE_INFO.py_imports,
deps = [
":framework_py",
":module_py",
":rendering_py",
"//bindings/pydrake:geometry_py",
"//bindings/pydrake:lcm_py",
"//bindings/pydrake:math_py",
"//bindings/pydrake/common:eigen_geometry_py",
"@meshcat_python//:meshcat_sans_deprecation_warning",
],
)

drake_py_library(
name = "jupyter_widgets_py",
srcs = ["jupyter_widgets.py"],
Expand Down Expand Up @@ -333,7 +317,6 @@ PY_LIBRARIES = [
":_resample_interp1d_py",
":drawing_py",
":jupyter_widgets_py",
":meshcat_visualizer_py",
":scalar_conversion_py",
":module_py",
":perception_py",
Expand Down Expand Up @@ -490,33 +473,6 @@ drake_py_unittest(
],
)

drake_py_unittest(
name = "meshcat_visualizer_test",
data = [
"//examples/kuka_iiwa_arm:models",
"//examples/multibody/cart_pole:models",
"//examples/quadrotor:models",
"//geometry/render:test_models",
"//manipulation/models/allegro_hand_description:models",
"//manipulation/models/iiwa_description:models",
],
# Defects related to ZMQ when run under DRD or Helgrind.
tags = [
"no_drd",
"no_helgrind",
],
deps = [
":analysis_py",
":framework_py",
":meshcat_visualizer_py",
":test_util_py",
"//bindings/pydrake:geometry_py",
"//bindings/pydrake:perception_py",
"//bindings/pydrake/common/test_utilities",
"//bindings/pydrake/multibody",
],
)

drake_py_unittest(
name = "perception_test",
deps = [
Expand Down
Loading

0 comments on commit 7daf84d

Please sign in to comment.