Skip to content

Commit

Permalink
[geometry] Deprecate geometry_visualization (and old ConnectDrakeVisu…
Browse files Browse the repository at this point in the history
…alizer) (RobotLocomotion#14282)

* Extend DrakeVisualizer with static API

This adds a number of new static methods to DrakeVisualizer to facilitate
work flows:

  1. Static AddToBuilder to facilitate adding and connecting to a diagram.
  2. Expose core publshing functionality to allow evaluation without
     events.  (Ad hoc broadcasting.)
  3. The new AddToBuilder API is used in examples/scene_graph to show
     case the new feature. This is a pre-cursor to deprecating
     geometry_visualization.{h|cc} showing the alternative is just as
     compact as the old. (Deprecation will follow.)

 - Deprecates the three public functions in geometry_visualization.h.
    - Note: the unit test doesn't change because it isn't actually
      testing the public API.
 - Python bindings (and unit tests) appropriately deprecated.
 - Change all call sites to use the preferred mechanism.
   - Manipulation station has changed; it exports its constituent
     SceneGraph's query_object port. In the future, we'll deprecate
     the pose_bundle port.
  • Loading branch information
SeanCurtis-TRI authored Nov 6, 2020
1 parent 24b73e7 commit 4751fd6
Show file tree
Hide file tree
Showing 102 changed files with 674 additions and 285 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
import argparse

from pydrake.common import FindResourceOrThrow
from pydrake.geometry import (ConnectDrakeVisualizer, SceneGraph)
from pydrake.geometry import (DrakeVisualizer, SceneGraph)
from pydrake.lcm import DrakeLcm
from pydrake.multibody.plant import MultibodyPlant
from pydrake.multibody.parsing import Parser
Expand Down Expand Up @@ -44,7 +44,7 @@ def main():
cart_pole.get_geometry_poses_output_port(),
scene_graph.get_source_pose_port(cart_pole.get_source_id()))

ConnectDrakeVisualizer(builder=builder, scene_graph=scene_graph)
DrakeVisualizer.AddToBuilder(builder=builder, scene_graph=scene_graph)
diagram = builder.Build()

diagram_context = diagram.CreateDefaultContext()
Expand Down
61 changes: 49 additions & 12 deletions bindings/pydrake/geometry_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -998,22 +998,27 @@ void DoScalarIndependentDefinitions(py::module m) {
.value("kReplace", Class::kReplace, cls_doc.kReplace.doc);
}

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
m.def("ConnectDrakeVisualizer",
py::overload_cast<systems::DiagramBuilder<double>*,
const SceneGraph<double>&, lcm::DrakeLcmInterface*, geometry::Role>(
&ConnectDrakeVisualizer),
WrapDeprecated(doc.ConnectDrakeVisualizer.doc_deprecated_4args,
py::overload_cast<systems::DiagramBuilder<double>*,
const SceneGraph<double>&, lcm::DrakeLcmInterface*,
geometry::Role>(&ConnectDrakeVisualizer)),
py::arg("builder"), py::arg("scene_graph"), py::arg("lcm") = nullptr,
py::arg("role") = geometry::Role::kIllustration,
// Keep alive, ownership: `return` keeps `builder` alive.
py::keep_alive<0, 1>(),
// Keep alive, ownership: `builder` keeps `lcm` alive.
py::keep_alive<1, 3>(),
// See #11531 for why `py_rvp::reference` is needed.
py_rvp::reference, doc.ConnectDrakeVisualizer.doc_4args);
py_rvp::reference, doc.ConnectDrakeVisualizer.doc_deprecated_4args);
m.def("ConnectDrakeVisualizer",
py::overload_cast<systems::DiagramBuilder<double>*,
const SceneGraph<double>&, const systems::OutputPort<double>&,
lcm::DrakeLcmInterface*, geometry::Role>(&ConnectDrakeVisualizer),
WrapDeprecated(doc.ConnectDrakeVisualizer.doc_deprecated_5args,
py::overload_cast<systems::DiagramBuilder<double>*,
const SceneGraph<double>&, const systems::OutputPort<double>&,
lcm::DrakeLcmInterface*, geometry::Role>(
&ConnectDrakeVisualizer)),
py::arg("builder"), py::arg("scene_graph"),
py::arg("pose_bundle_output_port"), py::arg("lcm") = nullptr,
py::arg("role") = geometry::Role::kIllustration,
Expand All @@ -1022,10 +1027,14 @@ void DoScalarIndependentDefinitions(py::module m) {
// Keep alive, ownership: `builder` keeps `lcm` alive.
py::keep_alive<1, 3>(),
// See #11531 for why `py_rvp::reference` is needed.
py_rvp::reference, doc.ConnectDrakeVisualizer.doc_5args);
m.def("DispatchLoadMessage", &DispatchLoadMessage, py::arg("scene_graph"),
py::arg("lcm"), py::arg("role") = geometry::Role::kIllustration,
doc.DispatchLoadMessage.doc);
py_rvp::reference, doc.ConnectDrakeVisualizer.doc_deprecated_5args);
m.def("DispatchLoadMessage",
WrapDeprecated(
doc.DispatchLoadMessage.doc_deprecated, &DispatchLoadMessage),
py::arg("scene_graph"), py::arg("lcm"),
py::arg("role") = geometry::Role::kIllustration,
doc.DispatchLoadMessage.doc_deprecated);
#pragma GCC diagnostic pop

