Skip to content

Commit

Permalink
Move meshes and models into drake_models
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri committed Apr 7, 2023
1 parent 3f9800b commit a544708
Show file tree
Hide file tree
Showing 357 changed files with 714 additions and 1,186,854 deletions.
2 changes: 1 addition & 1 deletion bindings/pydrake/common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -489,7 +489,7 @@ install(

drake_py_unittest(
name = "module_test",
data = ["//examples/atlas:models"],
data = ["//examples/acrobot:models"],
deps = [
":module_py",
"//bindings/pydrake:autodiffutils_py",
Expand Down
4 changes: 1 addition & 3 deletions bindings/pydrake/common/test/module_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,7 @@ def test_drake_demand_throws(self):
]))

def test_find_resource_or_throw(self):
mut.FindResourceOrThrow(
'drake/examples/atlas/urdf/atlas_convex_hull.urdf'
)
mut.FindResourceOrThrow("drake/examples/acrobot/Acrobot.urdf")

def test_test_temp_directory(self):
temp_dir = mut.temp_directory()
Expand Down
2 changes: 0 additions & 2 deletions bindings/pydrake/multibody/test/parsing_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,6 @@ def test_package_map(self):
dut = PackageMap.MakeEmpty()
dut2 = PackageMap.MakeEmpty()
tmpdir = os.environ.get('TEST_TMPDIR')
model = FindResourceOrThrow(
"drake/examples/atlas/urdf/atlas_minimal_contact.urdf")

# Simple coverage test for Add, AddMap, Contains, size,
# GetPackageNames, GetPath, AddPackageXml, Remove.
Expand Down
1 change: 1 addition & 0 deletions bindings/pydrake/systems/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -271,6 +271,7 @@ drake_py_library(
":pyplot_visualizer_py",
":rendering_py",
"//bindings/pydrake:lcm_py",
"@bazel_tools//tools/python/runfiles",
],
)

Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
import unittest

import bazel_tools.tools.python.runfiles.runfiles
import numpy as np
import os

Expand Down Expand Up @@ -159,8 +160,9 @@ def scene_graph_with_mesh(filename, scale=1.0):
return scene_graph

# This mesh should load correctly.
mesh_name = FindResourceOrThrow(
"drake/manipulation/models/iiwa_description/meshes/visual/"
runfiles = bazel_tools.tools.python.runfiles.runfiles.Create()
mesh_name = runfiles.Rlocation(
"drake_models/iiwa_description/meshes/iiwa14/visual/"
"link_0.obj")
scene_graph = scene_graph_with_mesh(mesh_name)
PlanarSceneGraphVisualizer(scene_graph)
Expand Down
1 change: 0 additions & 1 deletion examples/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,6 @@ drake_cc_binary(
# process, and loaded into drake_visualizer's model database by default.
INSTALLED_MODEL_PACKAGES = [
"//examples/acrobot",
"//examples/atlas",
"//examples/hydroelastic/spatula_slip_control",
"//examples/kuka_iiwa_arm/models",
"//examples/manipulation_station",
Expand Down
272 changes: 264 additions & 8 deletions examples/atlas/BUILD.bazel

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion examples/atlas/README.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@

This directory contains models for Atlas.
This directory contains a small demo of Atlas dynamics.

Historical note
---------------
Expand Down
2 changes: 1 addition & 1 deletion examples/atlas/atlas_run_dynamics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ int do_main() {
multibody::AddMultibodyPlant(plant_config, &builder);

multibody::Parser(&plant).AddModelsFromUrl(
"package://drake/examples/atlas/urdf/atlas_convex_hull.urdf");
"package://drake_models/atlas/atlas_convex_hull.urdf");

// Add model of the ground.
const double static_friction = 1.0;
Expand Down
1 change: 0 additions & 1 deletion examples/atlas/config/.gitignore

This file was deleted.

Loading

0 comments on commit a544708

Please sign in to comment.