diff --git a/geometry/meshcat_visualizer.cc b/geometry/meshcat_visualizer.cc index 66d7df8582c0..51a2e68971be 100644 --- a/geometry/meshcat_visualizer.cc +++ b/geometry/meshcat_visualizer.cc @@ -49,8 +49,6 @@ MeshcatVisualizer::MeshcatVisualizer(std::shared_ptr meshcat, this->DeclareAbstractInputPort("query_object", Value>()) .get_index(); - meshcat_->SetProperty(params_.prefix, "visible", params_.visible_by_default); - if (params_.enable_alpha_slider) { meshcat_->AddSlider( alpha_slider_name_, 0.02, 1.0, 0.02, alpha_value_); @@ -65,7 +63,7 @@ MeshcatVisualizer::MeshcatVisualizer(const MeshcatVisualizer& other) template void MeshcatVisualizer::Delete() const { meshcat_->Delete(params_.prefix); - version_ = GeometryVersion(); + version_ = std::nullopt; } template @@ -127,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; } @@ -281,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 00745ad73862..4f75b6cc0c00 100644 --- a/geometry/test/meshcat_visualizer_test.cc +++ b/geometry/test/meshcat_visualizer_test.cc @@ -66,6 +66,7 @@ class MeshcatVisualizerWithIiwaTest : public ::testing::Test { 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>(); @@ -84,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")); @@ -92,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 = @@ -100,8 +106,6 @@ TEST_F(MeshcatVisualizerWithIiwaTest, BasicTest) { simulator.AdvanceTo(0.1); EXPECT_NE(meshcat_->GetPackedTransform("visualizer/iiwa14/iiwa_link_7"), packed_X_W7); - - CheckVisible("/drake/visualizer", true); } TEST_F(MeshcatVisualizerWithIiwaTest, PublishPeriod) { @@ -179,8 +183,10 @@ 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); + systems::Simulator simulator(*diagram_); + simulator.AdvanceTo(0.1); // Confirm that the path was added but was set to be invisible. CheckVisible("/drake/visualizer", false); @@ -189,7 +195,6 @@ TEST_F(MeshcatVisualizerWithIiwaTest, NotVisibleByDefault) { TEST_F(MeshcatVisualizerWithIiwaTest, DeletePrefixOnInitialization) { MeshcatVisualizerParams params; params.delete_on_initialization_event = true; - params.visible_by_default = false; SetUpDiagram(params); // Scribble a transform onto the scene tree beneath the visualizer prefix. meshcat_->SetTransform("/drake/visualizer/my_random_path", @@ -203,13 +208,10 @@ TEST_F(MeshcatVisualizerWithIiwaTest, DeletePrefixOnInitialization) { } // Confirm that my scribble was deleted. EXPECT_FALSE(meshcat_->HasPath("/drake/visualizer/my_random_path")); - // Confirm that the path that was re-added is again set to be invisible. - CheckVisible("/drake/visualizer", false); // Repeat, but this time with delete prefix disabled. params.delete_on_initialization_event = false; SetUpDiagram(params); - CheckVisible("/drake/visualizer", false); meshcat_->SetTransform("/drake/visualizer/my_random_path", math::RigidTransformd()); { // Send an initialization event. @@ -219,7 +221,6 @@ TEST_F(MeshcatVisualizerWithIiwaTest, DeletePrefixOnInitialization) { } // Confirm that my scribble remains. EXPECT_TRUE(meshcat_->HasPath("/drake/visualizer/my_random_path")); - CheckVisible("/drake/visualizer", false); } TEST_F(MeshcatVisualizerWithIiwaTest, Delete) {