{
using Class = DrakeVisualizerParams;
Expand All @@ -1050,7 +1059,35 @@ void DoScalarIndependentDefinitions(py::module m) {
py::keep_alive<1, 2>(), // BR
cls_doc.ctor.doc)
.def("query_object_input_port", &Class::query_object_input_port,
py_rvp::reference_internal, cls_doc.query_object_input_port.doc);
py_rvp::reference_internal, cls_doc.query_object_input_port.doc)
.def_static("AddToBuilder",
py::overload_cast<systems::DiagramBuilder<double>*,
const SceneGraph<double>&, lcm::DrakeLcmInterface*,
DrakeVisualizerParams>(&DrakeVisualizer::AddToBuilder),
py::arg("builder"), py::arg("scene_graph"),
py::arg("lcm") = nullptr,
py::arg("params") = DrakeVisualizerParams{},
// Keep alive, ownership: `return` keeps `builder` alive.
py::keep_alive<0, 1>(),
// Keep alive, reference: `return` keeps `lcm` alive.
py::keep_alive<0, 3>(), py_rvp::reference,
cls_doc.AddToBuilder.doc_4args_builder_scene_graph_lcm_params)
.def_static("AddToBuilder",
py::overload_cast<systems::DiagramBuilder<double>*,
const systems::OutputPort<double>&, lcm::DrakeLcmInterface*,
DrakeVisualizerParams>(&DrakeVisualizer::AddToBuilder),
py::arg("builder"), py::arg("query_object_port"),
py::arg("lcm") = nullptr,
py::arg("params") = DrakeVisualizerParams{},
// Keep alive, ownership: `return` keeps `builder` alive.
py::keep_alive<0, 1>(),
// Keep alive, reference: `return` keeps `lcm` alive.
py::keep_alive<0, 3>(), py_rvp::reference,
cls_doc.AddToBuilder.doc_4args_builder_query_object_port_lcm_params)
.def_static("DispatchLoadMessage",
&DrakeVisualizer::DispatchLoadMessage, py::arg("scene_graph"),
py::arg("lcm"), py::arg("params") = DrakeVisualizerParams{},
cls_doc.DispatchLoadMessage.doc);
}

