Skip to content

Commit

Permalink
pydrake: Remove deprecated attic-module aliases (RobotLocomotion#12145)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Oct 7, 2019
1 parent 0f748c3 commit 1522387
Show file tree
Hide file tree
Showing 4 changed files with 2 additions and 43 deletions.
10 changes: 0 additions & 10 deletions bindings/pydrake/attic/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -60,14 +60,4 @@ install(
deps = get_drake_py_installs(PY_LIBRARIES_WITH_INSTALL),
)

drake_py_unittest(
name = "attic_forwarding_test",
deps = [
"//bindings/pydrake/attic/multibody",
"//bindings/pydrake/attic/solvers",
"//bindings/pydrake/multibody",
"//bindings/pydrake/solvers",
],
)

add_lint_tests_pydrake()
19 changes: 1 addition & 18 deletions bindings/pydrake/multibody/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -134,23 +134,6 @@ drake_pybind_library(
],
)

PY_LIBRARIES_ATTIC_ALIASES = [
":collision_py",
":joints_py",
":parsers_py",
":rigid_body_plant_py",
":rigid_body_py",
":rigid_body_tree_py",
":shapes_py",
]

drake_py_library_aliases(
actual_subdir = "bindings/pydrake/attic/multibody",
add_deprecation_warning = 1,
deprecation_removal_date = "2019-10-01",
relative_labels = PY_LIBRARIES_ATTIC_ALIASES,
)

PY_LIBRARIES_WITH_INSTALL = [
":benchmarks_py",
":inverse_kinematics_py",
Expand All @@ -160,7 +143,7 @@ PY_LIBRARIES_WITH_INSTALL = [
":tree_py",
]

PY_LIBRARIES = PY_LIBRARIES_ATTIC_ALIASES + [
PY_LIBRARIES = [
":module_py",
]

Expand Down
13 changes: 1 addition & 12 deletions bindings/pydrake/solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -173,17 +173,6 @@ drake_pybind_library(
],
)

PY_LIBRARIES_ATTIC_ALIASES = [
":ik_py",
]

drake_py_library_aliases(
actual_subdir = "bindings/pydrake/attic/solvers",
add_deprecation_warning = 1,
deprecation_removal_date = "2019-10-01",
relative_labels = PY_LIBRARIES_ATTIC_ALIASES,
)

PY_LIBRARIES_WITH_INSTALL = [
":gurobi_py",
":ipopt_py",
Expand All @@ -195,7 +184,7 @@ PY_LIBRARIES_WITH_INSTALL = [
":snopt_py",
]

PY_LIBRARIES = PY_LIBRARIES_ATTIC_ALIASES + [
PY_LIBRARIES = [
":module_py",
]

Expand Down
3 changes: 0 additions & 3 deletions bindings/pydrake/test/all_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,6 @@ def test_import_warnings(self):
sys.stderr.write("Encountered import warnings:\n{}\n".format(
"\n".join(map(str, w)) + "\n"))
self.assertEqual(len(w), 0)
# Show that deprecated modules are not incorporated in `.all` (#11363).
with catch_drake_warnings(expected_count=1):
import pydrake.multibody.rigid_body_tree

def test_usage_no_all(self):
from pydrake.common import FindResourceOrThrow
Expand Down

0 comments on commit 1522387

Please sign in to comment.