Skip to content

Commit

Permalink
[pydrake] Deprecate the pydrake.examples.* submodules (#18685)
Browse files Browse the repository at this point in the history
All of the classes have been available from the pydrake.examples
module directly for a while now. It's time to clean out the cruft.
  • Loading branch information
jwnimmer-tri authored Jan 31, 2023
1 parent 7411176 commit c0ae8b6
Show file tree
Hide file tree
Showing 15 changed files with 91 additions and 30 deletions.
8 changes: 7 additions & 1 deletion bindings/pydrake/examples/acrobot.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,10 @@
"""Shim module that provides vestigial names for pydrake.examples.
Prefer not to use this import path in new code; all of the code in
this module can be imported from pydrake.examples directly.
This module will be deprecated at some point in the future.
"""

from pydrake.common.deprecation import _warn_deprecated

from pydrake.examples import (
AcrobotGeometry,
AcrobotInput,
Expand All @@ -13,3 +14,8 @@
AcrobotState,
SpongControllerParams,
)

_warn_deprecated(
"Please import from the pydrake.examples module directly, instead of the "
f"deprecated {__name__} submodule.",
date="2023-05-01", stacklevel=3)
8 changes: 7 additions & 1 deletion bindings/pydrake/examples/compass_gait.py
Original file line number Diff line number Diff line change
@@ -1,12 +1,18 @@
"""Shim module that provides vestigial names for pydrake.examples.
Prefer not to use this import path in new code; all of the code in
this module can be imported from pydrake.examples directly.
This module will be deprecated at some point in the future.
"""

from pydrake.common.deprecation import _warn_deprecated

from pydrake.examples import (
CompassGait,
CompassGaitContinuousState,
CompassGaitGeometry,
CompassGaitParams,
)

_warn_deprecated(
"Please import from the pydrake.examples module directly, instead of the "
f"deprecated {__name__} submodule.",
date="2023-05-01", stacklevel=3)
8 changes: 7 additions & 1 deletion bindings/pydrake/examples/manipulation_station.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,10 @@
"""Shim module that provides vestigial names for pydrake.examples.
Prefer not to use this import path in new code; all of the code in
this module can be imported from pydrake.examples directly.
This module will be deprecated at some point in the future.
"""

from pydrake.common.deprecation import _warn_deprecated

from pydrake.examples import (
CreateClutterClearingYcbObjectList,
CreateManipulationClassYcbObjectList,
Expand All @@ -12,3 +13,8 @@
ManipulationStationHardwareInterface,
SchunkCollisionModel,
)

_warn_deprecated(
"Please import from the pydrake.examples module directly, instead of the "
f"deprecated {__name__} submodule.",
date="2023-05-01", stacklevel=3)
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
import numpy as np

from pydrake.common import FindResourceOrThrow, temp_directory
from pydrake.examples.manipulation_station import ManipulationStation
from pydrake.examples import ManipulationStation
from pydrake.multibody.parsing import Parser
from pydrake.multibody.plant import AddMultibodyPlantSceneGraph
from pydrake.systems.analysis import Simulator
Expand Down
8 changes: 7 additions & 1 deletion bindings/pydrake/examples/pendulum.py
Original file line number Diff line number Diff line change
@@ -1,13 +1,19 @@
"""Shim module that provides vestigial names for pydrake.examples.
Prefer not to use this import path in new code; all of the code in
this module can be imported from pydrake.examples directly.
This module will be deprecated at some point in the future.
"""

from pydrake.common.deprecation import _warn_deprecated

from pydrake.examples import (
PendulumGeometry,
PendulumInput,
PendulumParams,
PendulumPlant,
PendulumState,
)

_warn_deprecated(
"Please import from the pydrake.examples module directly, instead of the "
f"deprecated {__name__} submodule.",
date="2023-05-01", stacklevel=3)
8 changes: 7 additions & 1 deletion bindings/pydrake/examples/quadrotor.py
Original file line number Diff line number Diff line change
@@ -1,11 +1,17 @@
"""Shim module that provides vestigial names for pydrake.examples.
Prefer not to use this import path in new code; all of the code in
this module can be imported from pydrake.examples directly.
This module will be deprecated at some point in the future.
"""

from pydrake.common.deprecation import _warn_deprecated

from pydrake.examples import (
QuadrotorGeometry,
QuadrotorPlant,
StabilizingLQRController,
)

_warn_deprecated(
"Please import from the pydrake.examples module directly, instead of the "
f"deprecated {__name__} submodule.",
date="2023-05-01", stacklevel=3)
8 changes: 7 additions & 1 deletion bindings/pydrake/examples/rimless_wheel.py
Original file line number Diff line number Diff line change
@@ -1,12 +1,18 @@
"""Shim module that provides vestigial names for pydrake.examples.
Prefer not to use this import path in new code; all of the code in
this module can be imported from pydrake.examples directly.
This module will be deprecated at some point in the future.
"""

from pydrake.common.deprecation import _warn_deprecated

from pydrake.examples import (
RimlessWheel,
RimlessWheelContinuousState,
RimlessWheelGeometry,
RimlessWheelParams,
)

_warn_deprecated(
"Please import from the pydrake.examples module directly, instead of the "
f"deprecated {__name__} submodule.",
date="2023-05-01", stacklevel=3)
13 changes: 9 additions & 4 deletions bindings/pydrake/examples/test/acrobot_test.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,14 @@
import unittest

from pydrake.examples.acrobot import (
AcrobotGeometry, AcrobotInput, AcrobotParams, AcrobotPlant,
AcrobotSpongController, AcrobotState, SpongControllerParams
)
from pydrake.examples import (
AcrobotGeometry,
AcrobotInput,
AcrobotParams,
AcrobotPlant,
AcrobotSpongController,
AcrobotState,
SpongControllerParams,
)
from pydrake.geometry import SceneGraph
from pydrake.systems.analysis import Simulator
from pydrake.systems.framework import DiagramBuilder
Expand Down
8 changes: 5 additions & 3 deletions bindings/pydrake/examples/test/compass_gait_test.py
Original file line number Diff line number Diff line change
@@ -1,8 +1,10 @@
import unittest

from pydrake.examples.compass_gait import (
CompassGait, CompassGaitContinuousState,
CompassGaitGeometry, CompassGaitParams
from pydrake.examples import (
CompassGait,
CompassGaitContinuousState,
CompassGaitGeometry,
CompassGaitParams,
)
from pydrake.geometry import SceneGraph
from pydrake.systems.analysis import Simulator
Expand Down
5 changes: 3 additions & 2 deletions bindings/pydrake/examples/test/manipulation_station_test.py
Original file line number Diff line number Diff line change
@@ -1,14 +1,15 @@
import unittest

import numpy as np

from pydrake.common import FindResourceOrThrow
from pydrake.common.test_utilities.deprecation import catch_drake_warnings
from pydrake.examples.manipulation_station import (
from pydrake.examples import (
CreateClutterClearingYcbObjectList,
CreateManipulationClassYcbObjectList,
IiwaCollisionModel,
ManipulationStation,
ManipulationStationHardwareInterface
ManipulationStationHardwareInterface,
)
from pydrake.geometry.render import (
ClippingRange,
Expand Down
11 changes: 7 additions & 4 deletions bindings/pydrake/examples/test/pendulum_test.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,12 @@
import unittest

from pydrake.examples.pendulum import (
PendulumGeometry, PendulumInput, PendulumParams, PendulumPlant,
PendulumState
)
from pydrake.examples import (
PendulumGeometry,
PendulumInput,
PendulumParams,
PendulumPlant,
PendulumState,
)
from pydrake.geometry import SceneGraph
from pydrake.systems.analysis import Simulator
from pydrake.systems.framework import DiagramBuilder
Expand Down
8 changes: 6 additions & 2 deletions bindings/pydrake/examples/test/quadrotor_test.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,13 @@
import unittest

import numpy as np

from pydrake.geometry import SceneGraph
from pydrake.examples.quadrotor import (
QuadrotorPlant, QuadrotorGeometry, StabilizingLQRController)
from pydrake.examples import (
QuadrotorGeometry,
QuadrotorPlant,
StabilizingLQRController,
)
from pydrake.systems.framework import DiagramBuilder


Expand Down
13 changes: 8 additions & 5 deletions bindings/pydrake/examples/test/rimless_wheel_test.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,13 @@
import numpy as np
import unittest

from pydrake.examples.rimless_wheel import (
RimlessWheel, RimlessWheelContinuousState,
RimlessWheelGeometry, RimlessWheelParams
)
import numpy as np

from pydrake.examples import (
RimlessWheel,
RimlessWheelContinuousState,
RimlessWheelGeometry,
RimlessWheelParams,
)
from pydrake.geometry import SceneGraph
from pydrake.systems.analysis import Simulator
from pydrake.systems.framework import DiagramBuilder
Expand Down
5 changes: 3 additions & 2 deletions bindings/pydrake/examples/test/van_der_pol_test.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
import numpy as np
import unittest

from pydrake.examples.van_der_pol import VanDerPolOscillator
import numpy as np

from pydrake.examples import VanDerPolOscillator
from pydrake.systems.analysis import Simulator


Expand Down
8 changes: 7 additions & 1 deletion bindings/pydrake/examples/van_der_pol.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,15 @@
"""Shim module that provides vestigial names for pydrake.examples.
Prefer not to use this import path in new code; all of the code in
this module can be imported from pydrake.examples directly.
This module will be deprecated at some point in the future.
"""

from pydrake.common.deprecation import _warn_deprecated

from pydrake.examples import (
VanDerPolOscillator,
)

_warn_deprecated(
"Please import from the pydrake.examples module directly, instead of the "
f"deprecated {__name__} submodule.",
date="2023-05-01", stacklevel=3)

0 comments on commit c0ae8b6

Please sign in to comment.