// Shape constructors
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
"from ipywidgets import Layout, Text, ToggleButton\n",
"\n",
"from pydrake.common import FindResourceOrThrow\n",
"from pydrake.geometry import ConnectDrakeVisualizer, DispatchLoadMessage, SceneGraph\n",
"from pydrake.geometry import DrakeVisualizer, SceneGraph\n",
"from pydrake.lcm import DrakeLcm\n",
"from pydrake.multibody.plant import AddMultibodyPlantSceneGraph, MultibodyPlant\n",
"from pydrake.multibody.parsing import Parser\n",
Expand Down Expand Up @@ -59,7 +59,7 @@
" to_pose.get_output_port(),\n",
" scene_graph.get_source_pose_port(plant.get_source_id()))\n",
"\n",
"ConnectDrakeVisualizer(builder, scene_graph)\n",
"DrakeVisualizer.AddToBuilder(builder, scene_graph)\n",
"\n",
"# Make the diagram and run it.\n",
"diagram = builder.Build()\n",
Expand Down Expand Up @@ -103,7 +103,7 @@
" \"drake/manipulation/models/iiwa_description/iiwa7/iiwa7_no_collision.sdf\"))\n",
"plant.Finalize()\n",
"\n",
"viz = ConnectDrakeVisualizer(builder, scene_graph)\n",
"viz = DrakeVisualizer.AddToBuilder(builder, scene_graph)\n",
"\n",
"# Make the diagram and run it.\n",
"diagram = builder.Build()\n",
Expand All @@ -118,7 +118,6 @@
" num_calls += 1\n",
" callback_output.value = f\"Called {num_calls} times\"\n",
"\n",
"DispatchLoadMessage(scene_graph, DrakeLcm())\n",
"sliders = MakeJointSlidersThatPublishOnCallback(plant, viz, context, my_callback=callback_test)\n",
"display(callback_output)\n"
]
Expand Down Expand Up @@ -152,4 +151,4 @@
},
"nbformat": 4,
"nbformat_minor": 4
}
}
2 changes: 1 addition & 1 deletion bindings/pydrake/multibody/jupyter_widgets.py
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ def MakeJointSlidersThatPublishOnCallback(
Args:
plant: A MultibodyPlant.
publishing_system: The System whos Publish method will be called. Can
publishing_system: The System whose Publish method will be called. Can
be the entire Diagram, but can also be a subsystem.
root_context: A mutable root Context of the Diagram containing both the
``plant`` and the ``publishing_system``; we will extract
Expand Down
4 changes: 2 additions & 2 deletions bindings/pydrake/systems/drawing_graphviz_example.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
import matplotlib.pyplot as plt

from pydrake.common import FindResourceOrThrow
from pydrake.geometry import ConnectDrakeVisualizer, SceneGraph
from pydrake.geometry import DrakeVisualizer, SceneGraph
from pydrake.lcm import DrakeLcm
from pydrake.multibody.parsing import Parser
from pydrake.multibody.plant import MultibodyPlant
Expand Down Expand Up @@ -30,7 +30,7 @@
scene_graph.get_source_pose_port(cart_pole.get_source_id()))
builder.ExportInput(cart_pole.get_actuation_input_port())

ConnectDrakeVisualizer(builder=builder, scene_graph=scene_graph)
DrakeVisualizer.AddToBuilder(builder=builder, scene_graph=scene_graph)

