diff --git a/multibody/parsing/detail_sdf_parser.cc b/multibody/parsing/detail_sdf_parser.cc index b770a12ebaf6..04c5cc4f2ef6 100644 --- a/multibody/parsing/detail_sdf_parser.cc +++ b/multibody/parsing/detail_sdf_parser.cc @@ -811,15 +811,6 @@ std::vector AddModelsFromSpecification( nested_model, sdf::JoinName(model_name, nested_model.Name()), X_WM, plant, package_map, root_dir); - DRAKE_DEMAND(!nested_model_instances.empty()); - const ModelInstanceIndex nested_model_instance = - nested_model_instances.front(); - - plant->AddFrame(std::make_unique>( - nested_model.Name(), - plant->GetFrameByName("__model__", nested_model_instance), - RigidTransformd::Identity(), model_instance)); - added_model_instances.insert(added_model_instances.end(), nested_model_instances.begin(), nested_model_instances.end()); diff --git a/multibody/parsing/test/detail_sdf_parser_test.cc b/multibody/parsing/test/detail_sdf_parser_test.cc index 40ff92fda78f..a12c2e5eef74 100644 --- a/multibody/parsing/test/detail_sdf_parser_test.cc +++ b/multibody/parsing/test/detail_sdf_parser_test.cc @@ -1486,16 +1486,8 @@ GTEST_TEST(SdfParser, ModelPlacementFrame) { ASSERT_TRUE(plant->HasModelInstanceNamed("table::mug")); ModelInstanceIndex model_m = plant->GetModelInstanceByName("table::mug"); - ASSERT_TRUE(plant->HasFrameNamed("mug")); - const Frame& frame_M = plant->GetFrameByName("mug"); ASSERT_TRUE(plant->HasFrameNamed("__model__", model_m)); - // frame M is equivalent to mug::__model__ - EXPECT_TRUE(CompareMatrices( - plant->GetFrameByName("__model__", model_m) - .CalcPoseInWorld(*context) - .GetAsMatrix4(), - plant->GetFrameByName("mug").CalcPoseInWorld(*context).GetAsMatrix4(), - kEps)); + const Frame& frame_M = plant->GetFrameByName("__model__", model_m); ASSERT_TRUE(plant->HasFrameNamed("table_top")); const Frame& frame_S = plant->GetFrameByName("table_top");