diff --git a/bindings/pydrake/manipulation/BUILD.bazel b/bindings/pydrake/manipulation/BUILD.bazel index 2600b2f0c3b0..dc0fb202bed0 100644 --- a/bindings/pydrake/manipulation/BUILD.bazel +++ b/bindings/pydrake/manipulation/BUILD.bazel @@ -71,13 +71,6 @@ drake_pybind_library( ], ) -drake_py_library( - name = "simple_ui_py", - srcs = ["simple_ui.py"], - imports = PACKAGE_INFO.py_imports, - deps = [":module_py"], -) - PY_LIBRARIES_WITH_INSTALL = [ ":kuka_iiwa_py", ":planner_py", @@ -86,7 +79,6 @@ PY_LIBRARIES_WITH_INSTALL = [ PY_LIBRARIES = [ ":module_py", - ":simple_ui_py", ] drake_py_unittest( @@ -116,18 +108,6 @@ drake_py_unittest( ], ) -drake_py_unittest( - name = "simple_ui_test", - data = [ - "//multibody/benchmarks/acrobot:models", - ], - deps = [ - ":simple_ui_py", - "//bindings/pydrake/common/test_utilities:deprecation_py", - "//bindings/pydrake/multibody", - ], -) - # Symbol roll-up (for user ease). drake_py_library( name = "all_py", diff --git a/bindings/pydrake/manipulation/simple_ui.py b/bindings/pydrake/manipulation/simple_ui.py deleted file mode 100644 index 8928b44a7c71..000000000000 --- a/bindings/pydrake/manipulation/simple_ui.py +++ /dev/null @@ -1,261 +0,0 @@ -""" -Provides a number of tcl/tk-based user interfaces helpful for manipulation ( -and potentially other robotics) applications. -""" - -try: - import tkinter as tk -except ImportError: - import Tkinter as tk -import numpy as np - -from pydrake.multibody.plant import MultibodyPlant -from pydrake.multibody.tree import JointIndex -from pydrake.systems.framework import ( - LeafSystem, - PublishEvent, - VectorSystem, -) -from pydrake.common.deprecation import deprecated_callable - - -@deprecated_callable("pydrake.manipulation.simple_ui.JointSliders has been" - "deprecated in favor of " - "pydrake.multibody.meshcat.JointSliders", - date="2022-06-01") -class JointSliders(VectorSystem): - """ - Provides a simple tcl/tk gui with one slider per joint of the - MultibodyPlant. Any positions that are not associated with joints (e.g. - floating-base "mobilizers") are held constant at the default value - obtained from robot.CreateDefaultContext(). - - .. pydrake_system:: - - name: JointSliders - output_ports: - - positions - """ - - def __init__(self, robot, lower_limit=-10., upper_limit=10., - resolution=-1, length=200, update_period_sec=0.005, - window=None, title=None): - """" - Args: - robot: A MultibodyPlant. - lower_limit: A scalar or vector of length robot.num_positions(). - The lower limit of the slider will be the maximum - value of this number and any limit specified in the - Joint. - upper_limit: A scalar or vector of length robot.num_positions(). - The upper limit of the slider will be the minimum - value of this number and any limit specified in the - Joint. - resolution: A scalar or vector of length robot.num_positions() - that specifies the discretization of the slider. Use - -1 (the default) to disable any rounding. - length: The length of the sliders (passed as an argument to - tk.Scale). - update_period_sec: Specifies how often the window update() method - gets called. - window: Optionally pass in a tkinter.Tk() object to add these - widgets to. Default behavior is to create a new - window. - title: The string that appears as the title of the gui - window. Use None to generate a default title. This - parameter is only used if a window==None. - """ - VectorSystem.__init__(self, 0, robot.num_positions()) - - def _reshape(x, num): - x = np.array(x) - assert len(x.shape) <= 1 - return np.array(x) * np.ones(num) - - lower_limit = _reshape(lower_limit, robot.num_positions()) - upper_limit = _reshape(upper_limit, robot.num_positions()) - resolution = _reshape(resolution, robot.num_positions()) - - if title is None: - if robot.num_model_instances() == 1: - title = robot.GetModelInstanceName(0) + " Joints" - else: - title = "Multibody Joints" - - if window is None: - self.window = tk.Tk() - self.window.title(title) - else: - self.window = window - - # Schedule window updates in either case (new or existing window): - self.DeclarePeriodicEvent(update_period_sec, 0.0, - PublishEvent(self._update)) - - self._slider = [] - self._slider_position_start = [] - context = robot.CreateDefaultContext() - state = robot.GetPositionsAndVelocities(context) - self._default_position = state[:robot.num_positions()] - - k = 0 - for i in range(0, robot.num_joints()): - joint = robot.get_joint(JointIndex(i)) - low = joint.position_lower_limits() - upp = joint.position_upper_limits() - for j in range(0, joint.num_positions()): - self._slider_position_start.append(joint.position_start() + j) - self._slider.append(tk.Scale(self.window, - from_=max(low[j], - lower_limit[k]), - to=min(upp[j], upper_limit[k]), - resolution=resolution[k], - label=joint.name(), - length=length, - orient=tk.HORIZONTAL)) - self._slider[k].pack() - k += 1 - - # TODO(russt): Consider resolving constraints in a slider event - # callback. - - def set_position(self, q): - """ - Set all robot positions (corresponding to joint positions and - potentially positions not associated with any joint) to the values in - q. Note that most models have a floating-base mobilizer by default - (unless the MultibodyPlant explicitly welds the base to the world), and - so have 7 positions corresponding to the quaternion representation of - that floating-base position, but not to any joint. - - Args: - q: a vector whose length is robot.num_positions(). - """ - self._default_position = q - for i in range(len(self._slider)): - self._slider[i].set(q[self._slider_position_start[i]]) - - def set_joint_position(self, q): - """ - Set the slider positions to the values in q. A list of positions which - must be the same length as the number of positions ASSOCIATED WITH - JOINTS in the MultibodyPlant. This does not include, e.g., - floating-base coordinates, which will be assigned a default value. - - Args: - q: a vector whose length is the same as the number of joint - positions (also the number of sliders) for the robot. - """ - assert(len(q) == len(self._slider)) - for i in range(len(self._slider)): - self._slider[i].set(q[i]) - - def _update(self, unused_context, unused_event): - self.window.update_idletasks() - self.window.update() - - def DoCalcVectorOutput(self, context, unused, unused2, output): - output[:] = self._default_position - for i in range(0, len(self._slider)): - output[self._slider_position_start[i]] = self._slider[i].get() - - -@deprecated_callable("pydrake.manipulation.simple_ui.SchunkWsgButtons has been" - " deprecated", date="2022-06-01") -class SchunkWsgButtons(LeafSystem): - """ - Adds buttons to open/close the Schunk WSG gripper to an existing Tkinter - window. - - .. pydrake_system:: - - name: SchunkWsgButtons - output_ports: - - position - - max_force - """ - - def __init__(self, window=None, open_position=0.107, - closed_position=0.002, force_limit=40, - update_period_sec=0.05): - """" - Args: - window: Optionally pass in a tkinter.Tk() object to add - these widgets to. Default behavior is to create - a new window. - update_period_sec: Specifies how often the window update() method - gets called. - open_position: Target position for the finger when open. - closed_position: Target position for the gripper when closed. - force_limit: Force limit to send to Schunk WSG controller. - """ - LeafSystem.__init__(self) - self.DeclareVectorOutputPort("position", 1, self.CalcPositionOutput) - self.DeclareVectorOutputPort("force_limit", 1, - self.CalcForceLimitOutput) - - if window is None: - self.window = tk.Tk() - self.window.title("Schunk WSG Buttons") - else: - self.window = window - - # Schedule window updates in either case (new or existing window): - self.DeclarePeriodicEvent(update_period_sec, 0.0, - PublishEvent(self._update)) - - self._open_button = tk.Button(self.window, - text="Open Gripper (spacebar)", - state=tk.DISABLED, - command=self.open) - self._open_button.pack() - self._close_button = tk.Button(self.window, - text="Close Gripper (spacebar)", - command=self.close) - self._close_button.pack() - - self._open_state = True - - self._open_position = open_position - self._closed_position = closed_position - self._force_limit = force_limit - - self.window.bind("", self._space_callback) - - def open(self): - """ - Output a command that will open the gripper. - """ - self._open_state = True - self._open_button.configure(state=tk.DISABLED) - self._close_button.configure(state=tk.NORMAL) - - def close(self): - """ - Output a command that will close the gripper. - """ - self._open_state = False - self._open_button.configure(state=tk.NORMAL) - self._close_button.configure(state=tk.DISABLED) - - def _space_callback(self, event): - if (self._open_state): - self.close() - else: - self.open() - - def _update(self, unused_context, unused_event): - self.window.update_idletasks() - self.window.update() - - def CalcPositionOutput(self, context, output): - if self._open_state: - # Push to joint limit specified in schunk_wsg_50.sdf. - output.SetAtIndex(0, self._open_position) - else: - # Closing to 0mm can smash the fingers together and keep applying - # force even when no object is grasped. - output.SetAtIndex(0, self._closed_position) - - def CalcForceLimitOutput(self, context, output): - output.SetAtIndex(0, self._force_limit) diff --git a/bindings/pydrake/manipulation/test/simple_ui_test.py b/bindings/pydrake/manipulation/test/simple_ui_test.py deleted file mode 100644 index 720f69924f63..000000000000 --- a/bindings/pydrake/manipulation/test/simple_ui_test.py +++ /dev/null @@ -1,69 +0,0 @@ -# -*- coding: utf-8 -*- - -from pydrake.manipulation.simple_ui import JointSliders, SchunkWsgButtons - -import unittest - -import numpy as np -try: - import tkinter as tk -except ImportError: - import Tkinter as tk - -from pydrake.common import FindResourceOrThrow -from pydrake.common.test_utilities.deprecation import catch_drake_warnings -from pydrake.multibody.plant import MultibodyPlant -from pydrake.multibody.parsing import Parser -from pydrake.systems.framework import BasicVector - - -class TestSimpleUI(unittest.TestCase): - def test_joint_slider(self): - # Simply test to make sure that the UI loads and produces the output. - file_name = FindResourceOrThrow( - "drake/multibody/benchmarks/acrobot/acrobot.sdf") - plant = MultibodyPlant(0.0) - Parser(plant).AddModelFromFile(file_name) - plant.Finalize() - with catch_drake_warnings(expected_count=1): - slider = JointSliders(robot=plant, lower_limit=-5., upper_limit=5., - resolution=0.001, update_period_sec=0.01, - title='test', length=300) - slider.window.withdraw() # Don't open a window during testing. - context = slider.CreateDefaultContext() - output = slider.AllocateOutput() - - q = [.1, .2] - slider.set_position(q) - slider.set_joint_position(q) - slider.CalcOutput(context, output) - - np.testing.assert_array_equal(output.get_vector_data(0).get_value(), q) - - def test_schunk_wsg_buttons(self): - window = tk.Tk() - window.withdraw() # Don't open a window during testing. - with catch_drake_warnings(expected_count=1): - wsg_buttons = SchunkWsgButtons(window, closed_position=0.008, - open_position=0.05, force_limit=50, - update_period_sec=1.0) - context = wsg_buttons.CreateDefaultContext() - output = wsg_buttons.AllocateOutput() - - # Check the port names. - wsg_buttons.GetOutputPort("position") - wsg_buttons.GetOutputPort("force_limit") - - wsg_buttons.open() - wsg_buttons.CalcOutput(context, output) - np.testing.assert_array_equal(output.get_vector_data(0).get_value(), - [0.05]) - np.testing.assert_array_equal(output.get_vector_data(1).get_value(), - [50.]) - - wsg_buttons.close() - wsg_buttons.CalcOutput(context, output) - np.testing.assert_array_equal(output.get_vector_data(0).get_value(), - [0.008]) - np.testing.assert_array_equal(output.get_vector_data(1).get_value(), - [50.]) diff --git a/bindings/pydrake/systems/BUILD.bazel b/bindings/pydrake/systems/BUILD.bazel index bc1bc5e236a5..a33834062ba0 100644 --- a/bindings/pydrake/systems/BUILD.bazel +++ b/bindings/pydrake/systems/BUILD.bazel @@ -318,13 +318,6 @@ drake_py_library( imports = PACKAGE_INFO.py_imports, ) -drake_py_library( - name = "system_sliders_py", - srcs = ["system_sliders.py"], - imports = PACKAGE_INFO.py_imports, - deps = [":module_py"], -) - PY_LIBRARIES_WITH_INSTALL = [ ":analysis_py", ":controllers_py", @@ -346,7 +339,6 @@ PY_LIBRARIES = [ ":perception_py", ":planar_scenegraph_visualizer_py", ":pyplot_visualizer_py", - ":system_sliders_py", ] # Symbol roll-up (for user ease). @@ -617,15 +609,6 @@ drake_py_unittest( ], ) -drake_py_unittest( - name = "system_sliders_test", - deps = [ - ":primitives_py", - ":system_sliders_py", - "//bindings/pydrake/common/test_utilities:deprecation_py", - ], -) - drake_py_unittest( name = "trajectory_optimization_test", deps = [ diff --git a/bindings/pydrake/systems/system_sliders.py b/bindings/pydrake/systems/system_sliders.py deleted file mode 100644 index 455df282b4d9..000000000000 --- a/bindings/pydrake/systems/system_sliders.py +++ /dev/null @@ -1,156 +0,0 @@ -try: - import tkinter as tk -except ImportError: - import Tkinter as tk - -import numpy as np - -from pydrake.systems.framework import (PublishEvent, VectorSystem) -from pydrake.common.deprecation import deprecated_callable - - -@deprecated_callable("pydrake.systems.system_sliders.SystemSliders has been" - " deprecated", date="2022-06-01") -class SystemSliders(VectorSystem): - """ - Provides a set of tcl/tk-based sliders intended to control the values - of a system's input port. Each value of the input port gets a float slider. - Each slider has can be customized with lower_limit, upper_limit, and - resolution. These values can be set generally across all sliders or - per slider with a vector of length port_size. - - Note: The sliders can only be manipulated while the simulation is - advancing time. - - @warning: Do not close the slider GUI while running a simulation. It will - cause the simulation to crash. - - .. pydrake_system:: - - name: SystemSliders - output_ports: - - slider_positions - """ - def __init__(self, port_size, slider_names=None, - lower_limit=-10., upper_limit=10., - resolution=-1, length=200, update_period_sec=0.0166, - window=None, title="System inputs"): - """ - Args: - port_size: Size of the input port that's being controlled. This - is the number of sliders that will show up. - slider_names: A list of strings describing the names of the sliders - that should be displayed. - lower_limit: The value(s) for the lower limits of each slider. See - class documentation for more details. - upper_limit: The value(s) for the upper limits of each slider. See - class documentation for more details. - resolution: A scalar or vector of length port_size - that specifies the discretization that the slider will - be rounded to. Use -1 (the default) to disable any - rounding. For example, a resolution of 0.1 will round - to the nearest 0.1. See class documentation for more - details. - length: The length of the sliders in pixels. - update_period_sec: Specifies how often the window update() method - gets called. Smaller values will theoretically make - GUI values available to the simulation more quickly, - but may require the simulation to take more steps than - necessary. The default value is suitable for most - applications. - window: Optionally pass in a tkinter.Tk() object to add these - widgets to. Default behavior is to create a new - window. - title: The string that appears as the title of the gui - window. Default title is "System sliders" This - parameter is only used if window is None. - """ - VectorSystem.__init__(self, 0, port_size) - - if window is None: - self.window = tk.Tk() - self.window.title(title) - else: - self.window = window - - self.port_size = port_size - - if slider_names is None: - slider_names = ["Index " + str(i) for i in range(self.port_size)] - if len(slider_names) != self.port_size: - raise ValueError( - f"Slider names size ({len(slider_names)}) doesn't " - f"match port size ({self.port_size})") - - def input_to_vector(x, desc): - """ - Turn scalar inputs into vector of size self.port_size. - Throws error if vector input is the wrong size, - otherwise returning the vector. - - Args: - x: scalar or vector input. - desc: string describing the vector, used in error message. - """ - if np.isscalar(x): - return np.repeat(x, self.port_size) - - if len(x) == self.port_size: - return x - - raise ValueError( - f"Size of {desc} ({len(x)}) doesn't " - f"match port size ({self.port_size})" - ) - - lower_limit = input_to_vector(lower_limit, "lower_limit") - upper_limit = input_to_vector(upper_limit, "upper_limit") - resolution = input_to_vector(resolution, "resolution") - - # Schedule window updates in either case (new or existing window): - self.DeclarePeriodicEvent(update_period_sec, 0.0, - PublishEvent(self._update_window)) - - self._sliders = [] - - # TODO: support a scroll bar for larger input sizes - for i in range(self.port_size): - slider = tk.Scale(self.window, - from_=lower_limit[i], - to=upper_limit[i], - resolution=resolution[i], - label=slider_names[i], - length=length, - orient=tk.HORIZONTAL) - slider.pack() - self._sliders.append(slider) - - def set_position(self, q): - """ - Sets all slider positions to the values in q. - - Args: - q: a vector whose length is self.port_size. - """ - if len(q) != self.port_size: - raise ValueError( - f"Size of q ({len(q)}) doesn't match input " - f"port size ({self.port_size})") - for i in range(self.port_size): - self._sliders[i].set(q[i]) - - # TODO(SeanCurtis-TRI): This is technically making a change to system - # "state" (the state of the tk window). It's not contained in the - # context, which is why we can get away with it. However, it would - # be better to add a discrete state vector that gets updated values - # from the sliders (and handles the slider update at that time) and - # update that in a DiscreteUpdate. - def _update_window(self, context, event): - # GUI functionality is not automatically tested - # Must manually test this function to ensure updates run properly - self.window.update_idletasks() - self.window.update() - - def DoCalcVectorOutput(self, context, unused, unused2, output): - for i in range(self.port_size): - output[i] = self._sliders[i].get() diff --git a/bindings/pydrake/systems/test/system_sliders_test.py b/bindings/pydrake/systems/test/system_sliders_test.py deleted file mode 100644 index 0fb5a9d710d7..000000000000 --- a/bindings/pydrake/systems/test/system_sliders_test.py +++ /dev/null @@ -1,94 +0,0 @@ -# -*- coding: utf-8 -*- - -import unittest - -import numpy as np -try: - import tkinter as tk -except ImportError: - import Tkinter as tk - -from pydrake.systems.system_sliders import SystemSliders -from pydrake.common.test_utilities.deprecation import catch_drake_warnings - - -class TestSystemSliders(unittest.TestCase): - def test_multibody_plant_slider(self): - # Tests that the UI loads and produces the output, the - # size of the output port is correct, and appropriate - # errors are thrown for incorrect usage. - port_size = 3 - with catch_drake_warnings(expected_count=1): - slider = SystemSliders(port_size, - slider_names=["x", "y", "z"], - lower_limit=-5., - upper_limit=[5., 1., 10.], resolution=0.001, - update_period_sec=0.01, title='test', - length=300) - slider.window.withdraw() # Don't open a window during testing. - context = slider.CreateDefaultContext() - output = slider.AllocateOutput() - - # Input size matches output size. - self.assertEqual( - slider.get_output_port(0).size(), - port_size - ) - - # Valid position. - q = [.1, 0, 5] - slider.set_position(q) - slider.CalcOutput(context, output) - np.testing.assert_array_equal(output.get_vector_data(0).get_value(), q) - - # Outside of upper limits. - q = [10, 10, 10] - slider.set_position(q) - slider.CalcOutput(context, output) - np.testing.assert_array_equal( - output.get_vector_data(0).get_value(), [5., 1., 10.]) - - # Outside of lower limits. - # We set lower limit to -5 by scalar value and we indirectly confirm - # that all slider lower limits got set to that scalar by setting all - # sliders to a value lower than that lower limit and observing that - # they get clamped to the same value. - q = [-10, -10, -10] - slider.set_position(q) - slider.CalcOutput(context, output) - np.testing.assert_array_equal( - output.get_vector_data(0).get_value(), [-5, -5, -5]) - - # Incorrect size of q when setting slider positions. - with self.assertRaisesRegex( - ValueError, - r"Size of q \(2\) doesn't match input port size \(3\)"): - slider.set_position([2, 4]) - - # Incorrect size of passed in slider names. - with self.assertRaisesRegex( - ValueError, - r"Slider names size \(2\) doesn't match port size \(3\)"): - with catch_drake_warnings(expected_count=1): - SystemSliders(port_size, slider_names=["a", "b"]) - - # Incorrect size of passed in lower limits. - with self.assertRaisesRegex( - ValueError, - r"Size of lower_limit \(4\) doesn't match port size \(3\)"): - with catch_drake_warnings(expected_count=1): - SystemSliders(port_size, lower_limit=[2, 3, 4, 5]) - - # Incorrect size of passed in upper limits. - with self.assertRaisesRegex( - ValueError, - r"Size of upper_limit \(0\) doesn't match port size \(3\)"): - with catch_drake_warnings(expected_count=1): - SystemSliders(port_size, upper_limit=[]) - - # Incorrect size of passed in resolutions. - with self.assertRaisesRegex( - ValueError, - r"Size of resolution \(5\) doesn't match port size \(3\)"): - with catch_drake_warnings(expected_count=1): - SystemSliders(port_size, resolution=[1, 2, 3, 4, 5]) diff --git a/setup/mac/binary_distribution/Brewfile b/setup/mac/binary_distribution/Brewfile index d8147e05419e..b54b710b1737 100644 --- a/setup/mac/binary_distribution/Brewfile +++ b/setup/mac/binary_distribution/Brewfile @@ -25,7 +25,6 @@ brew 'msgpack-cxx' brew 'openblas' brew 'pkg-config' brew 'python@3.9' -brew 'python-tk@3.9' brew 'scipy' brew 'spdlog' brew 'suite-sparse' diff --git a/setup/ubuntu/binary_distribution/packages-focal.txt b/setup/ubuntu/binary_distribution/packages-focal.txt index 9dc041a49dd6..428caf5f2ee2 100644 --- a/setup/ubuntu/binary_distribution/packages-focal.txt +++ b/setup/ubuntu/binary_distribution/packages-focal.txt @@ -58,7 +58,6 @@ python3-pil python3-pydot python3-pygame python3-scipy -python3-tk python3-tornado python3-u-msgpack python3-yaml diff --git a/setup/ubuntu/source_distribution/packages-focal-test-only.txt b/setup/ubuntu/source_distribution/packages-focal-test-only.txt index c7370e2dc950..0dd1bd9096cd 100644 --- a/setup/ubuntu/source_distribution/packages-focal-test-only.txt +++ b/setup/ubuntu/source_distribution/packages-focal-test-only.txt @@ -16,7 +16,6 @@ python3-psutil python3-requests python3-scipy-dbg python3-six -python3-tk-dbg python3-uritemplate python3-websockets python3-yaml-dbg