diagram = builder.Build()
diagram.set_name("graphviz_example")
Expand Down
6 changes: 3 additions & 3 deletions bindings/pydrake/systems/jupyter_widgets_examples.ipynb
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
"\n",
"from pydrake.common import FindResourceOrThrow\n",
"from pydrake.common.value import AbstractValue\n",
"from pydrake.geometry import ConnectDrakeVisualizer, FramePoseVector, SceneGraph\n",
"from pydrake.geometry import DrakeVisualizer, FramePoseVector, SceneGraph\n",
"from pydrake.math import RigidTransform\n",
"from pydrake.multibody.plant import MultibodyPlant\n",
"from pydrake.multibody.parsing import Parser\n",
Expand Down Expand Up @@ -83,7 +83,7 @@
" to_vector.get_output_port(0),\n",
" scene_graph.get_source_pose_port(plant.get_source_id()))\n",
"\n",
"vis = ConnectDrakeVisualizer(builder, scene_graph)\n",
"DrakeVisualizer.AddToBuilder(builder, scene_graph)\n",
"\n",
"diagram = builder.Build()\n",
"simulator = Simulator(diagram)\n",
Expand Down Expand Up @@ -166,4 +166,4 @@
},
"nbformat": 4,
"nbformat_minor": 4
}
}
6 changes: 3 additions & 3 deletions bindings/pydrake/systems/meshcat_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
from drake import lcmt_viewer_load_robot
from pydrake.common.value import AbstractValue
from pydrake.common.eigen_geometry import Quaternion, Isometry3
from pydrake.geometry import DispatchLoadMessage, SceneGraph
from pydrake.geometry import DrakeVisualizer, SceneGraph
from pydrake.lcm import DrakeLcm, Subscriber
from pydrake.math import RigidTransform, RotationMatrix
from pydrake.systems.framework import LeafSystem, PublishEvent, TriggerType
Expand Down Expand Up @@ -404,7 +404,7 @@ def load(self):
lcm=memq_lcm,
channel="DRAKE_VIEWER_LOAD_ROBOT",
lcm_type=lcmt_viewer_load_robot)
DispatchLoadMessage(self._scene_graph, memq_lcm)
DrakeVisualizer.DispatchLoadMessage(self._scene_graph, memq_lcm)
memq_lcm.HandleSubscriptions(0)
assert memq_lcm_subscriber.count > 0
load_robot_msg = memq_lcm_subscriber.message
Expand Down Expand Up @@ -755,7 +755,7 @@ def ConnectMeshcatVisualizer(builder, scene_graph, output_port=None, **kwargs):
"""Creates an instance of MeshcatVisualizer, adds it to the
diagram, and wires the scene_graph pose bundle output port to the input
port of the visualizer. Provides an interface comparable to
ConnectDrakeVisualizer.
DrakeVisualizer.AddToBuilder.
Args:
builder: The diagram builder used to construct the Diagram.
Expand Down
6 changes: 3 additions & 3 deletions bindings/pydrake/systems/planar_scenegraph_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
from drake import lcmt_viewer_load_robot
from pydrake.common.eigen_geometry import Quaternion
from pydrake.common.value import AbstractValue
from pydrake.geometry import DispatchLoadMessage, ReadObjToSurfaceMesh
from pydrake.geometry import DrakeVisualizer, ReadObjToSurfaceMesh
from pydrake.lcm import DrakeLcm, Subscriber
from pydrake.math import RigidTransform, RotationMatrix
from pydrake.systems.pyplot_visualizer import PyPlotVisualizer
Expand Down Expand Up @@ -175,7 +175,7 @@ def _build_body_patches(self, use_random_colors,
lcm_type=lcmt_viewer_load_robot)
# TODO(SeanCurtis-TRI): Use SceneGraph inspection instead of mocking
# LCM and inspecting the generated message.
DispatchLoadMessage(self._scene_graph, memq_lcm)
DrakeVisualizer.DispatchLoadMessage(self._scene_graph, memq_lcm)
memq_lcm.HandleSubscriptions(0)
assert memq_lcm_subscriber.count > 0
load_robot_msg = memq_lcm_subscriber.message
Expand Down Expand Up @@ -388,7 +388,7 @@ def ConnectPlanarSceneGraphVisualizer(builder,
"""Creates an instance of PlanarSceneGraphVisualizer, adds it to the
diagram, and wires the scene_graph pose bundle output port to the input
port of the visualizer. Provides an interface comparable to
ConnectDrakeVisualizer.
DrakeVisualizer.AddToBuilder.
Args:
builder: The diagram builder used to construct the Diagram.
Expand Down
77 changes: 54 additions & 23 deletions bindings/pydrake/test/geometry_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -215,20 +215,22 @@ def test_connect_drake_visualizer(self):
role = mut.Role.kIllustration

def normal(builder, scene_graph):
mut.ConnectDrakeVisualizer(
builder=builder, scene_graph=scene_graph,
lcm=lcm, role=role)
mut.DispatchLoadMessage(
scene_graph=scene_graph, lcm=lcm, role=role)
with catch_drake_warnings(expected_count=2):
mut.ConnectDrakeVisualizer(
builder=builder, scene_graph=scene_graph,
lcm=lcm, role=role)
mut.DispatchLoadMessage(
scene_graph=scene_graph, lcm=lcm, role=role)

