Skip to content

Commit

Permalink
fixup! Simplify test resource finding
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored and RussTedrake committed Jun 30, 2024
1 parent 1e02382 commit b95a2fe
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 99 deletions.
21 changes: 4 additions & 17 deletions multibody/parsing/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,6 @@ load(
"//tools/workspace/dm_control_internal:files.bzl",
"dm_control_mujoco_files",
)
load(
"//tools/workspace/mujoco_menagerie_internal:files.bzl",
"mujoco_menagerie_files",
)

filegroup(
name = "test_models",
Expand Down Expand Up @@ -48,18 +44,6 @@ _DM_CONTROL_MUJOCO_FILES = forward_files(
visibility = ["//visibility:private"],
)

_MUJOCO_MENAGERIE_FILES = forward_files(
srcs = [
"@mujoco_menagerie_internal//:" +
x
for x in mujoco_menagerie_files()
],
dest_prefix = "mujoco_menagerie/",
strip_prefix = "@mujoco_menagerie_internal//:",
tags = ["manual"],
visibility = ["//visibility:private"],
)

drake_cc_package_library(
name = "parsing",
visibility = ["//visibility:public"],
Expand Down Expand Up @@ -668,10 +652,13 @@ drake_cc_googletest(
":test_models",
"//geometry:test_obj_files",
"//geometry:test_stl_files",
] + _DM_CONTROL_MUJOCO_FILES + _MUJOCO_MENAGERIE_FILES,
"@mujoco_menagerie_internal//:google_robot",
"@mujoco_menagerie_internal//:kuka_iiwa_14",
] + _DM_CONTROL_MUJOCO_FILES,
deps = [
":detail_mujoco_parser",
"//common:find_resource",
"//common:find_runfiles",
"//common/test_utilities:diagnostic_policy_test_base",
"//common/test_utilities:eigen_matrix_compare",
"//common/test_utilities:expect_throws_message",
Expand Down
8 changes: 5 additions & 3 deletions multibody/parsing/test/detail_mujoco_parser_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <gtest/gtest.h>

#include "drake/common/find_resource.h"
#include "drake/common/find_runfiles.h"
#include "drake/common/test_utilities/diagnostic_policy_test_base.h"
#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/common/test_utilities/expect_throws_message.h"
Expand Down Expand Up @@ -149,9 +150,10 @@ TEST_P(MujocoMenagerieTest, MujocoMenagerie) {
// Confirm successful parsing of the MuJoCo models in the DeepMind control
// suite.
std::string model{GetParam()};
const std::string filename = FindResourceOrThrow(
fmt::format("drake/multibody/parsing/mujoco_menagerie/{}.xml", model));
AddModelFromFile(filename, model);
const RlocationOrError rlocation = FindRunfile(
fmt::format("mujoco_menagerie_internal/{}.xml", model));
ASSERT_EQ(rlocation.error, "");
AddModelFromFile(rlocation.abspath, model);

EXPECT_TRUE(plant_.HasModelInstanceNamed(model));

Expand Down
74 changes: 0 additions & 74 deletions tools/workspace/mujoco_menagerie_internal/files.bzl

This file was deleted.

12 changes: 7 additions & 5 deletions tools/workspace/mujoco_menagerie_internal/package.BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,13 @@

package(default_visibility = ["//visibility:public"])

# We maintain a different export_files for each subdirectory of the repository,
# We maintain a different filegroup for each subdirectory of the repository,
# and only once we have vetted the license (in the main LICENSE file).
#
# DO NOT ADD new subdirectories here unless and until you vet their LICENSE.

# google_robot
exports_files(
filegroup(
name = "google_robot",
srcs = [
"google_robot/robot.xml",
"google_robot/LICENSE",
Expand All @@ -17,8 +19,8 @@ exports_files(
]),
)

# kuka_iiwa_14
exports_files(
filegroup(
name = "kuka_iiwa_14",
srcs = [
"kuka_iiwa_14/iiwa14.xml",
"kuka_iiwa_14/LICENSE",
Expand Down

0 comments on commit b95a2fe

Please sign in to comment.