Skip to content

Commit

Permalink
[workspace] Upgrade drake_models to latest commit
Browse files Browse the repository at this point in the history
Document that manipulation/models is being removed, remove all of its
from the install rules.

Port installed software to the new paths:
- examples/manipulation_station
- tutorials
  • Loading branch information
jwnimmer-tri committed Mar 29, 2024
1 parent 2b325f9 commit 6c6e29e
Show file tree
Hide file tree
Showing 29 changed files with 55 additions and 785 deletions.
1 change: 0 additions & 1 deletion BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,6 @@ install(
"//examples:install",
"//geometry:install",
"//lcmtypes:install",
"//manipulation/models:install_data",
"//multibody/parsing:install",
"//setup:install",
"//tools/install/libdrake:install",
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/visualization/model_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
An example of viewing an iiwa model file::
python3 -m pydrake.visualization.model_visualizer --open-window \
package://drake/manipulation/models/iiwa_description/iiwa7/iiwa7_with_box_collision.sdf
package://drake_models/iiwa_description/sdf/iiwa7_with_box_collision.sdf
This program respects the ``ROS_PACKAGE_PATH``; if your model uses external
resources then you will need to set that environment variable.
Expand Down
8 changes: 5 additions & 3 deletions examples/manipulation_station/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -54,9 +54,12 @@ drake_cc_library(
data = [
":models",
"//examples/kuka_iiwa_arm:models",
"@drake_models",
# TODO(jwnimmer-tri) These are not actually used by this library
# anymore, but removing them breaks too many other things. We'll
# revisit this later when we finally delete these paths entirely.
"//manipulation/models/iiwa_description:models",
"//manipulation/models/wsg_50_description:models",
"@drake_models",
],
visibility = ["//visibility:public"],
deps = [
Expand Down Expand Up @@ -85,8 +88,7 @@ drake_cc_library(
"manipulation_station_hardware_interface.h",
],
data = [
"//manipulation/models/iiwa_description:models",
"//manipulation/models/wsg_50_description:models",
"@drake_models",
],
visibility = ["//visibility:public"],
deps = [
Expand Down
42 changes: 20 additions & 22 deletions examples/manipulation_station/manipulation_station.cc
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ using multibody::ExternallyAppliedSpatialForce;
using multibody::Joint;
using multibody::MultibodyForces;
using multibody::MultibodyPlant;
using multibody::PackageMap;
using multibody::PrismaticJoint;
using multibody::RevoluteJoint;
using multibody::RigidBody;
Expand Down Expand Up @@ -455,15 +456,14 @@ void ManipulationStation<T>::SetupPlanarIiwaStation(

// Add planar iiwa model.
{
std::string sdf_path =
"drake/manipulation/models/iiwa_description/urdf/"
const std::string sdf_url =
"package://drake_models/iiwa_description/urdf/"
"planar_iiwa14_spheres_dense_elbow_collision.urdf";
std::string sdf_url = "package://" + sdf_path;
const auto X_WI = RigidTransform<double>::Identity();
auto iiwa_instance = internal::AddAndWeldModelFrom(
sdf_url, "iiwa", plant_->world_frame(), "iiwa_link_0", X_WI, plant_);
RegisterIiwaControllerModel(
FindResourceOrThrow(sdf_path), iiwa_instance, plant_->world_frame(),
PackageMap{}.ResolveUrl(sdf_url), iiwa_instance, plant_->world_frame(),
plant_->GetFrameByName("iiwa_link_0", iiwa_instance), X_WI);
}

Expand Down Expand Up @@ -1115,55 +1115,53 @@ ManipulationStation<T>::GetStaticCameraPosesInWorld() const {
template <typename T>
void ManipulationStation<T>::AddDefaultIiwa(
const IiwaCollisionModel collision_model) {
std::string sdf_path;
std::string sdf_url;
switch (collision_model) {
case IiwaCollisionModel::kNoCollision:
sdf_path =
"drake/manipulation/models/iiwa_description/iiwa7/"
sdf_url =
"package://drake_models/iiwa_description/sdf/"
"iiwa7_no_collision.sdf";
break;
case IiwaCollisionModel::kBoxCollision:
sdf_path =
"drake/manipulation/models/iiwa_description/iiwa7/"
sdf_url =
"package://drake_models/iiwa_description/sdf/"
"iiwa7_with_box_collision.sdf";
break;
}
std::string sdf_url = "package://" + sdf_path;
const auto X_WI = RigidTransform<double>::Identity();
auto iiwa_instance = internal::AddAndWeldModelFrom(
sdf_url, "iiwa", plant_->world_frame(), "iiwa_link_0", X_WI, plant_);
RegisterIiwaControllerModel(
FindResourceOrThrow(sdf_path), iiwa_instance, plant_->world_frame(),
PackageMap{}.ResolveUrl(sdf_url), iiwa_instance, plant_->world_frame(),
plant_->GetFrameByName("iiwa_link_0", iiwa_instance), X_WI);
}

// Add default wsg.
template <typename T>
void ManipulationStation<T>::AddDefaultWsg(
const SchunkCollisionModel schunk_model) {
std::string sdf_path;
std::string sdf_url;
switch (schunk_model) {
case SchunkCollisionModel::kBox:
sdf_path =
"drake/manipulation/models/wsg_50_description/sdf"
"/schunk_wsg_50_no_tip.sdf";
sdf_url =
"package://drake_models/wsg_50_description/sdf/"
"schunk_wsg_50_no_tip.sdf";
break;
case SchunkCollisionModel::kBoxPlusFingertipSpheres:
sdf_path =
"drake/manipulation/models/wsg_50_description/sdf"
"/schunk_wsg_50_with_tip.sdf";
sdf_url =
"package://drake_models/wsg_50_description/sdf/"
"schunk_wsg_50_with_tip.sdf";
break;
}
std::string sdf_url = "package://" + sdf_path;
const multibody::Frame<T>& link7 =
plant_->GetFrameByName("iiwa_link_7", iiwa_model_.model_instance);
const RigidTransform<double> X_7G(RollPitchYaw<double>(M_PI_2, 0, M_PI_2),
Vector3d(0, 0, 0.114));
auto wsg_instance = internal::AddAndWeldModelFrom(sdf_url, "gripper", link7,
"body", X_7G, plant_);
RegisterWsgControllerModel(FindResourceOrThrow(sdf_path), wsg_instance, link7,
plant_->GetFrameByName("body", wsg_instance),
X_7G);
RegisterWsgControllerModel(
PackageMap{}.ResolveUrl(sdf_url), wsg_instance, link7,
plant_->GetFrameByName("body", wsg_instance), X_7G);
}

} // namespace manipulation_station
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -129,8 +129,7 @@ ManipulationStationHardwareInterface::ManipulationStationHardwareInterface(
// Build the controller's version of the plant, which only contains the
// IIWA and the equivalent inertia of the gripper.
const std::string iiwa_sdf_url =
"package://drake/manipulation/models/iiwa_description/sdf/"
"iiwa14_no_collision.sdf";
"package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf";
Parser parser(owned_controller_plant_.get());
iiwa_model_instance_ = parser.AddModelsFromUrl(iiwa_sdf_url).at(0);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,7 @@ multibody::SpatialInertia<double> MakeCompositeGripperInertia() {
multibody::MultibodyPlant<double> plant(1.0);
multibody::Parser parser(&plant);
parser.AddModelsFromUrl(
"package://drake/manipulation/models/wsg_50_description/sdf/"
"schunk_wsg_50_no_tip.sdf");
"package://drake_models/wsg_50_description/sdf/schunk_wsg_50_no_tip.sdf");
plant.Finalize();
const std::string gripper_body_frame_name = "body";
const auto& frame = plant.GetFrameByName(gripper_body_frame_name);
Expand Down
13 changes: 0 additions & 13 deletions manipulation/models/BUILD.bazel
Original file line number Diff line number Diff line change
@@ -1,16 +1,3 @@
load("//tools/install:install.bzl", "install")
load("//tools/lint:lint.bzl", "add_lint_tests")

install(
name = "install_data",
visibility = ["//visibility:public"],
deps = [
"//manipulation/models/franka_description:install_data",
"//manipulation/models/iiwa_description:install_data",
"//manipulation/models/jaco_description:install_data",
"//manipulation/models/ur3e:install_data",
"//manipulation/models/wsg_50_description:install_data",
],
)

add_lint_tests()
11 changes: 11 additions & 0 deletions manipulation/models/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@

# Drake Users

All files in drake/manipulation/models are in the process of being moved to the
https://github.com/RobotLocomotion/models/ repository, instead. Do not use any
of these (package://drake) models in new code. Instead, use the models from
their new home (package://drake_models).

# Drake Developers

Do not many any further changes to these model files.
24 changes: 0 additions & 24 deletions manipulation/models/franka_description/BUILD.bazel
Original file line number Diff line number Diff line change
@@ -1,9 +1,4 @@
load(
"//tools/skylark:drake_cc.bzl",
"drake_cc_googletest",
)
load("//tools/skylark:drake_data.bzl", "models_filegroup")
load("//tools/install:install_data.bzl", "install_data")
load("//tools/lint:lint.bzl", "add_lint_tests")

package(default_visibility = ["//visibility:public"])
Expand All @@ -17,11 +12,6 @@ models_filegroup(
visibility = ["//visibility:private"],
)

install_data(
name = "install_data",
data = [":glob_models"],
)

filegroup(
name = "models",
srcs = [
Expand Down Expand Up @@ -49,18 +39,4 @@ filegroup(
],
)

# === test/ ===

drake_cc_googletest(
name = "franka_arm_test",
srcs = ["urdf/test/franka_arm_test.cc"],
data = [":models"],
deps = [
"//common:find_resource",
"//common/test_utilities:eigen_matrix_compare",
"//multibody/parsing",
"//multibody/plant",
],
)

add_lint_tests()
1 change: 1 addition & 0 deletions manipulation/models/franka_description/VESTIGIAL.md
117 changes: 0 additions & 117 deletions manipulation/models/franka_description/urdf/test/franka_arm_test.cc

This file was deleted.

23 changes: 0 additions & 23 deletions manipulation/models/iiwa_description/BUILD.bazel
Original file line number Diff line number Diff line change
@@ -1,9 +1,4 @@
load(
"//tools/skylark:drake_cc.bzl",
"drake_cc_googletest",
)
load("//tools/skylark:drake_data.bzl", "models_filegroup")
load("//tools/install:install_data.bzl", "install_data")
load("//tools/lint:lint.bzl", "add_lint_tests")

package(default_visibility = ["//visibility:public"])
Expand All @@ -17,11 +12,6 @@ models_filegroup(
visibility = ["//visibility:private"],
)

install_data(
name = "install_data",
data = [":glob_models"],
)

filegroup(
name = "models",
srcs = [
Expand Down Expand Up @@ -80,17 +70,4 @@ filegroup(
],
)

# === test/ ===

drake_cc_googletest(
name = "iiwa_variants_parsing_test",
srcs = ["test/iiwa_variants_parsing_test.cc"],
data = [":models"],
deps = [
"//common:find_resource",
"//common/test_utilities:eigen_matrix_compare",
"//multibody/parsing",
],
)

add_lint_tests()
1 change: 1 addition & 0 deletions manipulation/models/iiwa_description/VESTIGIAL.md
Loading

0 comments on commit 6c6e29e

Please sign in to comment.