def port(builder, scene_graph):
mut.ConnectDrakeVisualizer(
builder=builder, scene_graph=scene_graph,
pose_bundle_output_port=(
scene_graph.get_pose_bundle_output_port()),
lcm=lcm, role=role)
mut.DispatchLoadMessage(
scene_graph=scene_graph, lcm=lcm, role=role)
with catch_drake_warnings(expected_count=2):
mut.ConnectDrakeVisualizer(
builder=builder, scene_graph=scene_graph,
pose_bundle_output_port=(
scene_graph.get_pose_bundle_output_port()),
lcm=lcm, role=role)
mut.DispatchLoadMessage(
scene_graph=scene_graph, lcm=lcm, role=role)

for func in [normal, port]:
# Create subscribers.
Expand Down Expand Up @@ -261,16 +263,9 @@ def test_drake_visualizer(self):
Simulator = Simulator_[T]
lcm = DrakeLcm()
role = mut.Role.kIllustration

# Build the diagram.
builder = DiagramBuilder()
scene_graph = builder.AddSystem(SceneGraph())
params = mut.DrakeVisualizerParams(
publish_period=0.1, role=mut.Role.kIllustration,
default_color=mut.Rgba(0.1, 0.2, 0.3, 0.4))
visualizer = builder.AddSystem(mut.DrakeVisualizer(lcm=lcm))
builder.Connect(scene_graph.get_query_output_port(),
visualizer.query_object_input_port())

# Add some subscribers to detect message broadcast.
load_channel = "DRAKE_VIEWER_LOAD_ROBOT"
Expand All @@ -280,12 +275,48 @@ def test_drake_visualizer(self):
draw_subscriber = Subscriber(
lcm, draw_channel, lcmt_viewer_draw)

# Simulate to t = 0 to send initial load and draw messages.
diagram = builder.Build()
Simulator(diagram).AdvanceTo(0)
# There are three ways to configure DrakeVisualizer.
def by_hand(builder, scene_graph, params):
visualizer = builder.AddSystem(
mut.DrakeVisualizer(lcm=lcm, params=params))
builder.Connect(scene_graph.get_query_output_port(),
visualizer.query_object_input_port())

def auto_connect_to_system(builder, scene_graph, params):
mut.DrakeVisualizer.AddToBuilder(builder=builder,
scene_graph=scene_graph,
lcm=lcm, params=params)

def auto_connect_to_port(builder, scene_graph, params):
mut.DrakeVisualizer.AddToBuilder(
builder=builder,
query_object_port=scene_graph.get_query_output_port(),
lcm=lcm, params=params)

for func in [by_hand, auto_connect_to_system, auto_connect_to_port]:
# Build the diagram.
builder = DiagramBuilder()
scene_graph = builder.AddSystem(SceneGraph())
func(builder, scene_graph, params)

# Simulate to t = 0 to send initial load and draw messages.
diagram = builder.Build()
Simulator(diagram).AdvanceTo(0)
lcm.HandleSubscriptions(0)
self.assertEqual(load_subscriber.count, 1)
self.assertEqual(draw_subscriber.count, 1)
load_subscriber.clear()
draw_subscriber.clear()

# Ad hoc broadcasting.
scene_graph = SceneGraph()

mut.DrakeVisualizer.DispatchLoadMessage(scene_graph, lcm, params)
lcm.HandleSubscriptions(0)
self.assertEqual(load_subscriber.count, 1)
self.assertEqual(draw_subscriber.count, 1)
self.assertEqual(draw_subscriber.count, 0)
load_subscriber.clear()
draw_subscriber.clear()

@numpy_compare.check_nonsymbolic_types
def test_frame_pose_vector_api(self, T):
Expand Down
Loading

0 comments on commit 4751fd6

Please sign in to comment.