From 95e4496bb63df54349e32dc88c9aad595cb228e4 Mon Sep 17 00:00:00 2001 From: Russ Tedrake Date: Tue, 13 Jun 2023 12:23:43 -0400 Subject: [PATCH] MeshcatVisualizer sets visibility directly without events (#19578) Previously, the visibility parameter was not respected (a) before the initialization event or (b) if delete_on_initialization_event was false. Now, we update visibility exactly when we first transmit shapes to Meshcat and we don't update visibility during (re-)initialization. --- geometry/meshcat_visualizer.cc | 14 +++++++--- geometry/meshcat_visualizer.h | 3 +- geometry/test/meshcat_visualizer_test.cc | 35 ++++++++++++++---------- 3 files changed, 33 insertions(+), 19 deletions(-) diff --git a/geometry/meshcat_visualizer.cc b/geometry/meshcat_visualizer.cc index cce3a10d22fc..51a2e68971be 100644 --- a/geometry/meshcat_visualizer.cc +++ b/geometry/meshcat_visualizer.cc @@ -63,7 +63,7 @@ MeshcatVisualizer::MeshcatVisualizer(const MeshcatVisualizer& other) template void MeshcatVisualizer::Delete() const { meshcat_->Delete(params_.prefix); - version_ = GeometryVersion(); + version_ = std::nullopt; } template @@ -125,8 +125,15 @@ systems::EventStatus MeshcatVisualizer::UpdateMeshcat( query_object_input_port().template Eval>(context); const GeometryVersion& current_version = query_object.inspector().geometry_version(); - - if (!version_.IsSameAs(current_version, params_.role)) { + if (!version_.has_value()) { + // When our current version is null, that means we haven't added any + // geometry to Meshcat yet, which means we also need to establish our + // default visibility just prior to sending the geometry. + meshcat_->SetProperty(params_.prefix, "visible", + params_.visible_by_default); + } + if (!version_.has_value() || + !version_->IsSameAs(current_version, params_.role)) { SetObjects(query_object.inspector()); version_ = current_version; } @@ -279,7 +286,6 @@ template systems::EventStatus MeshcatVisualizer::OnInitialization( const systems::Context&) const { Delete(); - meshcat_->SetProperty(params_.prefix, "visible", params_.visible_by_default); return systems::EventStatus::Succeeded(); } diff --git a/geometry/meshcat_visualizer.h b/geometry/meshcat_visualizer.h index 3a24db06e60f..c757b0c6eda3 100644 --- a/geometry/meshcat_visualizer.h +++ b/geometry/meshcat_visualizer.h @@ -2,6 +2,7 @@ #include #include +#include #include #include "drake/geometry/geometry_roles.h" @@ -193,7 +194,7 @@ class MeshcatVisualizer final : public systems::LeafSystem { before SetTransforms. This is intended to track the information in meshcat_, and is therefore also a mutable member variable (instead of declared state). */ - mutable GeometryVersion version_; + mutable std::optional version_; /* A store of the dynamic frames and their path. It is coupled with the version_. This is only for efficiency; it does not represent undeclared diff --git a/geometry/test/meshcat_visualizer_test.cc b/geometry/test/meshcat_visualizer_test.cc index 71a1a1d641aa..4f75b6cc0c00 100644 --- a/geometry/test/meshcat_visualizer_test.cc +++ b/geometry/test/meshcat_visualizer_test.cc @@ -62,6 +62,18 @@ class MeshcatVisualizerWithIiwaTest : public ::testing::Test { context_ = diagram_->CreateDefaultContext(); } + void CheckVisible(const std::string& path, bool visibility) { + ASSERT_TRUE(meshcat_->HasPath(path)); + const std::string property = + meshcat_->GetPackedProperty(path, "visible"); + ASSERT_GT(property.size(), 0); + msgpack::object_handle oh = + msgpack::unpack(property.data(), property.size()); + auto data = oh.get().as>(); + EXPECT_EQ(data.property, "visible"); + EXPECT_EQ(data.value, visibility); + } + std::shared_ptr meshcat_; multibody::MultibodyPlant* plant_{}; SceneGraph* scene_graph_{}; @@ -73,6 +85,10 @@ class MeshcatVisualizerWithIiwaTest : public ::testing::Test { TEST_F(MeshcatVisualizerWithIiwaTest, BasicTest) { SetUpDiagram(); + // Visibility remains unset until geometry gets added. + EXPECT_EQ(meshcat_->GetPackedProperty("/drake/visualizer", "visible").size(), + 0); + EXPECT_FALSE(meshcat_->HasPath("/drake/visualizer/iiwa14")); diagram_->ForcedPublish(*context_); EXPECT_TRUE(meshcat_->HasPath("/drake/visualizer/iiwa14")); @@ -81,6 +97,7 @@ TEST_F(MeshcatVisualizerWithIiwaTest, BasicTest) { fmt::format("/drake/visualizer/iiwa14/iiwa_link_{}", link)), ""); } + CheckVisible("/drake/visualizer", true); // Confirm that the transforms change after running a simulation. const std::string packed_X_W7 = @@ -166,23 +183,13 @@ TEST_F(MeshcatVisualizerWithIiwaTest, NotVisibleByDefault) { MeshcatVisualizerParams params; params.visible_by_default = false; - // Create the diagram and publish both the initialization and periodic event. + // Create and run the diagram. SetUpDiagram(params); - { - auto events = diagram_->AllocateCompositeEventCollection(); - diagram_->GetInitializationEvents(*context_, events.get()); - diagram_->Publish(*context_, events->get_publish_events()); - diagram_->ForcedPublish(*context_); - } + systems::Simulator simulator(*diagram_); + simulator.AdvanceTo(0.1); // Confirm that the path was added but was set to be invisible. - ASSERT_TRUE(meshcat_->HasPath("/drake/visualizer")); - const std::string property = - meshcat_->GetPackedProperty("/drake/visualizer", "visible"); - msgpack::object_handle oh = msgpack::unpack(property.data(), property.size()); - auto data = oh.get().as>(); - EXPECT_EQ(data.property, "visible"); - EXPECT_EQ(data.value, false); + CheckVisible("/drake/visualizer", false); } TEST_F(MeshcatVisualizerWithIiwaTest, DeletePrefixOnInitialization) {