Skip to content

Commit

Permalink
Add remaining menagerie models
Browse files Browse the repository at this point in the history
Towards RobotLocomotion#20444

Brings the remaining models from the menagerie under test for the
mujoco parser. All of them are permissively licensed (but this
requires manual confirmation).

The non-uniform mesh error is being tracked in RobotLocomotion#22046. My plan is to
follow-up immediately with fixes for the other two known errors that
are being documented in the expanded test.
  • Loading branch information
RussTedrake committed Jan 2, 2025
1 parent c0f66f6 commit fd88e8c
Show file tree
Hide file tree
Showing 5 changed files with 657 additions and 21 deletions.
5 changes: 1 addition & 4 deletions multibody/parsing/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -669,10 +669,7 @@ drake_cc_googletest(
":test_models",
"//geometry:test_obj_files",
"//geometry:test_stl_files",
"@mujoco_menagerie_internal//:google_robot",
"@mujoco_menagerie_internal//:hello_robot_stretch",
"@mujoco_menagerie_internal//:kuka_iiwa_14",
"@mujoco_menagerie_internal//:rethink_robotics_sawyer",
"@mujoco_menagerie_internal//:menagerie",
] + _DM_CONTROL_MUJOCO_FILES,
deps = [
":detail_mujoco_parser",
Expand Down
2 changes: 1 addition & 1 deletion multibody/parsing/detail_mujoco_parser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ class MujocoParser {
R.col(0) = xyaxes.head<3>();
R.col(1) = xyaxes.tail<3>();
R.col(2) = xyaxes.head<3>().cross(xyaxes.tail<3>());
return RigidTransformd(RotationMatrixd(R), pos);
return RigidTransformd(RotationMatrixd::ProjectToRotationMatrix(R), pos);
}

Vector3d zaxis;
Expand Down
169 changes: 160 additions & 9 deletions multibody/parsing/test/detail_mujoco_parser_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -144,13 +144,15 @@ const char* dm_control_models[] = {
INSTANTIATE_TEST_SUITE_P(DeepMindControl, DeepMindControlTest,
testing::ValuesIn(dm_control_models));

class MujocoMenagerieTest : public MujocoParserTest,
public testing::WithParamInterface<const char*> {};
class MujocoMenagerieTest
: public MujocoParserTest,
public testing::WithParamInterface<std::pair<const char*, const char*>> {
};

TEST_P(MujocoMenagerieTest, MujocoMenagerie) {
// Confirm successful parsing of the MuJoCo models in the DeepMind control
// suite.
std::string model{GetParam()};
auto [model, error_regex] = GetParam();
const RlocationOrError rlocation = FindRunfile(
fmt::format("mujoco_menagerie_internal/{}.xml", model));
ASSERT_EQ(rlocation.error, "");
Expand All @@ -160,17 +162,166 @@ TEST_P(MujocoMenagerieTest, MujocoMenagerie) {

// For this test, ignore all warnings.
warning_records_.clear();

if (!std::string(error_regex).empty()) {
EXPECT_THAT(TakeError(), MatchesRegex(error_regex));
// For now, we'll just capture the *first* error.
error_records_.clear();
}
}

const char* mujoco_menagerie_models[] = {"google_robot/robot",
"kuka_iiwa_14/iiwa14",
"rethink_robotics_sawyer/sawyer"};
// TODO(russt): Add the remaining models, once they can be parsed correctly, as
// tracked in #20444.
// TODO(russt): Add logic to check for warnings, too. Some are
// acceptable/expected, but warnings like the stl2obj message make the model
// unusable.

const char* kItWorks = "";
namespace KnownErrors {
const char* kNonUniformScale = ".*non-uniform scale.*"; // #22046
const char* kMoreThanOneOrientation = ".*more than one orientation.*";
const char* kCapsuleSize = ".*size attribute for capsule geom.*";
} // namespace KnownErrors

const std::pair<const char*, const char*> mujoco_menagerie_models[] = {
{"agility_cassie/cassie", KnownErrors::kNonUniformScale},
{"agility_cassie/scene", KnownErrors::kNonUniformScale},
{"aloha/aloha", kItWorks},
{"aloha/scene", kItWorks},
{"anybotics_anymal_b/anymal_b", KnownErrors::kMoreThanOneOrientation},
{"anybotics_anymal_b/scene", KnownErrors::kMoreThanOneOrientation},
{"anybotics_anymal_c/anymal_c", kItWorks},
{"anybotics_anymal_c/anymal_c_mjx", kItWorks},
{"anybotics_anymal_c/scene", kItWorks},
{"anybotics_anymal_c/scene_mjx", kItWorks},
{"berkeley_humanoid/berkeley_humanoid", kItWorks},
{"berkeley_humanoid/scene", kItWorks},
{"bitcraze_crazyflie_2/cf2", kItWorks},
{"bitcraze_crazyflie_2/scene", kItWorks},
{"boston_dynamics_spot/scene", kItWorks},
{"boston_dynamics_spot/scene_arm", kItWorks},
{"boston_dynamics_spot/spot", kItWorks},
{"boston_dynamics_spot/spot_arm", kItWorks},
{"flybody/fruitfly", kItWorks},
{"flybody/scene", kItWorks},
{"franka_emika_panda/hand", kItWorks},
{"franka_emika_panda/mjx_panda", kItWorks},
{"franka_emika_panda/mjx_scene", kItWorks},
{"franka_emika_panda/mjx_single_cube", kItWorks},
{"franka_emika_panda/panda", kItWorks},
{"franka_emika_panda/panda_nohand", kItWorks},
{"franka_emika_panda/scene", kItWorks},
{"franka_fr3/fr3", kItWorks},
{"franka_fr3/scene", kItWorks},
{"google_barkour_v0/barkour_v0", kItWorks},
{"google_barkour_v0/barkour_v0_mjx", kItWorks},
{"google_barkour_v0/scene", kItWorks},
{"google_barkour_v0/scene_barkour", kItWorks},
{"google_barkour_v0/scene_mjx", kItWorks},
{"google_barkour_vb/barkour_vb", kItWorks},
{"google_barkour_vb/barkour_vb_mjx", kItWorks},
{"google_barkour_vb/scene", kItWorks},
{"google_barkour_vb/scene_hfield_mjx", kItWorks},
{"google_barkour_vb/scene_mjx", kItWorks},
{"google_robot/robot", kItWorks},
{"google_robot/scene", kItWorks},
/* These currently throw in RotationalInertia<T>::ThrowNotPhysicallyValid(),
but only in Debug mode. This is possibly due to the fact that the stl
geometries are not being parsed, so the proper inertias are not being
computed.
{"hello_robot_stretch/scene", KnownErrors::kNonUniformScale},
{"hello_robot_stretch/stretch", KnownErrors::kNonUniformScale},
{"hello_robot_stretch_3/scene", KnownErrors::kNonUniformScale},
{"hello_robot_stretch_3/stretch", KnownErrors::kNonUniformScale},
*/
{"kinova_gen3/gen3", kItWorks},
{"kinova_gen3/scene", kItWorks},
{"kuka_iiwa_14/iiwa14", kItWorks},
{"kuka_iiwa_14/scene", kItWorks},
{"leap_hand/left_hand", kItWorks},
{"leap_hand/right_hand", kItWorks},
{"leap_hand/scene_left", kItWorks},
{"leap_hand/scene_right", kItWorks},
{"pal_talos/scene_motor", KnownErrors::kNonUniformScale},
{"pal_talos/scene_position", KnownErrors::kNonUniformScale},
{"pal_talos/talos", KnownErrors::kNonUniformScale},
{"pal_talos/talos_motor", KnownErrors::kNonUniformScale},
{"pal_talos/talos_position", KnownErrors::kNonUniformScale},
{"pal_tiago/scene_motor", KnownErrors::kNonUniformScale},
{"pal_tiago/scene_position", KnownErrors::kNonUniformScale},
{"pal_tiago/scene_velocity", KnownErrors::kNonUniformScale},
{"pal_tiago/tiago", KnownErrors::kNonUniformScale},
{"pal_tiago/tiago_motor", KnownErrors::kNonUniformScale},
{"pal_tiago/tiago_position", KnownErrors::kNonUniformScale},
{"pal_tiago/tiago_velocity", KnownErrors::kNonUniformScale},
{"pal_tiago_dual/scene_motor", KnownErrors::kNonUniformScale},
{"pal_tiago_dual/scene_position", KnownErrors::kNonUniformScale},
{"pal_tiago_dual/scene_velocity", KnownErrors::kNonUniformScale},
{"pal_tiago_dual/tiago_dual", KnownErrors::kNonUniformScale},
{"pal_tiago_dual/tiago_dual_motor", KnownErrors::kNonUniformScale},
{"pal_tiago_dual/tiago_dual_position", KnownErrors::kNonUniformScale},
{"pal_tiago_dual/tiago_dual_velocity", KnownErrors::kNonUniformScale},
{"realsense_d435i/d435i", KnownErrors::kCapsuleSize},
{"rethink_robotics_sawyer/scene", kItWorks},
{"rethink_robotics_sawyer/sawyer", kItWorks},
{"robotiq_2f85/2f85", kItWorks},
{"robotiq_2f85/scene", kItWorks},
{"robotiq_2f85_v4/2f85", kItWorks},
{"robotiq_2f85_v4/scene", kItWorks},
{"robotis_op3/op3", kItWorks},
{"robotis_op3/scene", kItWorks},
{"shadow_dexee/scene", kItWorks},
{"shadow_dexee/shadow_dexee", kItWorks},
{"shadow_hand/keyframes", kItWorks},
{"shadow_hand/left_hand", KnownErrors::kNonUniformScale},
{"shadow_hand/right_hand", kItWorks},
{"shadow_hand/scene_left", KnownErrors::kNonUniformScale},
{"shadow_hand/scene_right", kItWorks},
{"skydio_x2/scene", kItWorks},
{"skydio_x2/x2", kItWorks},
{"trossen_vx300s/scene", kItWorks},
{"trossen_vx300s/vx300s", kItWorks},
{"trossen_wx250s/scene", kItWorks},
{"trossen_wx250s/wx250s", kItWorks},
{"trs_so_arm100/scene", kItWorks},
{"trs_so_arm100/so_arm100", kItWorks},
{"ufactory_lite6/lite6", kItWorks},
{"ufactory_lite6/lite6_gripper_narrow", kItWorks},
{"ufactory_lite6/lite6_gripper_wide", kItWorks},
{"ufactory_lite6/scene", kItWorks},
{"ufactory_xarm7/hand", kItWorks},
{"ufactory_xarm7/scene", kItWorks},
{"ufactory_xarm7/xarm7", kItWorks},
{"ufactory_xarm7/xarm7_nohand", kItWorks},
{"unitree_a1/a1", kItWorks},
{"unitree_a1/scene", kItWorks},
{"unitree_g1/g1", kItWorks},
{"unitree_g1/g1_with_hands", kItWorks},
{"unitree_g1/scene", kItWorks},
{"unitree_g1/scene_with_hands", kItWorks},
{"unitree_go1/go1", kItWorks},
{"unitree_go1/scene", kItWorks},
{"unitree_go2/go2", kItWorks},
{"unitree_go2/go2_mjx", kItWorks},
{"unitree_go2/scene", kItWorks},
{"unitree_go2/scene_mjx", kItWorks},
{"unitree_h1/h1", kItWorks},
{"unitree_h1/scene", kItWorks},
{"unitree_z1/scene", kItWorks},
{"unitree_z1/z1", kItWorks},
{"unitree_z1/z1_gripper", kItWorks},
{"universal_robots_ur10e/scene", kItWorks},
{"universal_robots_ur10e/ur10e", kItWorks},
{"universal_robots_ur5e/scene", kItWorks},
{"universal_robots_ur5e/ur5e", kItWorks},
{"wonik_allegro/left_hand", kItWorks},
{"wonik_allegro/right_hand", kItWorks},
{"wonik_allegro/scene_left", kItWorks},
{"wonik_allegro/scene_right", kItWorks},
};

INSTANTIATE_TEST_SUITE_P(MujocoMenagerie, MujocoMenagerieTest,
testing::ValuesIn(mujoco_menagerie_models));


// In addition to confirming that the parser can successfully parse the model,
// this test can be used to manually inspect the resulting visualization.
GTEST_TEST(MujocoParserExtraTest, Visualize) {
Expand Down Expand Up @@ -840,7 +991,7 @@ TEST_F(MujocoParserTest, MeshFileRelativePathFromFile) {
EXPECT_EQ(mesh->scale(), 1.0);
}

TEST_F(MujocoParserTest, InertiaFromGeometry) {
TEST_F(MujocoParserTest, InertialFromGeometry) {
std::string xml = fmt::format(R"""(
<mujoco model="test">
<default class="main">
Expand Down
Loading

0 comments on commit fd88e8c

Please sign in to comment.