Skip to content

Commit

Permalink
move from gcs repo to RobotLocomotion/models
Browse files Browse the repository at this point in the history
  • Loading branch information
RussTedrake committed Jul 20, 2023
1 parent be6cc71 commit 1f84c13
Show file tree
Hide file tree
Showing 13 changed files with 202 additions and 28 deletions.
18 changes: 18 additions & 0 deletions geometry/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -607,6 +607,24 @@ drake_cc_googletest(

# -----------------------------------------------------

filegroup(
name = "models",
srcs = [
"models/bin/bin.sdf",
"@drake_models//:geometry/bin/bin.mtl",
"@drake_models//:geometry/bin/bin.obj",
"@drake_models//:geometry/bin/bin.png",
"models/table/table_wide.sdf",
"@drake_models//:geometry/table/table_wide.mtl",
"@drake_models//:geometry/table/table_wide.obj",
"@drake_models//:geometry/table/table_wide.png",
"models/shelves/shelves.sdf",
"@drake_models//:geometry/shelves/shelves.mtl",
"@drake_models//:geometry/shelves/shelves.obj",
"@drake_models//:geometry/shelves/shelves.png",
],
)

filegroup(
name = "test_obj_files",
testonly = 1,
Expand Down
1 change: 1 addition & 0 deletions geometry/benchmarking/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ drake_cc_googlebench_binary(
add_test_rule = True,
data = [
"//examples/manipulation_station:models",
"//geometry:models",
"//manipulation/models/iiwa_description:models",
"//manipulation/models/wsg_50_description:models",
],
Expand Down
30 changes: 5 additions & 25 deletions geometry/benchmarking/iris_in_configuration_space_benchmarks.cc
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ class IiwaWithShelvesAndBins : public benchmark::Fixture {
# Add Bins
- add_model:
name: binR
file: package://drake/examples/manipulation_station/models/bin.sdf
file: package://drake/geometry/models/bin/bin.sdf
- add_weld:
parent: world
Expand All @@ -114,37 +114,18 @@ class IiwaWithShelvesAndBins : public benchmark::Fixture {
- add_model:
name: binL
file: package://drake/examples/manipulation_station/models/bin.sdf
file: package://drake/geometry/models/bin/bin.sdf
- add_weld:
parent: world
child: binL::bin_base
X_PC:
translation: [0, 0.6, 0]
rotation: !Rpy { deg: [0.0, 0.0, 90.0 ]}
)""";

parser.AddModelsFromString(model_directives, ".dmd.yaml");

// Don't add remote resources if we're in test mode.
if (!FLAGS_test) {
// We'll use some tables, shelves, and bins from a remote resource.
multibody::PackageMap::RemoteParams params;
params.urls.push_back(
"https://github.com/mpetersen94/gcs/archive/refs/tags/"
"arxiv_paper_version.tar.gz");
params.sha256 =
"6dd5e841c8228561b6d622f592359c36517cd3c3d5e1d3e04df74b2f5435680c";
params.strip_prefix = "gcs-arxiv_paper_version";
parser.package_map().AddRemote("gcs", params);

model_directives = R"""(
directives:
# Add shelves
- add_model:
name: shelves
file: package://gcs/models/shelves/shelves.sdf
file: package://drake/geometry/models/shelves/shelves.sdf
- add_weld:
parent: world
Expand All @@ -155,7 +136,7 @@ class IiwaWithShelvesAndBins : public benchmark::Fixture {
# Add table
- add_model:
name: table
file: package://gcs/models/table/table_wide.sdf
file: package://drake/geometry/models/table/table_wide.sdf
- add_weld:
parent: world
Expand All @@ -165,8 +146,7 @@ class IiwaWithShelvesAndBins : public benchmark::Fixture {
rotation: !Rpy { deg: [0., 0., 00]}
)""";

parser.AddModelsFromString(model_directives, ".dmd.yaml");
}
parser.AddModelsFromString(model_directives, ".dmd.yaml");
}

VectorXd MyInverseKinematics(const RigidTransformd& X_WE) {
Expand Down
1 change: 1 addition & 0 deletions geometry/models/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
This directory contains models that are used by geometry benchmarks.
1 change: 1 addition & 0 deletions geometry/models/bin/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
This model was copied from https://github.com/mpetersen94/gcs.
86 changes: 86 additions & 0 deletions geometry/models/bin/bin.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
<?xml version="1.0"?>
<sdf version="1.7">
<model name="bin_model">
<!--
Axes:
+X - Pointing towards front (slope)
+Y - Pointing to left side
+Z - Up
Origin:
(0, 0, 0) at the center bottom of the bin
-->
<link name="bin_base">
<inertial>
<mass>18.70</mass>
<inertia>
<ixx>0.79</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.53</iyy>
<iyz>0</iyz>
<izz>1.2</izz>
</inertia>
</inertial>
<visual name="visual">
<pose>0 0 0 0 0 1.570796</pose>
<geometry>
<mesh>
<uri>package://drake_models/geometry/bin/bin.obj</uri>
</mesh>
</geometry>
</visual>
<collision name="front">
<pose>0.22 0 0.105 0 0 0</pose>
<geometry>
<box>
<size>0.05 0.63 0.21</size>
</box>
</geometry>
</collision>
<!--
<collision name="slope">
<pose>0.182 0 0.102 0 0.35 0</pose>
<geometry>
<box>
<size>0.05 0.63 0.21</size>
</box>
</geometry>
</collision>-->
<collision name="back">
<pose>-0.22 0 0.105 0 0 0</pose>
<geometry>
<box>
<size>0.05 0.63 0.21</size>
</box>
</geometry>
</collision>
<collision name="left">
<pose>0 0.29 0.105 0 0 0</pose>
<geometry>
<box>
<size>0.49 0.05 0.21</size>
</box>
</geometry>
</collision>
<collision name="right">
<pose>0 -0.29 0.105 0 0 0</pose>
<geometry>
<box>
<size>0.49 0.05 0.21</size>
</box>
</geometry>
</collision>
<collision name="bottom">
<pose>0.0 0.0 0.0075 0 0 0</pose>
<geometry>
<box>
<size>0.49 0.63 0.015</size>
</box>
</geometry>
</collision>
</link>
<frame name="bin_front_top_center">
<pose relative_to="bin_base">0.22 0 0.21 0 0 0</pose>
</frame>
</model>
</sdf>
1 change: 1 addition & 0 deletions geometry/models/shelves/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
This model was copied from https://github.com/mpetersen94/gcs.
61 changes: 61 additions & 0 deletions geometry/models/shelves/shelves.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
<?xml version="1.0"?>
<sdf version="1.7">
<model name="shelves">
<link name="shelves_body">
<visual name="shelves_visual">
<geometry>
<mesh>
<uri>package://drake_models/geometry/shelves/shelves.obj</uri>
</mesh>
</geometry>
</visual>
<collision name="right_wall">
<pose> 0 0.292 0 0 0 0</pose>
<geometry>
<box>
<size>0.3 0.016 0.783</size>
</box>
</geometry>
</collision>
<collision name="left_wall">
<pose> 0 -0.292 0 0 0 0</pose>
<geometry>
<box>
<size>0.3 0.016 0.783</size>
</box>
</geometry>
</collision>
</link>
<link name="top_and_bottom">
<collision name="top">
<pose> 0 0 0.3995 0 0 0</pose>
<geometry>
<box>
<size>0.3 0.6 0.016</size>
</box>
</geometry>
</collision>
<collision name="shelf_lower">
<pose> 0 0 -0.13115 0 0 0</pose>
<geometry>
<box>
<size>0.3 0.6 0.016</size>
</box>
</geometry>
</collision>
<collision name="shelf_upper">
<pose> 0 0 0.13115 0 0 0</pose>
<geometry>
<box>
<size>0.3 0.6 0.016</size>
</box>
</geometry>
</collision>
</link>
<!-- joint between bottom_top and world -->
<joint name="top_and_bottom_shelves_body" type="fixed">
<child>top_and_bottom</child>
<parent>shelves_body</parent>
</joint>
</model>
</sdf>
1 change: 1 addition & 0 deletions geometry/models/table/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
This model was copied from https://github.com/mpetersen94/gcs.
22 changes: 22 additions & 0 deletions geometry/models/table/table_wide.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<?xml version="1.0"?>
<sdf version="1.7">
<model name="table">
<link name="table_body">
<visual name="table_visual">
<geometry>
<mesh>
<uri>package://drake_models/geometry/table/table_wide.obj</uri>
</mesh>
</geometry>
</visual>
<collision name="table_top">
<pose> 0 0 -0.1 0 0 0</pose>
<geometry>
<box>
<size>2.5 2.5 0.2</size>
</box>
</geometry>
</collision>
</link>
</model>
</sdf>
2 changes: 1 addition & 1 deletion multibody/parsing/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ drake_cc_library(
srcs = ["package_map.cc"],
hdrs = ["package_map.h"],
data = [
":drake_models.json",
# ":drake_models.json",
":package_downloader.py",
"//:package.xml",
"@drake_models//:package.xml",
Expand Down
5 changes: 3 additions & 2 deletions multibody/parsing/package_map.cc
Original file line number Diff line number Diff line change
Expand Up @@ -532,8 +532,9 @@ PackageMap::PackageMap() : PackageMap{std::nullopt} {
// Prepare the params for fetching remote drake_models. We do this outside of
// the if-else to ensure it receives test coverage under bazel (i.e., even if
// we're never going to download anything).
static const never_destroyed<RemoteParams> memoized_params(
GetDrakeModelsRemoteParams());
static const never_destroyed<RemoteParams> memoized_params;
unused(GetDrakeModelsRemoteParams);
// GetDrakeModelsRemoteParams());

// For drake_models (i.e., https://github.com/RobotLocomotion/models), the
// location where we find the data will vary. If we have Bazel runfiles with
Expand Down
1 change: 1 addition & 0 deletions tools/workspace/drake_models/repository.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ def drake_models_repository(
mirrors = None):
github_archive(
name = name,
local_repository_override = "/Users/russt/tmp/models",
repository = "RobotLocomotion/models",
commit = "611246c443152946e9dcc901b4f956d89a439a61",
sha256 = "66ad3b0f85b2aaa823d2e69cdaa980af9c0414cdb829b8224fbaa8a2dc083a7c", # noqa
Expand Down

0 comments on commit 1f84c13

Please sign in to comment.