diff --git a/BUILD.bazel b/BUILD.bazel index eabd7ed288d0..520873ff0845 100644 --- a/BUILD.bazel +++ b/BUILD.bazel @@ -53,11 +53,6 @@ filegroup( "//examples/quadrotor:models", "//examples/scene_graph:models", "//examples/simple_gripper:simple_gripper_models", - "//manipulation/models/franka_description:models", - "//manipulation/models/iiwa_description:models", - "//manipulation/models/jaco_description:models", - "//manipulation/models/ur3e:models", - "//manipulation/models/wsg_50_description:models", "//multibody/benchmarks/acrobot:models", "@drake_models", ], diff --git a/bindings/pydrake/examples/test/manipulation_station_test.py b/bindings/pydrake/examples/test/manipulation_station_test.py index 343cf0b4b493..d6dbc6f245c8 100644 --- a/bindings/pydrake/examples/test/manipulation_station_test.py +++ b/bindings/pydrake/examples/test/manipulation_station_test.py @@ -2,7 +2,6 @@ import numpy as np -from pydrake.common import FindResourceOrThrow from pydrake.examples import ( CreateClutterClearingYcbObjectList, CreateManipulationClassYcbObjectList, @@ -20,7 +19,10 @@ from pydrake.math import RigidTransform, RollPitchYaw from pydrake.multibody.plant import MultibodyPlant from pydrake.multibody.tree import ModelInstanceIndex -from pydrake.multibody.parsing import Parser +from pydrake.multibody.parsing import ( + PackageMap, + Parser, +) from pydrake.systems.sensors import CameraInfo @@ -66,8 +68,8 @@ def test_manipulation_station_add_iiwa_and_wsg_explicitly(self): plant = station.get_mutable_multibody_plant() # Add models for iiwa and wsg - iiwa_model_file = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/iiwa7/" + iiwa_model_file = PackageMap().ResolveUrl( + "package://drake_models/iiwa_description/sdf/" "iiwa7_no_collision.sdf") (iiwa,) = parser.AddModels(iiwa_model_file) X_WI = RigidTransform.Identity() @@ -75,8 +77,8 @@ def test_manipulation_station_add_iiwa_and_wsg_explicitly(self): plant.GetFrameByName("iiwa_link_0", iiwa), X_WI) - wsg_model_file = FindResourceOrThrow( - "drake/manipulation/models/wsg_50_description/sdf/" + wsg_model_file = PackageMap().ResolveUrl( + "package://drake_models/wsg_50_description/sdf/" "schunk_wsg_50.sdf") (wsg,) = parser.AddModels(wsg_model_file) X_7G = RigidTransform.Identity() diff --git a/bindings/pydrake/manipulation/BUILD.bazel b/bindings/pydrake/manipulation/BUILD.bazel index 68c2bba3dbd9..1734c02ea2b2 100644 --- a/bindings/pydrake/manipulation/BUILD.bazel +++ b/bindings/pydrake/manipulation/BUILD.bazel @@ -47,8 +47,8 @@ drake_pybind_library( drake_py_unittest( name = "kuka_iiwa_test", data = [ - "//manipulation/models/iiwa_description:models", "//manipulation/util:test_directives", + "@drake_models//:iiwa_description", ], deps = [ ":manipulation", diff --git a/bindings/pydrake/manipulation/test/kuka_iiwa_test.py b/bindings/pydrake/manipulation/test/kuka_iiwa_test.py index fccd9c0b0b9a..f83e3101e37c 100644 --- a/bindings/pydrake/manipulation/test/kuka_iiwa_test.py +++ b/bindings/pydrake/manipulation/test/kuka_iiwa_test.py @@ -33,9 +33,9 @@ def make_builder_plant_controller_plant(self): plant.Finalize() controller_plant = MultibodyPlant(1.) parser = Parser(controller_plant) - parser.AddModels(FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/iiwa7/" - "iiwa7_no_collision.sdf")) + parser.AddModels(url=( + "package://drake_models/iiwa_description/sdf/" + + "iiwa7_no_collision.sdf")) controller_plant.WeldFrames( controller_plant.world_frame(), controller_plant.GetFrameByName("iiwa_link_0"), RigidTransform()) diff --git a/bindings/pydrake/multibody/BUILD.bazel b/bindings/pydrake/multibody/BUILD.bazel index 28ae95cad627..0f71a78492b5 100644 --- a/bindings/pydrake/multibody/BUILD.bazel +++ b/bindings/pydrake/multibody/BUILD.bazel @@ -379,7 +379,7 @@ drake_jupyter_py_binary( name = "examples/jupyter_widgets_examples", add_test_rule = 1, data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":jupyter_widgets_py", @@ -427,11 +427,11 @@ drake_py_unittest( data = [ ":models", "//examples/acrobot:models", - "//manipulation/models/iiwa_description:models", - "//manipulation/models/wsg_50_description:models", "//multibody:models", "//multibody/benchmarks/acrobot:models", "//multibody/benchmarks/free_body:models", + "@drake_models//:iiwa_description", + "@drake_models//:wsg_50_description", ], deps = [ ":benchmarks_py", diff --git a/bindings/pydrake/multibody/examples/jupyter_widgets_examples.ipynb b/bindings/pydrake/multibody/examples/jupyter_widgets_examples.ipynb index 299cc5112fae..3d4bac69afe3 100644 --- a/bindings/pydrake/multibody/examples/jupyter_widgets_examples.ipynb +++ b/bindings/pydrake/multibody/examples/jupyter_widgets_examples.ipynb @@ -47,7 +47,7 @@ "plant = MultibodyPlant(time_step=0.0)\n", "plant.RegisterAsSourceForSceneGraph(scene_graph)\n", "Parser(plant, scene_graph).AddModelsFromUrl(\n", - " url=\"package://drake/manipulation/models/iiwa_description/iiwa7/iiwa7_no_collision.sdf\")\n", + " url=\"package://drake_models/iiwa_description/sdf/iiwa7_no_collision.sdf\")\n", "plant.Finalize()\n", "\n", "# Add sliders to set positions of the joints.\n", @@ -101,7 +101,7 @@ "builder = DiagramBuilder()\n", "plant, scene_graph = AddMultibodyPlantSceneGraph(builder, time_step=0.0)\n", "Parser(plant).AddModelsFromUrl(\n", - " url=\"package://drake/manipulation/models/iiwa_description/iiwa7/iiwa7_no_collision.sdf\")\n", + " url=\"package://drake_models/iiwa_description/sdf/iiwa7_no_collision.sdf\")\n", "plant.Finalize()\n", "\n", "viz = DrakeVisualizer.AddToBuilder(builder, scene_graph)\n", diff --git a/bindings/pydrake/multibody/test/optimization_test.py b/bindings/pydrake/multibody/test/optimization_test.py index bd49eb5c0352..342f2399ed51 100644 --- a/bindings/pydrake/multibody/test/optimization_test.py +++ b/bindings/pydrake/multibody/test/optimization_test.py @@ -297,10 +297,10 @@ def test_gridpoints(self): def test_all_constraints(self): plant = MultibodyPlant(0) - file_path = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/iiwa7/" - "iiwa7_no_collision.sdf") - iiwa_id, = Parser(plant).AddModels(file_path) + url = ( + "package://drake_models/iiwa_description/sdf/" + + "iiwa7_no_collision.sdf") + iiwa_id, = Parser(plant).AddModels(url=url) plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("iiwa_link_0", iiwa_id)) plant.Finalize() diff --git a/bindings/pydrake/multibody/test/plant_test.py b/bindings/pydrake/multibody/test/plant_test.py index 285228fc2da8..c484dfef05f2 100644 --- a/bindings/pydrake/multibody/test/plant_test.py +++ b/bindings/pydrake/multibody/test/plant_test.py @@ -1398,18 +1398,18 @@ def test_port_access(self, T): # Create a MultibodyPlant with a kuka arm and a schunk gripper. # the arm is welded to the world, the gripper is welded to the # arm's end effector. - wsg50_sdf_path = FindResourceOrThrow( - "drake/manipulation/models/" + wsg50_sdf_url = ( + "package://drake_models/" "wsg_50_description/sdf/schunk_wsg_50.sdf") - iiwa_sdf_path = FindResourceOrThrow( - "drake/manipulation/models/" + iiwa_sdf_url = ( + "package://drake_models/" "iiwa_description/sdf/iiwa14_no_collision.sdf") # N.B. `Parser` only supports `MultibodyPlant_[float]`. plant_f = MultibodyPlant_[float](time_step=2e-3) parser = Parser(plant_f) - iiwa_model, = parser.AddModels(file_name=iiwa_sdf_path) - gripper_model, = parser.AddModels(file_name=wsg50_sdf_path) + iiwa_model, = parser.AddModels(url=iiwa_sdf_url) + gripper_model, = parser.AddModels(url=wsg50_sdf_url) plant_f.Finalize() plant = to_type(plant_f, T) models = [iiwa_model, gripper_model] @@ -1558,19 +1558,19 @@ def test_model_instance_state_access(self, T): RigidTransform = RigidTransform_[T] RollPitchYaw = RollPitchYaw_[T] - wsg50_sdf_path = FindResourceOrThrow( - "drake/manipulation/models/" - "wsg_50_description/sdf/schunk_wsg_50.sdf") - iiwa_sdf_path = FindResourceOrThrow( - "drake/manipulation/models/" - "iiwa_description/sdf/iiwa14_no_collision.sdf") + wsg50_sdf_url = ( + "package://drake_models/wsg_50_description/sdf/" + + "schunk_wsg_50.sdf") + iiwa_sdf_url = ( + "package://drake_models/iiwa_description/sdf/" + + "iiwa14_no_collision.sdf") # N.B. `Parser` only supports `MultibodyPlant_[float]`. plant_f = MultibodyPlant_[float](0.0) parser = Parser(plant_f) - iiwa_model, = parser.AddModels(file_name=iiwa_sdf_path) - gripper_model, = parser.AddModels(file_name=wsg50_sdf_path) + iiwa_model, = parser.AddModels(url=iiwa_sdf_url) + gripper_model, = parser.AddModels(url=wsg50_sdf_url) # Weld the base of arm and gripper to reduce the number of states. X_EeGripper = RigidTransform_[float]( @@ -1704,11 +1704,11 @@ def test_model_instance_state_access_by_array(self, T): # Create a MultibodyPlant with a kuka arm and a schunk gripper. # the arm is welded to the world, the gripper is welded to the # arm's end effector. - wsg50_sdf_path = FindResourceOrThrow( - "drake/manipulation/models/" + wsg50_sdf_url = ( + "package://drake_models/" "wsg_50_description/sdf/schunk_wsg_50.sdf") - iiwa_sdf_path = FindResourceOrThrow( - "drake/manipulation/models/" + iiwa_sdf_url = ( + "package://drake_models/" "iiwa_description/sdf/iiwa14_no_collision.sdf") time_step = 0.0002 @@ -1716,8 +1716,8 @@ def test_model_instance_state_access_by_array(self, T): plant_f = MultibodyPlant_[float](time_step) parser = Parser(plant_f) - iiwa_model, = parser.AddModels(file_name=iiwa_sdf_path) - gripper_model, = parser.AddModels(file_name=wsg50_sdf_path) + iiwa_model, = parser.AddModels(url=iiwa_sdf_url) + gripper_model, = parser.AddModels(url=wsg50_sdf_url) # Weld the base of arm and gripper to reduce the number of states. X_EeGripper = RigidTransform_[float]( @@ -1813,12 +1813,12 @@ def test_map_qdot_to_v_and_back(self, T): RollPitchYaw = RollPitchYaw_[T] # N.B. `Parser` only supports `MultibodyPlant_[float]`. plant_f = MultibodyPlant_[float](0.0) - iiwa_sdf_path = FindResourceOrThrow( - "drake/manipulation/models/" - "iiwa_description/sdf/iiwa14_no_collision.sdf") + iiwa_sdf_url = ( + "package://drake_models/iiwa_description/sdf/" + + "iiwa14_no_collision.sdf") # Use floating base to effectively add a quaternion in the generalized # quaternion. - iiwa_model, = Parser(plant_f).AddModels(iiwa_sdf_path) + iiwa_model, = Parser(plant_f).AddModels(url=iiwa_sdf_url) plant_f.Finalize() plant = to_type(plant_f, T) context = plant.CreateDefaultContext() @@ -2325,13 +2325,13 @@ def loop_body(make_joint, time_step): loop_body(make_joint, 0.001) def test_actuation_matrix(self): - iiwa_sdf_path = FindResourceOrThrow( - "drake/manipulation/models/" - "iiwa_description/sdf/iiwa14_no_collision.sdf") + iiwa_sdf_url = ( + "package://drake_models/iiwa_description/sdf/" + + "iiwa14_no_collision.sdf") plant = MultibodyPlant_[float](0.0) parser = Parser(plant) - iiwa_model, = parser.AddModels(file_name=iiwa_sdf_path) + iiwa_model, = parser.AddModels(url=iiwa_sdf_url) plant.WeldFrames( frame_on_parent_F=plant.world_frame(), frame_on_child_M=plant.GetFrameByName("iiwa_link_0", iiwa_model)) @@ -2481,7 +2481,7 @@ def test_coupler_constraint_api(self): plant.set_discrete_contact_approximation( DiscreteContactApproximation.kSap) Parser(plant).AddModelsFromUrl( - "package://drake/manipulation/models/" + "package://drake_models/" "wsg_50_description/sdf/schunk_wsg_50.sdf") # Add coupler constraint. @@ -2558,7 +2558,7 @@ def test_constraint_active_status_api(self): body_A=body_A, X_AP=X_AP, body_B=body_B, X_BQ=X_BQ) Parser(plant).AddModelsFromUrl( - "package://drake/manipulation/models/" + "package://drake_models/" "wsg_50_description/sdf/schunk_wsg_50.sdf") # Add coupler constraint. diff --git a/bindings/pydrake/planning/BUILD.bazel b/bindings/pydrake/planning/BUILD.bazel index b552188348e1..e240ba78ca82 100644 --- a/bindings/pydrake/planning/BUILD.bazel +++ b/bindings/pydrake/planning/BUILD.bazel @@ -90,7 +90,7 @@ drake_py_unittest( drake_py_unittest( name = "robot_diagram_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":planning", diff --git a/bindings/pydrake/planning/test/robot_diagram_test.py b/bindings/pydrake/planning/test/robot_diagram_test.py index 535967c5497d..1016a607e1b3 100644 --- a/bindings/pydrake/planning/test/robot_diagram_test.py +++ b/bindings/pydrake/planning/test/robot_diagram_test.py @@ -18,9 +18,9 @@ def test_robot_diagram_builder(self, T): Class = mut.RobotDiagramBuilder_[T] dut = Class(time_step=0.0) if T == float: - dut.parser().AddModels(FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/urdf/" - "iiwa14_spheres_dense_collision.urdf")) + dut.parser().AddModels(url=( + "package://drake_models/iiwa_description/urdf/" + + "iiwa14_spheres_dense_collision.urdf")) else: # TODO(jwnimmer-tri) Use dut.plant() to manually add some # models, bodies, and geometries here. diff --git a/bindings/pydrake/systems/BUILD.bazel b/bindings/pydrake/systems/BUILD.bazel index 71b7171b07dc..960c1812c430 100644 --- a/bindings/pydrake/systems/BUILD.bazel +++ b/bindings/pydrake/systems/BUILD.bazel @@ -436,7 +436,7 @@ drake_py_unittest( drake_py_unittest( name = "controllers_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":controllers_py", @@ -473,7 +473,7 @@ drake_py_unittest( name = "planar_scenegraph_visualizer_test", data = [ "//examples/multibody/cart_pole:models", - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":analysis_py", diff --git a/bindings/pydrake/systems/test/controllers_test.py b/bindings/pydrake/systems/test/controllers_test.py index 6e61ed814daf..ebcdf4a4f4f7 100644 --- a/bindings/pydrake/systems/test/controllers_test.py +++ b/bindings/pydrake/systems/test/controllers_test.py @@ -108,12 +108,12 @@ def cost_to_go_function(state, parameters): self.assertAlmostEqual(J[0], 1., delta=1e-6) def test_joint_stiffness_controller(self): - sdf_path = FindResourceOrThrow( - "drake/manipulation/models/" - "iiwa_description/sdf/iiwa14_no_collision.sdf") + url = ( + "package://drake_models/iiwa_description/sdf/" + + "iiwa14_no_collision.sdf") plant = MultibodyPlant(time_step=0.01) - Parser(plant).AddModels(sdf_path) + Parser(plant).AddModels(url=url) plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("iiwa_link_0")) plant.Finalize() @@ -130,12 +130,12 @@ def test_joint_stiffness_controller(self): self.assertIsInstance(controller.get_multibody_plant(), MultibodyPlant) def test_inverse_dynamics(self): - sdf_path = FindResourceOrThrow( - "drake/manipulation/models/" - "iiwa_description/sdf/iiwa14_no_collision.sdf") + url = ( + "package://drake_models/iiwa_description/sdf/" + + "iiwa14_no_collision.sdf") plant = MultibodyPlant(time_step=0.01) - Parser(plant).AddModels(sdf_path) + Parser(plant).AddModels(url=url) plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("iiwa_link_0")) plant.Finalize() @@ -159,12 +159,12 @@ def test_inverse_dynamics(self): self.assertTrue(controller.is_pure_gravity_compensation()) def test_inverse_dynamics_controller(self): - sdf_path = FindResourceOrThrow( - "drake/manipulation/models/" - "iiwa_description/sdf/iiwa14_no_collision.sdf") + url = ( + "package://drake_models/iiwa_description/sdf/" + + "iiwa14_no_collision.sdf") plant = MultibodyPlant(time_step=0.01) - Parser(plant).AddModels(sdf_path) + Parser(plant).AddModels(url=url) plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("iiwa_link_0")) plant.mutable_gravity_field().set_gravity_vector([0.0, 0.0, 0.0]) diff --git a/bindings/pydrake/systems/test/planar_scenegraph_visualizer_test.py b/bindings/pydrake/systems/test/planar_scenegraph_visualizer_test.py index 59f06fedf35f..ca8302ff92e4 100644 --- a/bindings/pydrake/systems/test/planar_scenegraph_visualizer_test.py +++ b/bindings/pydrake/systems/test/planar_scenegraph_visualizer_test.py @@ -55,12 +55,12 @@ def test_cart_pole(self): def test_kuka(self): """Kuka IIWA with mesh geometry.""" - file_name = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf") + url = ( + "package://drake_models/iiwa_description/sdf/" + + "iiwa14_no_collision.sdf") builder = DiagramBuilder() kuka, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) - Parser(plant=kuka).AddModels(file_name) + Parser(plant=kuka).AddModels(url=url) kuka.Finalize() # Make sure that the frames to visualize exist. diff --git a/bindings/pydrake/visualization/test/meldis_test.py b/bindings/pydrake/visualization/test/meldis_test.py index 1061726aff78..551c90cd1ce0 100644 --- a/bindings/pydrake/visualization/test/meldis_test.py +++ b/bindings/pydrake/visualization/test/meldis_test.py @@ -191,7 +191,7 @@ def test_viewer_applet_plain_meshes(self): """Checks _ViewerApplet support for untextured meshes. """ self._check_viewer_applet_on_model( - "drake/manipulation/models/iiwa_description/urdf/" + "drake_models/iiwa_description/urdf/" "iiwa14_no_collision.urdf") def test_viewer_applet_textured_meshes(self): diff --git a/bindings/pydrake/visualization/test/model_visualizer_test.py b/bindings/pydrake/visualization/test/model_visualizer_test.py index 0956c45de456..2e8d759c84be 100644 --- a/bindings/pydrake/visualization/test/model_visualizer_test.py +++ b/bindings/pydrake/visualization/test/model_visualizer_test.py @@ -7,6 +7,7 @@ from pydrake.common import FindResourceOrThrow from pydrake.geometry import Meshcat +from pydrake.multibody.parsing import PackageMap import pydrake.visualization as mut import pydrake.visualization._model_visualizer as mut_private @@ -22,26 +23,27 @@ def setUp(self): self.dut = FindResourceOrThrow( "drake/bindings/pydrake/visualization/model_visualizer") - def model_file(self, model_runpath): - """Get a model file from a runpath.""" - return FindResourceOrThrow(model_runpath) + def model_file(self, *, model_url): + """Get a model file from a URL.""" + return PackageMap().ResolveUrl(model_url) def test_model_visualizer(self): """Test that model_visualizer doesn't crash.""" - model_runpaths = [ + model_urls = [ # Simple SDFormat file. - "drake/multibody/benchmarks/acrobot/acrobot.sdf", + "package://drake/multibody/benchmarks/acrobot/acrobot.sdf", # Simple URDF file. - "drake/multibody/benchmarks/acrobot/acrobot.urdf", + "package://drake/multibody/benchmarks/acrobot/acrobot.urdf", # Nested SDFormat file. - "drake/manipulation/util/test/simple_nested_model.sdf", + "package://drake/manipulation/util/test/simple_nested_model.sdf", # SDFormat world file with multiple models. - "drake/manipulation/util/test/simple_world_with_two_models.sdf", + "package://drake/manipulation/util/test/" + + "simple_world_with_two_models.sdf", ] - for model_runpath in model_runpaths: - print(model_runpath) - subprocess.check_call([self.dut, self.model_file(model_runpath), - "--loop_once"]) + for model_url in model_urls: + print(model_url) + filename = self.model_file(model_url=model_url) + subprocess.check_call([self.dut, filename, "--loop_once"]) def test_package_url(self): """Test that a package URL works.""" @@ -52,23 +54,24 @@ def test_package_url(self): def test_pyplot(self): """Test that pyplot doesn't crash.""" - model_runpath = ("drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf") - subprocess.check_call([self.dut, self.model_file(model_runpath), + model_url = ("package://drake_models/iiwa_description/sdf/" + + "iiwa14_no_collision.sdf") + subprocess.check_call([self.dut, self.model_file(model_url=model_url), "--loop_once", "--pyplot"]) def test_set_position(self): """Test that the --position option doesn't crash.""" - model_runpaths = [ + model_urls = [ # Simple SDFormat file. - "drake/multibody/benchmarks/acrobot/acrobot.sdf", + "package://drake/multibody/benchmarks/acrobot/acrobot.sdf", # Simple URDF file. - "drake/multibody/benchmarks/acrobot/acrobot.urdf", + "package://drake/multibody/benchmarks/acrobot/acrobot.urdf", ] - for model_runpath in model_runpaths: - print(model_runpath) - subprocess.check_call([self.dut, self.model_file(model_runpath), - "--loop_once", "--position", "0.1", "0.2"]) + for model_url in model_urls: + print(model_url) + filename = self.model_file(model_url=model_url) + subprocess.check_call([self.dut, filename, "--loop_once", + "--position", "0.1", "0.2"]) class TestModelVisualizer(unittest.TestCase): @@ -138,24 +141,26 @@ def test_model_from_file(self): Visualizes models from files, one at a time. Enables frame visualization for additional code coverage. """ - model_runpaths = [ + model_urls = [ # Simple SDFormat file. - "drake/multibody/benchmarks/acrobot/acrobot.sdf", + "package://drake/multibody/benchmarks/acrobot/acrobot.sdf", # Simple URDF file. - "drake/multibody/benchmarks/acrobot/acrobot.urdf", + "package://drake/multibody/benchmarks/acrobot/acrobot.urdf", # Nested SDFormat file. - "drake/manipulation/util/test/simple_nested_model.sdf", + "package://drake/manipulation/util/test/simple_nested_model.sdf", # SDFormat world file with multiple models. - "drake/manipulation/util/test/simple_world_with_two_models.sdf", + "package://drake/manipulation/util/test/" + + "simple_world_with_two_models.sdf", ] - for i, model_runpath in enumerate(model_runpaths): - with self.subTest(model=model_runpath): + for i, model_url in enumerate(model_urls): + with self.subTest(model=model_url): + filename = PackageMap().ResolveUrl(model_url) dut = mut.ModelVisualizer(visualize_frames=True) if i % 2 == 0: # Conditionally Ping the parser() here, so that we cover # both branching paths within AddModels(). dut.parser() - dut.AddModels(FindResourceOrThrow(model_runpath)) + dut.AddModels(filename=filename) dut.Run(loop_once=True) def test_model_from_url(self): diff --git a/bindings/pydrake/visualization/test/multicam_scenario.yaml b/bindings/pydrake/visualization/test/multicam_scenario.yaml index a4848b504cd4..049f0e72d99b 100644 --- a/bindings/pydrake/visualization/test/multicam_scenario.yaml +++ b/bindings/pydrake/visualization/test/multicam_scenario.yaml @@ -14,7 +14,7 @@ Multicam: child: amazon_table::amazon_table - add_model: name: iiwa - file: package://drake/manipulation/models/iiwa_description/urdf/iiwa14_primitive_collision.urdf + file: package://drake_models/iiwa_description/urdf/iiwa14_primitive_collision.urdf default_joint_positions: iiwa_joint_1: [-0.2] iiwa_joint_2: [0.79] @@ -34,7 +34,7 @@ Multicam: child: iiwa::base - add_model: name: wsg - file: package://drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_with_tip.sdf + file: package://drake_models/wsg_50_description/sdf/schunk_wsg_50_with_tip.sdf default_joint_positions: left_finger_sliding_joint: [-0.02] right_finger_sliding_joint: [0.02] diff --git a/bindings/pydrake/visualization/test/video_test.py b/bindings/pydrake/visualization/test/video_test.py index 070758d9f0c9..91d0c67073c4 100644 --- a/bindings/pydrake/visualization/test/video_test.py +++ b/bindings/pydrake/visualization/test/video_test.py @@ -43,10 +43,10 @@ def _test_usage(self, filename, backend, kinds): directives: - add_model: name: iiwa - file: package://drake/manipulation/models/iiwa_description/sdf/iiwa14_no_collision.sdf # noqa + file: package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf # noqa - add_model: name: wsg - file: package://drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf # noqa + file: package://drake_models/wsg_50_description/sdf/schunk_wsg_50.sdf # noqa - add_weld: parent: world child: iiwa::iiwa_link_0 diff --git a/examples/hardware_sim/BUILD.bazel b/examples/hardware_sim/BUILD.bazel index c98ab25f607d..317a1cd0cb04 100644 --- a/examples/hardware_sim/BUILD.bazel +++ b/examples/hardware_sim/BUILD.bazel @@ -22,9 +22,9 @@ filegroup( srcs = [ ":example_scenarios.yaml", "//examples/pendulum:models", - "//manipulation/models/iiwa_description:models", - "//manipulation/models/wsg_50_description:models", + "@drake_models//:iiwa_description", "@drake_models//:manipulation_station", + "@drake_models//:wsg_50_description", ], visibility = ["//:__pkg__"], ) diff --git a/examples/hardware_sim/example_scenarios.yaml b/examples/hardware_sim/example_scenarios.yaml index 624851d0e2a6..ddd1f028e2fb 100644 --- a/examples/hardware_sim/example_scenarios.yaml +++ b/examples/hardware_sim/example_scenarios.yaml @@ -12,7 +12,7 @@ Demo: child: amazon_table::amazon_table - add_model: name: iiwa - file: package://drake/manipulation/models/iiwa_description/urdf/iiwa14_primitive_collision.urdf + file: package://drake_models/iiwa_description/urdf/iiwa14_primitive_collision.urdf default_joint_positions: iiwa_joint_1: [-0.2] iiwa_joint_2: [0.79] @@ -32,7 +32,7 @@ Demo: child: iiwa::base - add_model: name: wsg - file: package://drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_with_tip.sdf + file: package://drake_models/wsg_50_description/sdf/schunk_wsg_50_with_tip.sdf default_joint_positions: left_finger_sliding_joint: [-0.02] right_finger_sliding_joint: [0.02] diff --git a/examples/kinova_jaco_arm/BUILD.bazel b/examples/kinova_jaco_arm/BUILD.bazel index d17d33086ef9..e0d9db7751c1 100644 --- a/examples/kinova_jaco_arm/BUILD.bazel +++ b/examples/kinova_jaco_arm/BUILD.bazel @@ -15,12 +15,11 @@ drake_cc_binary( srcs = ["jaco_controller.cc"], add_test_rule = 1, data = [ - "//manipulation/models/jaco_description:models", + "@drake_models//:jaco_description", ], test_rule_args = ["--build_only"], deps = [ "//common:add_text_logging_gflags", - "//common:find_resource", "//lcm", "//manipulation/kinova_jaco", "//manipulation/util:robot_plan_interpolator", @@ -39,7 +38,7 @@ drake_cc_binary( srcs = ["jaco_simulation.cc"], add_test_rule = 1, data = [ - "//manipulation/models/jaco_description:models", + "@drake_models//:jaco_description", ], test_rule_args = ["--simulation_sec=0.1"], deps = [ @@ -62,11 +61,10 @@ drake_cc_binary( name = "move_jaco_ee", srcs = ["move_jaco_ee.cc"], data = [ - "//manipulation/models/jaco_description:models", + "@drake_models//:jaco_description", ], deps = [ "//common:add_text_logging_gflags", - "//common:find_resource", "//lcmtypes:jaco", "//manipulation/kinova_jaco:jaco_constants", "//manipulation/util:move_ik_demo_base", diff --git a/examples/kinova_jaco_arm/jaco_controller.cc b/examples/kinova_jaco_arm/jaco_controller.cc index b024eb2af593..0aefa5ef7522 100644 --- a/examples/kinova_jaco_arm/jaco_controller.cc +++ b/examples/kinova_jaco_arm/jaco_controller.cc @@ -7,7 +7,6 @@ #include #include "drake/common/drake_assert.h" -#include "drake/common/find_resource.h" #include "drake/common/text_logging.h" #include "drake/lcm/drake_lcm.h" #include "drake/lcmt_jaco_command.hpp" @@ -17,6 +16,7 @@ #include "drake/manipulation/kinova_jaco/jaco_constants.h" #include "drake/manipulation/kinova_jaco/jaco_status_receiver.h" #include "drake/manipulation/util/robot_plan_interpolator.h" +#include "drake/multibody/parsing/package_map.h" #include "drake/systems/analysis/simulator.h" #include "drake/systems/controllers/pid_controller.h" #include "drake/systems/framework/context.h" @@ -47,9 +47,10 @@ using manipulation::kinova_jaco::kJacoDefaultArmNumJoints; using manipulation::kinova_jaco::kJacoDefaultArmNumFingers; using manipulation::kinova_jaco::JacoStatusReceiver; using manipulation::util::RobotPlanInterpolator; +using multibody::PackageMap; -const char* const kJacoUrdf = - "drake/manipulation/models/jaco_description/urdf/" +const char* const kJacoUrdfUrl = + "package://drake_models/jaco_description/urdf/" "j2s7s300_sphere_collision.urdf"; const char* const kLcmStatusChannel = "KINOVA_JACO_STATUS"; const char* const kLcmCommandChannel = "KINOVA_JACO_COMMAND"; @@ -64,7 +65,8 @@ int DoMain() { kLcmPlanChannel, &lcm)); const std::string urdf = - (!FLAGS_urdf.empty() ? FLAGS_urdf : FindResourceOrThrow(kJacoUrdf)); + (!FLAGS_urdf.empty() ? FLAGS_urdf + : PackageMap{}.ResolveUrl(kJacoUrdfUrl)); auto plan_source = builder.AddSystem(urdf); builder.Connect(plan_sub->get_output_port(), diff --git a/examples/kinova_jaco_arm/jaco_simulation.cc b/examples/kinova_jaco_arm/jaco_simulation.cc index 88a5d7232685..a41ddc7d59bc 100644 --- a/examples/kinova_jaco_arm/jaco_simulation.cc +++ b/examples/kinova_jaco_arm/jaco_simulation.cc @@ -54,7 +54,7 @@ namespace kinova_jaco_arm { namespace { const char kUrdfUrl[] = - "package://drake/manipulation/models/jaco_description/urdf/" + "package://drake_models/jaco_description/urdf/" "j2s7s300_sphere_collision.urdf"; int DoMain() { diff --git a/examples/kinova_jaco_arm/move_jaco_ee.cc b/examples/kinova_jaco_arm/move_jaco_ee.cc index f8d1dce54910..600bf3941d50 100644 --- a/examples/kinova_jaco_arm/move_jaco_ee.cc +++ b/examples/kinova_jaco_arm/move_jaco_ee.cc @@ -9,12 +9,12 @@ #include "lcm/lcm-cpp.hpp" #include -#include "drake/common/find_resource.h" #include "drake/lcmt_jaco_status.hpp" #include "drake/manipulation/kinova_jaco/jaco_constants.h" #include "drake/manipulation/util/move_ik_demo_base.h" #include "drake/math/rigid_transform.h" #include "drake/math/roll_pitch_yaw.h" +#include "drake/multibody/parsing/package_map.h" DEFINE_string(urdf, "", "Name of urdf to load"); DEFINE_string(lcm_status_channel, "KINOVA_JACO_STATUS", @@ -40,9 +40,10 @@ namespace { using manipulation::kinova_jaco::kFingerSdkToUrdf; using manipulation::util::MoveIkDemoBase; +using multibody::PackageMap; -const char kUrdfPath[] = - "drake/manipulation/models/jaco_description/urdf/" +const char kUrdfUrl[] = + "package://drake_models/jaco_description/urdf/" "j2s7s300_sphere_collision.urdf"; int DoMain() { @@ -51,7 +52,7 @@ int DoMain() { Eigen::Vector3d(FLAGS_x, FLAGS_y, FLAGS_z)); MoveIkDemoBase demo( - !FLAGS_urdf.empty() ? FLAGS_urdf : FindResourceOrThrow(kUrdfPath), + !FLAGS_urdf.empty() ? FLAGS_urdf : PackageMap{}.ResolveUrl(kUrdfUrl), "base", FLAGS_ee_name, 100); ::lcm::LCM lc; diff --git a/examples/kuka_iiwa_arm/BUILD.bazel b/examples/kuka_iiwa_arm/BUILD.bazel index 2fb08e8c8e86..0df766bf5026 100644 --- a/examples/kuka_iiwa_arm/BUILD.bazel +++ b/examples/kuka_iiwa_arm/BUILD.bazel @@ -77,7 +77,7 @@ drake_cc_binary( srcs = ["iiwa_controller.cc"], data = [ ":models", - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":iiwa_common", @@ -94,7 +94,7 @@ drake_cc_binary( add_test_rule = 1, data = [ ":models", - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], test_rule_args = ["--simulation_sec=0.1 --target_realtime_rate=0.0"], # TODO(kyle.edwards@kitware.com): Re-enable this test when it no longer @@ -123,7 +123,7 @@ drake_cc_binary( srcs = ["kuka_plan_runner.cc"], data = [ ":models", - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ "//common/trajectories:piecewise_polynomial", @@ -140,7 +140,7 @@ drake_cc_binary( srcs = ["move_iiwa_ee.cc"], data = [ ":models", - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":iiwa_common", @@ -163,7 +163,7 @@ alias( drake_cc_googletest( name = "kuka_torque_controller_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":iiwa_common", @@ -175,7 +175,7 @@ drake_cc_googletest( alias( name = "dual_iiwa14_polytope_collision.urdf", - actual = "//manipulation/models/iiwa_description:urdf/dual_iiwa14_polytope_collision.urdf", # noqa + actual = "@drake_models//:iiwa_description/urdf/dual_iiwa14_polytope_collision.urdf", # noqa ) # Test that kuka_simulation can load the dual arm urdf diff --git a/examples/kuka_iiwa_arm/iiwa_controller.cc b/examples/kuka_iiwa_arm/iiwa_controller.cc index 9f66c8a94f56..106d47c7a146 100644 --- a/examples/kuka_iiwa_arm/iiwa_controller.cc +++ b/examples/kuka_iiwa_arm/iiwa_controller.cc @@ -8,13 +8,13 @@ #include -#include "drake/common/find_resource.h" #include "drake/common/text_logging.h" #include "drake/examples/kuka_iiwa_arm/lcm_plan_interpolator.h" #include "drake/lcm/drake_lcm.h" #include "drake/lcmt_iiwa_command.hpp" #include "drake/lcmt_iiwa_status.hpp" #include "drake/lcmt_robot_plan.hpp" +#include "drake/multibody/parsing/package_map.h" #include "drake/systems/analysis/simulator.h" #include "drake/systems/framework/context.h" #include "drake/systems/framework/diagram.h" @@ -38,9 +38,10 @@ namespace kuka_iiwa_arm { namespace { using manipulation::util::InterpolatorType; using manipulation::util::RobotPlanInterpolator; +using multibody::PackageMap; -const char kIiwaUrdf[] = - "drake/manipulation/models/iiwa_description/urdf/" +const char kIiwaUrdfUrl[] = + "package://drake_models/iiwa_description/urdf/" "iiwa14_polytope_collision.urdf"; // Create a system which has an integrator on the interpolated @@ -57,7 +58,8 @@ int DoMain() { drake::log()->debug("Plan channel: {}", kLcmPlanChannel); const std::string urdf = - (!FLAGS_urdf.empty() ? FLAGS_urdf : FindResourceOrThrow(kIiwaUrdf)); + (!FLAGS_urdf.empty() ? FLAGS_urdf + : PackageMap{}.ResolveUrl(kIiwaUrdfUrl)); // Sets the robot plan interpolation type. std::string interp_str(FLAGS_interp_type); diff --git a/examples/kuka_iiwa_arm/kuka_plan_runner.cc b/examples/kuka_iiwa_arm/kuka_plan_runner.cc index de7893127e89..a572b710d8e8 100644 --- a/examples/kuka_iiwa_arm/kuka_plan_runner.cc +++ b/examples/kuka_iiwa_arm/kuka_plan_runner.cc @@ -181,7 +181,7 @@ class RobotPlanRunner { int do_main() { multibody::MultibodyPlant plant(0.0); multibody::Parser(&plant).AddModelsFromUrl( - "package://drake/manipulation/models/iiwa_description/urdf/" + "package://drake_models/iiwa_description/urdf/" "iiwa14_no_collision.urdf"); plant.WeldFrames(plant.world_frame(), plant.GetBodyByName("base").body_frame()); diff --git a/examples/kuka_iiwa_arm/kuka_simulation.cc b/examples/kuka_iiwa_arm/kuka_simulation.cc index 9ffb35dec3e1..288dfd1a3146 100644 --- a/examples/kuka_iiwa_arm/kuka_simulation.cc +++ b/examples/kuka_iiwa_arm/kuka_simulation.cc @@ -10,7 +10,6 @@ #include #include "drake/common/drake_assert.h" -#include "drake/common/find_resource.h" #include "drake/examples/kuka_iiwa_arm/iiwa_common.h" #include "drake/examples/kuka_iiwa_arm/iiwa_lcm.h" #include "drake/examples/kuka_iiwa_arm/kuka_torque_controller.h" @@ -47,6 +46,7 @@ namespace examples { namespace kuka_iiwa_arm { namespace { using multibody::MultibodyPlant; +using multibody::PackageMap; using systems::Context; using systems::Demultiplexer; using systems::StateInterpolatorWithDiscreteDerivative; @@ -60,11 +60,11 @@ int DoMain() { // Adds a plant. auto [plant, scene_graph] = multibody::AddMultibodyPlantSceneGraph( &builder, FLAGS_sim_dt); - const char* kModelPath = - "drake/manipulation/models/iiwa_description/" + const char* kModelUrl = + "package://drake_models/iiwa_description/" "urdf/iiwa14_polytope_collision.urdf"; const std::string urdf = - (!FLAGS_urdf.empty() ? FLAGS_urdf : FindResourceOrThrow(kModelPath)); + (!FLAGS_urdf.empty() ? FLAGS_urdf : PackageMap{}.ResolveUrl(kModelUrl)); auto iiwa_instance = multibody::Parser(&plant, &scene_graph).AddModels(urdf).at(0); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base")); diff --git a/examples/kuka_iiwa_arm/move_iiwa_ee.cc b/examples/kuka_iiwa_arm/move_iiwa_ee.cc index 1c8581b2b2d3..6e7ed072ecb7 100644 --- a/examples/kuka_iiwa_arm/move_iiwa_ee.cc +++ b/examples/kuka_iiwa_arm/move_iiwa_ee.cc @@ -15,6 +15,7 @@ #include "drake/lcmt_robot_plan.hpp" #include "drake/manipulation/util/move_ik_demo_base.h" #include "drake/math/rigid_transform.h" +#include "drake/multibody/parsing/package_map.h" DEFINE_string(urdf, "", "Name of urdf to load"); DEFINE_string(lcm_status_channel, "IIWA_STATUS", @@ -35,9 +36,10 @@ namespace kuka_iiwa_arm { namespace { using manipulation::util::MoveIkDemoBase; +using multibody::PackageMap; -const char kIiwaUrdf[] = - "drake/manipulation/models/iiwa_description/urdf/" +const char kIiwaUrdfUrl[] = + "package://drake_models/iiwa_description/urdf/" "iiwa14_polytope_collision.urdf"; int DoMain() { @@ -46,7 +48,7 @@ int DoMain() { Eigen::Vector3d(FLAGS_x, FLAGS_y, FLAGS_z)); MoveIkDemoBase demo( - !FLAGS_urdf.empty() ? FLAGS_urdf : FindResourceOrThrow(kIiwaUrdf), + !FLAGS_urdf.empty() ? FLAGS_urdf : PackageMap{}.ResolveUrl(kIiwaUrdfUrl), "base", FLAGS_ee_name, 100); demo.set_joint_velocity_limits(get_iiwa_max_joint_velocities()); diff --git a/examples/kuka_iiwa_arm/test/kuka_torque_controller_test.cc b/examples/kuka_iiwa_arm/test/kuka_torque_controller_test.cc index 32f4829400ca..ee392df3444f 100644 --- a/examples/kuka_iiwa_arm/test/kuka_torque_controller_test.cc +++ b/examples/kuka_iiwa_arm/test/kuka_torque_controller_test.cc @@ -39,11 +39,10 @@ Eigen::VectorXd CalcGravityCompensationTorque( } // namespace GTEST_TEST(KukaTorqueControllerTest, GravityCompensationTest) { - const std::string kIiwaUrdf = - "manipulation/models/iiwa_description/urdf/" - "iiwa14_polytope_collision.urdf"; multibody::MultibodyPlant plant(0.0); - multibody::Parser(&plant).AddModels(kIiwaUrdf); + multibody::Parser(&plant).AddModelsFromUrl( + "package://drake_models/iiwa_description/urdf/" + "iiwa14_polytope_collision.urdf"); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base")); plant.Finalize(); @@ -100,11 +99,10 @@ GTEST_TEST(KukaTorqueControllerTest, GravityCompensationTest) { } GTEST_TEST(KukaTorqueControllerTest, SpringTorqueTest) { - const std::string kIiwaUrdf = - "manipulation/models/iiwa_description/urdf/" - "iiwa14_polytope_collision.urdf"; multibody::MultibodyPlant plant(0.0); - multibody::Parser(&plant).AddModels(kIiwaUrdf); + multibody::Parser(&plant).AddModelsFromUrl( + "package://drake_models/iiwa_description/urdf/" + "iiwa14_polytope_collision.urdf"); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base")); plant.Finalize(); @@ -165,11 +163,10 @@ GTEST_TEST(KukaTorqueControllerTest, SpringTorqueTest) { } GTEST_TEST(KukaTorqueControllerTest, DampingTorqueTest) { - const std::string kIiwaUrdf = - "manipulation/models/iiwa_description/urdf/" - "iiwa14_polytope_collision.urdf"; multibody::MultibodyPlant plant(0.0); - multibody::Parser(&plant).AddModels(kIiwaUrdf); + multibody::Parser(&plant).AddModelsFromUrl( + "package://drake_models/iiwa_description/urdf/" + "iiwa14_polytope_collision.urdf"); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base")); plant.Finalize(); diff --git a/examples/manipulation_station/BUILD.bazel b/examples/manipulation_station/BUILD.bazel index b44355d9c2d1..2ae7bb5e66e8 100644 --- a/examples/manipulation_station/BUILD.bazel +++ b/examples/manipulation_station/BUILD.bazel @@ -29,11 +29,6 @@ drake_cc_library( "@drake_models//:realsense2_description", "@drake_models//:wsg_50_description", "@drake_models//:ycb", - # 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", ], visibility = ["//visibility:public"], deps = [ diff --git a/geometry/BUILD.bazel b/geometry/BUILD.bazel index 9dcf7b5e8bd2..35f5874831b8 100644 --- a/geometry/BUILD.bazel +++ b/geometry/BUILD.bazel @@ -547,8 +547,8 @@ drake_cc_binary( "//examples/kuka_iiwa_arm:models", "//examples/scene_graph:models", "//geometry/render:test_models", - "//manipulation/models/iiwa_description:models", "//multibody/meshcat:models", + "@drake_models//:iiwa_description", "@drake_models//:ycb", ], visibility = ["//visibility:private"], @@ -715,8 +715,8 @@ drake_cc_googletest( name = "meshcat_visualizer_test", data = [ "//geometry/render:test_models", - "//manipulation/models/iiwa_description:models", "//multibody/meshcat:models", + "@drake_models//:iiwa_description", ], deps = [ ":meshcat_visualizer", diff --git a/geometry/benchmarking/BUILD.bazel b/geometry/benchmarking/BUILD.bazel index ed3f1bb27488..8d715a2d710e 100644 --- a/geometry/benchmarking/BUILD.bazel +++ b/geometry/benchmarking/BUILD.bazel @@ -14,9 +14,9 @@ drake_cc_googlebench_binary( srcs = ["iris_in_configuration_space_benchmarks.cc"], add_test_rule = True, data = [ - "//manipulation/models/iiwa_description:models", - "//manipulation/models/wsg_50_description:models", + "@drake_models//:iiwa_description", "@drake_models//:manipulation_station", + "@drake_models//:wsg_50_description", ], test_args = [ "--test", diff --git a/geometry/benchmarking/iris_in_configuration_space_benchmarks.cc b/geometry/benchmarking/iris_in_configuration_space_benchmarks.cc index b88bcca6e1fe..2bf632e3d277 100644 --- a/geometry/benchmarking/iris_in_configuration_space_benchmarks.cc +++ b/geometry/benchmarking/iris_in_configuration_space_benchmarks.cc @@ -80,7 +80,7 @@ class IiwaWithShelvesAndBins : public benchmark::Fixture { # Add iiwa - add_model: name: iiwa - file: package://drake/manipulation/models/iiwa_description/urdf/iiwa14_primitive_collision.urdf + file: package://drake_models/iiwa_description/urdf/iiwa14_primitive_collision.urdf default_joint_positions: iiwa_joint_1: [0] iiwa_joint_2: [0.3] @@ -97,7 +97,7 @@ class IiwaWithShelvesAndBins : public benchmark::Fixture { # Add schunk - add_model: name: wsg - file: package://drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_welded_fingers.sdf + file: package://drake_models/wsg_50_description/sdf/schunk_wsg_50_welded_fingers.sdf - add_weld: parent: iiwa::iiwa_link_7 diff --git a/geometry/test/meshcat_manual_test.cc b/geometry/test/meshcat_manual_test.cc index 4b7a0888bc2e..f9883e75511b 100644 --- a/geometry/test/meshcat_manual_test.cc +++ b/geometry/test/meshcat_manual_test.cc @@ -440,9 +440,9 @@ Ignore those for now; we'll need to circle back and fix them later. auto [plant, scene_graph] = multibody::AddMultibodyPlantSceneGraph(&builder, 0.001); multibody::Parser parser(&plant); - parser.AddModels( - FindResourceOrThrow("drake/manipulation/models/iiwa_description/urdf/" - "iiwa14_spheres_collision.urdf")); + parser.AddModelsFromUrl( + "package://drake_models/iiwa_description/urdf/" + "iiwa14_spheres_collision.urdf"); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base")); parser.AddModels(FindResourceOrThrow( "drake/examples/kuka_iiwa_arm/models/table/" diff --git a/geometry/test/meshcat_visualizer_test.cc b/geometry/test/meshcat_visualizer_test.cc index 37216375687f..edd6b0e7e1f1 100644 --- a/geometry/test/meshcat_visualizer_test.cc +++ b/geometry/test/meshcat_visualizer_test.cc @@ -6,7 +6,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/expect_throws_message.h" #include "drake/geometry/meshcat_types_internal.h" #include "drake/multibody/parsing/parser.h" @@ -45,9 +44,9 @@ class MeshcatVisualizerWithIiwaTest : public ::testing::Test { auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, 0.001); plant_ = &plant; scene_graph_ = &scene_graph; - multibody::Parser(plant_).AddModels( - FindResourceOrThrow("drake/manipulation/models/iiwa_description/urdf/" - "iiwa14_spheres_collision.urdf")); + multibody::Parser(plant_).AddModelsFromUrl( + "package://drake_models/iiwa_description/urdf/" + "iiwa14_spheres_collision.urdf"); plant.WeldFrames(plant.world_frame(), plant.GetBodyByName("base").body_frame()); plant.Finalize(); @@ -466,13 +465,14 @@ GTEST_TEST(MeshcatVisualizerTest, MultipleModels) { systems::DiagramBuilder builder; auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, 0.001); - std::string urdf = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/urdf/" - "iiwa14_no_collision.urdf"); - auto iiwa0 = multibody::Parser(&plant).AddModels(urdf).at(0); + const std::string urdf_url = + "package://drake_models/iiwa_description/urdf/" + "iiwa14_no_collision.urdf"; + auto iiwa0 = multibody::Parser(&plant).AddModelsFromUrl(urdf_url).at(0); plant.WeldFrames(plant.world_frame(), plant.GetBodyByName("base", iiwa0).body_frame()); - auto iiwa1 = multibody::Parser(&plant, "second").AddModels(urdf).at(0); + auto iiwa1 = + multibody::Parser(&plant, "second").AddModelsFromUrl(urdf_url).at(0); plant.WeldFrames(plant.world_frame(), plant.GetBodyByName("base", iiwa1).body_frame()); plant.Finalize(); diff --git a/manipulation/kuka_iiwa/BUILD.bazel b/manipulation/kuka_iiwa/BUILD.bazel index 7f6099f13d4f..1df4e19c9bdc 100644 --- a/manipulation/kuka_iiwa/BUILD.bazel +++ b/manipulation/kuka_iiwa/BUILD.bazel @@ -193,12 +193,11 @@ drake_cc_googletest( drake_cc_googletest( name = "build_iiwa_control_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":build_iiwa_control", ":iiwa_constants", - "//common:find_resource", "//lcm", "//manipulation/util:make_arm_controller_model", "//multibody/parsing:model_instance_info", @@ -215,9 +214,9 @@ drake_cc_googletest( drake_cc_googletest( name = "iiwa_driver_functions_test", data = [ - "//manipulation/models/iiwa_description:models", - "//manipulation/models/wsg_50_description:models", "//manipulation/util:test_directives", + "@drake_models//:iiwa_description", + "@drake_models//:wsg_50_description", ], deps = [ ":iiwa_driver_functions", @@ -237,7 +236,7 @@ drake_cc_googletest( drake_cc_googletest( name = "sim_iiwa_driver_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":iiwa_constants", diff --git a/manipulation/kuka_iiwa/test/build_iiwa_control_test.cc b/manipulation/kuka_iiwa/test/build_iiwa_control_test.cc index a5cb16309b4b..f626c2579f5d 100644 --- a/manipulation/kuka_iiwa/test/build_iiwa_control_test.cc +++ b/manipulation/kuka_iiwa/test/build_iiwa_control_test.cc @@ -6,7 +6,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/lcm/drake_lcm.h" #include "drake/lcmt_iiwa_command.hpp" #include "drake/lcmt_iiwa_status.hpp" @@ -29,6 +28,7 @@ using Eigen::VectorXd; using math::RigidTransformd; using multibody::ModelInstanceIndex; using multibody::MultibodyPlant; +using multibody::PackageMap; using multibody::Parser; using multibody::parsing::ModelInstanceInfo; using systems::ConstantVectorSource; @@ -46,9 +46,9 @@ class BuildIiwaControlTest : public ::testing::Test { void SetUp() { sim_plant_ = builder_.AddSystem>(0.001); Parser parser{sim_plant_}; - const std::string iiwa7_model_path = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/iiwa7" - "/iiwa7_no_collision.sdf"); + const std::string iiwa7_model_path = PackageMap{}.ResolveUrl( + "package://drake_models/iiwa_description/sdf/" + "iiwa7_no_collision.sdf"); const ModelInstanceIndex iiwa7_instance = parser.AddModels(iiwa7_model_path).at(0); const std::string iiwa7_model_name = diff --git a/manipulation/kuka_iiwa/test/sim_iiwa_driver_test.cc b/manipulation/kuka_iiwa/test/sim_iiwa_driver_test.cc index a6b00295a234..4d82988dc08d 100644 --- a/manipulation/kuka_iiwa/test/sim_iiwa_driver_test.cc +++ b/manipulation/kuka_iiwa/test/sim_iiwa_driver_test.cc @@ -31,7 +31,7 @@ class SimIiwaDriverTest : public ::testing::Test { sim_plant_ = std::make_unique>(0.001); Parser parser{sim_plant_.get()}; iiwa_instance_ = parser.AddModelsFromUrl( - "package://drake/manipulation/models/iiwa_description/iiwa7/" + "package://drake_models/iiwa_description/sdf/" "iiwa7_no_collision.sdf")[0]; sim_plant_->WeldFrames(sim_plant_->world_frame(), sim_plant_->GetFrameByName("iiwa_link_0")); diff --git a/manipulation/models/BUILD.bazel b/manipulation/models/BUILD.bazel deleted file mode 100644 index 67914ea7e0a0..000000000000 --- a/manipulation/models/BUILD.bazel +++ /dev/null @@ -1,3 +0,0 @@ -load("//tools/lint:lint.bzl", "add_lint_tests") - -add_lint_tests() diff --git a/manipulation/models/README.md b/manipulation/models/README.md deleted file mode 100644 index 49940933c040..000000000000 --- a/manipulation/models/README.md +++ /dev/null @@ -1,11 +0,0 @@ - -# 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 make any further changes to these model files. diff --git a/manipulation/models/franka_description/BUILD.bazel b/manipulation/models/franka_description/BUILD.bazel deleted file mode 100644 index b3a92fa8eea8..000000000000 --- a/manipulation/models/franka_description/BUILD.bazel +++ /dev/null @@ -1,42 +0,0 @@ -load("//tools/skylark:drake_data.bzl", "models_filegroup") -load("//tools/lint:lint.bzl", "add_lint_tests") - -package(default_visibility = ["//visibility:public"]) - -models_filegroup( - name = "glob_models", - extra_srcs = [ - "LICENSE.TXT", - "README.md", - ], - visibility = ["//visibility:private"], -) - -filegroup( - name = "models", - srcs = [ - ":glob_models", - "@drake_models//:franka_description/meshes/visual/finger.mtl", - "@drake_models//:franka_description/meshes/visual/finger.obj", - "@drake_models//:franka_description/meshes/visual/hand.mtl", - "@drake_models//:franka_description/meshes/visual/hand.obj", - "@drake_models//:franka_description/meshes/visual/link0.mtl", - "@drake_models//:franka_description/meshes/visual/link0.obj", - "@drake_models//:franka_description/meshes/visual/link1.mtl", - "@drake_models//:franka_description/meshes/visual/link1.obj", - "@drake_models//:franka_description/meshes/visual/link2.mtl", - "@drake_models//:franka_description/meshes/visual/link2.obj", - "@drake_models//:franka_description/meshes/visual/link3.mtl", - "@drake_models//:franka_description/meshes/visual/link3.obj", - "@drake_models//:franka_description/meshes/visual/link4.mtl", - "@drake_models//:franka_description/meshes/visual/link4.obj", - "@drake_models//:franka_description/meshes/visual/link5.mtl", - "@drake_models//:franka_description/meshes/visual/link5.obj", - "@drake_models//:franka_description/meshes/visual/link6.mtl", - "@drake_models//:franka_description/meshes/visual/link6.obj", - "@drake_models//:franka_description/meshes/visual/link7.mtl", - "@drake_models//:franka_description/meshes/visual/link7.obj", - ], -) - -add_lint_tests() diff --git a/manipulation/models/franka_description/LICENSE.TXT b/manipulation/models/franka_description/LICENSE.TXT deleted file mode 100644 index c41e8d80a4b8..000000000000 --- a/manipulation/models/franka_description/LICENSE.TXT +++ /dev/null @@ -1,18 +0,0 @@ -This folder contains a model of the Franka Emika Panda arm. - -This model was originally taken from the Franka ROS package, which is -available at: -https://github.com/frankaemika/franka_ros/tree/kinetic-devel/franka_description -SHA d7cd447344. - -The license for these files is the Apache 2.0 license -https://github.com/frankaemika/franka_ros/blob/kinetic-devel/LICENSE -https://github.com/frankaemika/franka_ros/blob/kinetic-devel/franka_ros/package.xml - -The inertial properties for the arm/hand were copied from -https://github.com/mkrizmancic/franka_gazebo which also uses the -Apache 2.0 license. - -As a result, `urdf/*.urdf` are covered by the Apache 2.0 license. The remaining -files (README, unit test, BUILD, etc.) are covered by Drake's license terms -(see LICENSE.TXT in Drake's root folder). diff --git a/manipulation/models/franka_description/README.md b/manipulation/models/franka_description/README.md deleted file mode 100644 index e4f24aed6833..000000000000 --- a/manipulation/models/franka_description/README.md +++ /dev/null @@ -1,43 +0,0 @@ -This folder contains a drake-compatible model of the Franka Emika Panda arm. - -The model differs from the original ROS model and the real robot. In this model -the fingers are independently actuated, rather than using tag, which -Drake does not yet support. - -In addition, some tags unsupported by Drake have been removed, to reduce the -burden of warning output. For URDF support details, see: -https://drake.mit.edu/doxygen_cxx/group__multibody__parsing.html - -### Rotor Inertia and Gear Ratio -The rotor inertias and gear ratios have been picked so that their combination, -i.e rotor_interia * gear_ratio * gear_ratio, is equal to the reflected interia -provided by Franka for the FR-3 robots. -The reflected inertias for the joints of the Franka FR-3 are: -|Axis data | reflected inertia (kg m^2)| -|----------- |--------------------------:| -|Axis 1 (A1) |0.605721456 | -|Axis 2 (A2) |0.605721456 | -|Axis 3 (A3) |0.462474144 | -|Axis 4 (A4) |0.462474144 | -|Axis 5 (A5) |0.205544064 | -|Axis 6 (A6) |0.205544064 | -|Axis 7 (A7) |0.205544064 | - -### Acceleration Limits -The joint acceleration values are taken based on the older FE-3 Panda (not -the newer FR-3 robot): -https://frankaemika.github.io/docs/control_parameters.html#limits-for-panda - -|Axis data | acceleration limit (rad/s^2)| -|----------- |----------------------------:| -|Axis 1 (A1) |15 | -|Axis 2 (A2) |7.5 | -|Axis 3 (A3) |10 | -|Axis 4 (A4) |12.5 | -|Axis 5 (A5) |15 | -|Axis 6 (A6) |20 | -|Axis 7 (A7) |20 | - -### Collision Filters -There is collision filtering applied between `(panda_link5, panda_link7)` and -`(panda_link6, panda_link8)`. diff --git a/manipulation/models/franka_description/VESTIGIAL.md b/manipulation/models/franka_description/VESTIGIAL.md deleted file mode 120000 index 32d46ee883b5..000000000000 --- a/manipulation/models/franka_description/VESTIGIAL.md +++ /dev/null @@ -1 +0,0 @@ -../README.md \ No newline at end of file diff --git a/manipulation/models/franka_description/urdf/hand.urdf b/manipulation/models/franka_description/urdf/hand.urdf deleted file mode 100644 index a932a1811578..000000000000 --- a/manipulation/models/franka_description/urdf/hand.urdf +++ /dev/null @@ -1,128 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - diff --git a/manipulation/models/franka_description/urdf/panda_arm.urdf b/manipulation/models/franka_description/urdf/panda_arm.urdf deleted file mode 100644 index 7794b4606c10..000000000000 --- a/manipulation/models/franka_description/urdf/panda_arm.urdf +++ /dev/null @@ -1,610 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - - - - - - - - - - diff --git a/manipulation/models/franka_description/urdf/panda_arm_hand.urdf b/manipulation/models/franka_description/urdf/panda_arm_hand.urdf deleted file mode 100644 index 6f43fae244c5..000000000000 --- a/manipulation/models/franka_description/urdf/panda_arm_hand.urdf +++ /dev/null @@ -1,736 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - - - - - - - - diff --git a/manipulation/models/franka_description/urdf/panda_hand.urdf b/manipulation/models/franka_description/urdf/panda_hand.urdf deleted file mode 100644 index 1300b191edd2..000000000000 --- a/manipulation/models/franka_description/urdf/panda_hand.urdf +++ /dev/null @@ -1,178 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - diff --git a/manipulation/models/iiwa_description/BUILD.bazel b/manipulation/models/iiwa_description/BUILD.bazel deleted file mode 100644 index b2312d31fb1e..000000000000 --- a/manipulation/models/iiwa_description/BUILD.bazel +++ /dev/null @@ -1,73 +0,0 @@ -load("//tools/skylark:drake_data.bzl", "models_filegroup") -load("//tools/lint:lint.bzl", "add_lint_tests") - -package(default_visibility = ["//visibility:public"]) - -models_filegroup( - name = "glob_models", - extra_srcs = [ - "LICENSE.TXT", - "iiwa_stack.LICENSE.txt", - ], - visibility = ["//visibility:private"], -) - -filegroup( - name = "models", - srcs = [ - ":glob_models", - "@drake_models//:iiwa_description/meshes/iiwa14/collision/link_0.obj", - "@drake_models//:iiwa_description/meshes/iiwa14/collision/link_1.obj", - "@drake_models//:iiwa_description/meshes/iiwa14/collision/link_2.obj", - "@drake_models//:iiwa_description/meshes/iiwa14/collision/link_3.obj", - "@drake_models//:iiwa_description/meshes/iiwa14/collision/link_4.obj", - "@drake_models//:iiwa_description/meshes/iiwa14/collision/link_5.obj", - "@drake_models//:iiwa_description/meshes/iiwa14/collision/link_6.obj", - "@drake_models//:iiwa_description/meshes/iiwa14/collision/link_7.obj", - "@drake_models//:iiwa_description/meshes/iiwa14/collision/link_7_polytope.obj", # noqa - "@drake_models//:iiwa_description/meshes/iiwa14/visual/band.bin", - "@drake_models//:iiwa_description/meshes/iiwa14/visual/band.gltf", - "@drake_models//:iiwa_description/meshes/iiwa14/visual/kuka.bin", - "@drake_models//:iiwa_description/meshes/iiwa14/visual/kuka.gltf", - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_0.bin", - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_0.gltf", - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_1.bin", - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_1.gltf", - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_2_grey.bin", # noqa - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_2_grey.gltf", # noqa - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_2_orange.bin", # noqa - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_2_orange.gltf", # noqa - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_3.bin", - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_3.gltf", - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_4_grey.bin", # noqa - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_4_grey.gltf", # noqa - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_4_orange.bin", # noqa - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_4_orange.gltf", # noqa - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_5.bin", - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_5.gltf", - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_6_grey.bin", # noqa - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_6_grey.gltf", # noqa - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_6_orange.bin", # noqa - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_6_orange.gltf", # noqa - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_7.bin", - "@drake_models//:iiwa_description/meshes/iiwa14/visual/link_7.gltf", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_0.bin", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_0.gltf", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_1.bin", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_1.gltf", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_2.bin", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_2.gltf", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_3.bin", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_3.gltf", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_4.bin", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_4.gltf", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_5.bin", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_5.gltf", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_6.bin", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_6.gltf", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_7.bin", - "@drake_models//:iiwa_description/meshes/iiwa7/visual/link_7.gltf", - ], -) - -add_lint_tests() diff --git a/manipulation/models/iiwa_description/LICENSE.TXT b/manipulation/models/iiwa_description/LICENSE.TXT deleted file mode 100644 index 4737f497769a..000000000000 --- a/manipulation/models/iiwa_description/LICENSE.TXT +++ /dev/null @@ -1,12 +0,0 @@ -This folder contains a model of the Kuka LBR IIWA robot. The files were -originally taken from https://github.com/SalvoVirga/iiwa_stack, SHA -2fa5bd5. The original license for these files is given in the link below and -copied into file iiwa_stack.LICENSE.txt. - -https://github.com/SalvoVirga/iiwa_stack/blob/2fa5bd5/LICENSE.txt - -Since obtaining the model files from the above-mentioned source, they were -substantially modified for use by Drake. For example, the original STL mesh -files were converted to OBJ files, and various mass / inertia properties and -collision models were modified. Our changes are covered by Drake's license terms -(see LICENSE.TXT in Drake's root folder). diff --git a/manipulation/models/iiwa_description/README.md b/manipulation/models/iiwa_description/README.md deleted file mode 100644 index 3d1f680afcad..000000000000 --- a/manipulation/models/iiwa_description/README.md +++ /dev/null @@ -1,152 +0,0 @@ -# IIWA Models - -Execute the following commands to regenerate the URDF files using xacro. Note -that ROS Jade or newer must be used because the xacro scripts make use of more -expressive conditional statements [1]. - -``` -source /opt/ros/kinetic/setup.bash - -cd drake/manipulation/models - -export ROS_PACKAGE_PATH=`pwd`:$ROS_PACKAGE_PATH - -cd iiwa_description - -rosrun xacro xacro -o urdf/iiwa14_primitive_collision.urdf \ -urdf/iiwa14_primitive_collision.urdf.xacro - -rosrun xacro xacro -o urdf/iiwa14_polytope_collision.urdf \ -urdf/iiwa14_polytope_collision.urdf.xacro - -rosrun xacro xacro -o urdf/dual_iiwa14_polytope_collision.urdf \ -urdf/dual_iiwa14_polytope_collision.urdf.xacro -``` - -[1] http://wiki.ros.org/xacro#Conditional_Blocks - -Beware when generating the URDF files as some of them might have been edited -manually. - -## Additional Edits - -Limits have been added to the xacro files, and then manually merged into the -hand-edited files. - -### Velocity and Effort Limits for IIWA 7 - -Velocity and effort limits were derived from the third table at page 1 of the -followking KUKA brochure: - -* "KUKA LBR iiwa technical data. (URL: - -, Accessed on 2024-02-09) - -For the record, the velocity and effort limits: - -|Axis data |Max. Torque|Max. Velocity| -|-----------|----------:|------------:| -|Axis 1 (A1)|176 Nm |98 deg/s | -|Axis 2 (A2)|176 Nm |98 deg/s | -|Axis 3 (A3)|110 Nm |100 deg/s | -|Axis 4 (A4)|110 Nm |130 deg/s | -|Axis 5 (A5)|110 Nm |140 deg/s | -|Axis 6 (A6)|40 Nm |180 deg/s | -|Axis 7 (A7)|40 Nm |180 deg/s | - -### Velocity and Effort Limits for IIWA 14 - -Velocity and effort limits were derived from the third table at page 30 of the -followking KUKA brochure: - -* "KUKA Sensitive robotics_LBR iiwa. (URL: - -, Accessed on 2021-11-21) - -For the record, the velocity and effort limits: - -|Axis data |Max. Torque|Max. Velocity| -|-----------|----------:|------------:| -|Axis 1 (A1)|320 Nm |85 deg/s | -|Axis 2 (A2)|320 Nm |85 deg/s | -|Axis 3 (A3)|176 Nm |100 deg/s | -|Axis 4 (A4)|176 Nm |75 deg/s | -|Axis 5 (A5)|110 Nm |130 deg/s | -|Axis 6 (A6)|40 Nm |135 deg/s | -|Axis 7 (A7)|40 Nm |135 deg/s | - -### Acceleration Limits for iiwa 7 - -Acceleration limits were derived from the iiwa 14 acceleration limits. In particular, -effort limits were taken to be proportional to the spatial mass matrix times the -acceleration limits (manipulator equations). The iiwa 7 acceleration limits were then -calculated using the following formula: - -acc_limits_iiwa7 = acc_limits_iiwa14 * (mass_matrix_inverse_iiwa7 @ effort_limits_iiwa7) -/ (mass_matrix_inverse_iiwa14 @ effort_limits_iiwa14) - -Note that the actual acceleration limits are configuration and movement direction, i.e., -sign(q_ddot), dependent. The provided limits assume zero torques due to gravity and -might thus underestimate or overestimate the actual limits. - -For the record, the rounded acceleration limits: - -|Axis data | rad/s^2 | -|-----------|--------:| -|Axis 1 (A1)|8.65 | -|Axis 2 (A2)|5.44 | -|Axis 3 (A3)|5.69 | -|Axis 4 (A4)|11.01 | -|Axis 5 (A5)|11.78 | -|Axis 6 (A6)|13.76 | -|Axis 7 (A7)|13.17 | - -### Acceleration Limits for IIWA 14 - -Acceleration limits were derived from experimental results listed in Table 4 -(page 50) of the following Master's thesis: - -* "Including a Collaborative Robot in Digital Twin Manufacturing Systems", -Christian Larsen, Gothenburg, Sweden 2019. (URL: -, Accessed -on 2022-01-15) - -The average acceleration limits are used, and rounded to second decimal -place for radians. - -For the record, the rounded average acceleration limits: - -|Axis data | deg/s^2 | rad/s^2 | -|-----------|--------:|--------:| -|Axis 1 (A1)|490.77 |8.57 | -|Axis 2 (A2)|490.80 |8.57 | -|Axis 3 (A3)|500.77 |8.74 | -|Axis 4 (A4)|650.71 |11.36 | -|Axis 5 (A5)|700.73 |12.23 | -|Axis 6 (A6)|900.66 |15.72 | -|Axis 7 (A7)|900.69 |15.72 | - -### Rotor Inertias and Gear Ratios for IIWA 7 -The rotor inertias and gear ratios for the IIWA 7 are assumed to be the same as the DLR LWR II (with a payload of 7kg). -The values for the rotor inertias are obtained from Table A.2 on page 188 in [Ott 2008]. - -[Ott 2008] Ott, Christian. Cartesian impedance control of redundant and flexible-joint robots. Springer, 2008. - -### Rotor Inertia and Gear Ratios for IIWA 14 -The rotor inertias and gear ratios are estimated based on the specifications of a similar robot, i.e. DLR LWR III (link -below). The motors and gears are assumed to be the RoboDrive ILM series and Harmonic Drive CSG series. These values are -being validated experimentally. -* "DLR LWR III. (URL: -, Accessed on 2023-05-08) - -The motor and gear types: -|Axis data | motor | gear | gear ratio | rotor inertia (kg m^2)| -|-----------|-----------:|----------------:|-----------:|----------------------:| -|Axis 1 (A1)|ILM 85x23 |CSG-32-160-2A-GR |160 |1.321e-4 | -|Axis 2 (A2)|ILM 85x23 |CSG-32-160-2A-GR |160 |1.321e-4 | -|Axis 3 (A3)|ILM 70x18 |CSG-32-160-2A-GR |160 |1.321e-4 | -|Axis 4 (A4)|ILM 70x18 |CSG-32-160-2A-GR |160 |1.321e-4 | -|Axis 5 (A5)|ILM 70x18 |CSG-32-100-2A-GR |100 |1.321e-4 | -|Axis 6 (A6)|ILM 50x08 |CSG-20-160-2A-GR |160 |4.54e-5 | -|Axis 7 (A7)|ILM 50x08 |CSG-20-160-2A-GR |160 |4.54e-5 | - diff --git a/manipulation/models/iiwa_description/VESTIGIAL.md b/manipulation/models/iiwa_description/VESTIGIAL.md deleted file mode 120000 index 32d46ee883b5..000000000000 --- a/manipulation/models/iiwa_description/VESTIGIAL.md +++ /dev/null @@ -1 +0,0 @@ -../README.md \ No newline at end of file diff --git a/manipulation/models/iiwa_description/iiwa7/iiwa7_no_collision.sdf b/manipulation/models/iiwa_description/iiwa7/iiwa7_no_collision.sdf deleted file mode 100644 index 6bf968076a7d..000000000000 --- a/manipulation/models/iiwa_description/iiwa7/iiwa7_no_collision.sdf +++ /dev/null @@ -1,352 +0,0 @@ - - - - - - -0.013 0 0.07 0 0 0 - 3.863 - - 0.0141 - 0 - 0 - 0.0171 - 0 - 0.0178 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_0.gltf - - - - 1 - - - 0 0 0.1575 0 0 0 - - 0 -0.0347 0.113 0 0 0 - 2.7025 - - 0.0171 - 0 - 0 - 0.0163 - 0 - 0.006 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_1.gltf - - - - 1 - - - iiwa_link_1 - iiwa_link_0 - - 0 0 1 - - -2.96706 - 2.96706 - 176 - 1.7104226670 - 8.65 - - - 0.0 - 0 - 0 - 0 - - - 160.0 - 0.00007171875 - - - 0 0 0.3405 1.5708 0 -3.14159 - - 0.000 0.0668 0.0344 0 0 0 - 2.7258 - - 0.0170 - 0 - 0 - 0.0061 - 0 - 0.0162 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_2.gltf - - - - 1 - - - iiwa_link_2 - iiwa_link_1 - - -0 1 0 - - -2.0944 - 2.0944 - 176 - 1.7104226670 - 5.44 - - - 0.0 - 0 - 0 - 0 - - - 160.0 - 0.0001737109 - - - 0 0 0.5245 0 0 0 - - 0 0.0296 0.1265 0 0 0 - 3.175 - - 0.025 - 0 - 0 - 0.0238 - 0 - 0.0076 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_3.gltf - - - - 1 - - - iiwa_link_3 - iiwa_link_2 - - 0 0 1 - - -2.96706 - 2.96706 - 110 - 1.7453292520 - 5.69 - - - 0.0 - 0 - 0 - 0 - - - 160.0 - 0.0001266406 - - - 0 0 0.74 1.5708 0 0 - - 0 0.067 0.034 0 0 0 - 2.73 - - 0.017 - 0 - 0 - 0.0061 - 0 - 0.0162 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_4.gltf - - - - 1 - - - iiwa_link_4 - iiwa_link_3 - - 0 -1 0 - - -2.0944 - 2.0944 - 110 - 2.2689280276 - 11.01 - - - 0.0 - 0 - 0 - 0 - - - 160.0 - 0.0000709765 - - - 0 0 0.924 0 0 -3.14159 - - 0.0001 0.021 0.076 0 0 0 - 1.69 - - 0.01 - 0 - 0 - 0.0087 - 0 - 0.00449 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_5.gltf - - - - 1 - - - iiwa_link_5 - iiwa_link_4 - - 0 0 1 - - -2.96706 - 2.96706 - 110 - 2.4434609528 - 11.78 - - - 0.0 - 0 - 0 - 0 - - - 160.0 - 0.000054375 - - - 0 0 1.1395 1.5708 0 -3.14159 - - 0 0.0026 0.0005 0 0 0 - 1.8 - - 0.0051 - 0 - 0 - 0.0049 - 0 - 0.0035 - - - - 0 0 -0.060700 0 0 0 - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_6.gltf - - - - 1 - - - iiwa_link_6 - iiwa_link_5 - - -0 1 -0 - - -2.0944 - 2.0944 - 40 - 3.1415926536 - 13.76 - - - 0.0 - 0 - 0 - 0 - - - 160.0 - 0.000054765 - - - 0 0 1.22 0 0 0 - - 0 0 0.0294 0 0 0 - .4 - - 0.0004 - 0 - 0 - 0.0004 - 0 - 0.0005 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_7.gltf - - - - 1 - - - iiwa_link_7 - iiwa_link_6 - - 0 0 1 - - -3.05433 - 3.05433 - 40 - 3.1415926536 - 13.17 - - - 0.0 - 0 - 0 - 0 - - - 160.0 - 0.000054375 - - 0 - - diff --git a/manipulation/models/iiwa_description/iiwa7/iiwa7_with_box_collision.sdf b/manipulation/models/iiwa_description/iiwa7/iiwa7_with_box_collision.sdf deleted file mode 100644 index e839d1a8c020..000000000000 --- a/manipulation/models/iiwa_description/iiwa7/iiwa7_with_box_collision.sdf +++ /dev/null @@ -1,407 +0,0 @@ - - - - - - -0.013 0 0.07 0 0 0 - 3.863 - - 0.0141 - 0 - 0 - 0.0171 - 0 - 0.0178 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_0.gltf - - - - - -0.004563 0 0.07875 0 0 0 - - - 0.216874 0.207874 0.1575 - - - - - - 0 0 0.1575 0 0 0 - - 0 -0.0347 0.113 0 0 0 - 2.7025 - - 0.0171 - 0 - 0 - 0.0163 - 0 - 0.006 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_1.gltf - - - - - 0 -0.023301 0.127997 0 0 0 - - - 0.13596 0.182584 0.260995 - - - - - - iiwa_link_1 - iiwa_link_0 - - 0 0 1 - - -2.96706 - 2.96706 - 176 - 1.7104226670 - 8.65 - - - 0.0 - 0 - 0 - 0 - - - 160.0 - 0.00007171875 - - - 0 0 0.3405 1.5708 0 -3.14159 - - 0.000 0.0668 0.0344 0 0 0 - 2.7258 - - 0.0170 - 0 - 0 - 0.0061 - 0 - 0.0162 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_2.gltf - - - - - 0 0.0580045 0.0173035 0 0 0 - - - 0.135988 0.251991 0.182605 - - - - - - iiwa_link_2 - iiwa_link_1 - - -0 1 0 - - -2.0944 - 2.0944 - 176 - 1.7104226670 - 5.44 - - - 0 - 0 - 0 - 0 - - - 160.0 - 0.0001737109 - - - 0 0 0.5245 0 0 0 - - 0 0.0296 0.1265 0 0 0 - 3.175 - - 0.025 - 0 - 0 - 0.0238 - 0 - 0.0076 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_3.gltf - - - - - 0 0.0182965 0.11073 0 0 0 - - - 0.135987 0.182593 0.29346 - - - - - - iiwa_link_3 - iiwa_link_2 - - 0 0 1 - - -2.96706 - 2.96706 - 110 - 1.7453292520 - 5.69 - - - 0 - 0 - 0 - 0 - - - 160.0 - 0.0001266406 - - - 0 0 0.74 1.5708 0 0 - - 0 0.067 0.034 0 0 0 - 2.73 - - 0.017 - 0 - 0 - 0.0061 - 0 - 0.0162 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_4.gltf - - - - - 0 0.0580045 0.0233035 0 0 0 - - - 0.135988 0.251991 0.182605 - - - - - - iiwa_link_4 - iiwa_link_3 - - 0 -1 0 - - -2.0944 - 2.0944 - 110 - 2.2689280276 - 11.01 - - - 0 - 0 - 0 - 0 - - - 160.0 - 0.0000709765 - - - 0 0 0.924 0 0 -3.14159 - - 0.0001 0.021 0.076 0 0 0 - 1.69 - - 0.01 - 0 - 0 - 0.0087 - 0 - 0.00449 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_5.gltf - - - - - 0 0.015546 0.102458 0 0 0 - - - 0.135999 0.167092 0.276916 - - - - - - iiwa_link_5 - iiwa_link_4 - - 0 0 1 - - -2.96706 - 2.96706 - 110 - 2.4434609528 - 11.78 - - - 0 - 0 - 0 - 0 - - - 160.0 - 0.000054375 - - - 0 0 1.1395 1.5708 0 -3.14159 - - 0 0.0026 0.0005 0 0 0 - 1.8 - - 0.0051 - 0 - 0 - 0.0049 - 0 - 0.0035 - - - - 0 0 -0.060700 0 0 0 - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_6.gltf - - - - - - - 0.132334 0.177387 0.137409 - - - - - - iiwa_link_6 - iiwa_link_5 - - -0 1 -0 - - -2.0944 - 2.0944 - 40 - 3.1415926536 - 13.76 - - - 0 - 0 - 0 - 0 - - - 160.0 - 0.000054765 - - - 0 0 1.22 0 0 0 - - 0 0 0.0294 0 0 0 - .4 - - 0.0004 - 0 - 0 - 0.0004 - 0 - 0.0005 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa7/visual/link_7.gltf - - - - - 0 0 0.021997 0 0 0 - - - 0.10385 0.103885 0.045 - - - - - - iiwa_link_7 - iiwa_link_6 - - 0 0 1 - - -3.05433 - 3.05433 - 40 - 3.1415926536 - 13.17 - - - 0 - 0 - 0 - 0 - - - 160.0 - 0.000054375 - - 0 - - diff --git a/manipulation/models/iiwa_description/iiwa_stack.LICENSE.txt b/manipulation/models/iiwa_description/iiwa_stack.LICENSE.txt deleted file mode 100644 index 6604b9baee51..000000000000 --- a/manipulation/models/iiwa_description/iiwa_stack.LICENSE.txt +++ /dev/null @@ -1,59 +0,0 @@ -Copyright (c) 2015, Robert Krug & Todor Stoyanov, AASS Research Center, Orebro -University, Sweden All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this - list of conditions and the following disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND -ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED -WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE -FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ------------------------------------------------ - -Most of the files were drastically modified, but the original authors inspired -our work. For everything else : - -Copyright (c) 2016, Salvatore Virga - salvo.virga@tum.de, Marco Esposito - -marco.esposito@tum.de Technische Universität München Chair for Computer Aided -Medical Procedures and Augmented Reality Fakultät für Informatik / I16, -Boltzmannstraße 3, 85748 Garching bei München, Germany http://campar.in.tum.de -All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this - list of conditions and the following disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - -3. Neither the name of the copyright holder nor the names of its contributors - may be used to endorse or promote products derived from this software - without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND -ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED -WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE -FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/manipulation/models/iiwa_description/sdf/iiwa14_no_collision.sdf b/manipulation/models/iiwa_description/sdf/iiwa14_no_collision.sdf deleted file mode 100644 index f89c99077e06..000000000000 --- a/manipulation/models/iiwa_description/sdf/iiwa14_no_collision.sdf +++ /dev/null @@ -1,419 +0,0 @@ - - - - - - - -0.1 0 0.07 0 0 0 - 5 - - 0.05 - 0 - 0 - 0.06 - 0 - 0.03 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_0.gltf - - - - - - - - 0 -0.03 0.12 0 0 0 - 5.76 - - 0.033 - 0 - 0 - 0.0333 - 0 - 0.0123 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_1.gltf - - - - - - 0 0 0.1575 0 0 0 - iiwa_link_1 - iiwa_link_0 - - 0 0 1 - - -2.96705972839 - 2.96705972839 - 320 - 1.4835298641951802 - 8.57 - - - 0.0 - 0 - 0 - 0 - - - 160.0 - 0.0001321 - - - - - 0.0003 0.059 0.042 0 0 0 - 6.35 - - 0.0305 - 0 - 0 - 0.011 - 0 - 0.0304 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_2_grey.gltf - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_2_orange.gltf - - - - - - - 0 0 0.2025 1.570796326794897 0 3.141592653589793 - - iiwa_link_2 - iiwa_link_1 - - 0 0 1 - - -2.09439510239 - 2.09439510239 - 320 - 1.4835298641951802 - 8.57 - - - 0.0 - 0 - 0 - 0 - - - 160.0 - 0.0001321 - - - - - 0 0.03 0.13 0 0 0 - 3.5 - - 0.025 - 0 - 0 - 0.0238 - 0 - 0.0076 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_3.gltf - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/band.gltf - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/kuka.gltf - - - - - - 0 0.2045 0 1.570796326794897 0 3.141592653589793 - iiwa_link_3 - iiwa_link_2 - - 0 0 1 - - -2.96705972839 - 2.96705972839 - 176 - 1.7453292519943295 - 8.74 - - - 0.0 - 0 - 0 - 0 - - - 160.0 - 0.0001321 - - - - - 0 0.067 0.034 0 0 0 - 3.5 - - 0.017 - 0 - 0 - 0.006 - 0 - 0.0164 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_4_grey.gltf - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_4_orange.gltf - - - - - - 0 0 0.2155 1.570796326794897 0 0 - iiwa_link_4 - iiwa_link_3 - - 0 0 1 - - -2.09439510239 - 2.09439510239 - 176 - 1.3089969389957472 - 11.36 - - - 0.0 - 0 - 0 - 0 - - - 160.0 - 0.0001321 - - - - - 0.0001 0.021 0.076 0 0 0 - 3.5 - - 0.01 - 0 - 0 - 0.0087 - 0 - 0.00449 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_5.gltf - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/band.gltf - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/kuka.gltf - - - - - - 0 0.1845 0 -1.570796326794897 3.141592653589793 0 - iiwa_link_5 - iiwa_link_4 - - 0 0 1 - - -2.96705972839 - 2.96705972839 - 110 - 2.2689280275926285 - 12.23 - - - 0.0 - 0 - 0 - 0 - - - 100.0 - 0.0001321 - - - - - 0 0.0006 0.0004 0 0 0 - 1.8 - - 0.0049 - 0 - 0 - 0.0047 - 0 - 0.0036 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_6_grey.gltf - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_6_orange.gltf - - - - - - 0 0 0.2155 1.570796326794897 0 0 - iiwa_link_6 - iiwa_link_5 - - 0 0 1 - - -2.09439510239 - 2.09439510239 - 40 - 2.356194490192345 - 15.72 - - - 0.0 - 0 - 0 - 0 - - - 160.0 - 0.0000454 - - - - - 0 0 0.02 0 0 0 - 1.2 - - 0.001 - 0 - 0 - 0.001 - 0 - 0.001 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_7.gltf - - - - - - - 0 0.081 0 -1.570796326794897 3.141592653589793 0 - - iiwa_link_7 - iiwa_link_6 - - 0 0 1 - - -3.05432619099 - 3.05432619099 - 40 - 2.356194490192345 - 15.72 - - - 0.0 - 0 - 0 - 0 - - - 160.0 - 0.0000454 - - 0 - - diff --git a/manipulation/models/iiwa_description/sdf/iiwa14_polytope_collision.sdf b/manipulation/models/iiwa_description/sdf/iiwa14_polytope_collision.sdf deleted file mode 100644 index faac364e319b..000000000000 --- a/manipulation/models/iiwa_description/sdf/iiwa14_polytope_collision.sdf +++ /dev/null @@ -1,423 +0,0 @@ - - - - - - - -0.1 0 0.07 0 0 0 - 5 - - 0.05 - 0 - 0 - 0.06 - 0 - 0.03 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_0.gltf - - - - - - 0 0 0.1575 0 0 0 - - 0 -0.03 0.12 0 0 0 - 5.76 - - 0.033 - 0 - 0 - 0.0333 - 0 - 0.0123 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_1.gltf - - - - - - iiwa_link_1 - iiwa_link_0 - - 0 0 1 - - -2.96705972839 - 2.96705972839 - 320 - 1.4835298641951802 - 8.57 - - - 0 - 0 - 0 - 0 - - - 160.0 - 0.0001321 - - - 0 0 0.36 1.5708 0 -3.14159 - - 0.0003 0.059 0.042 0 0 0 - 6.35 - - 0.0305 - 0 - 0 - 0.011 - 0 - 0.0304 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_2_grey.gltf - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_2_orange.gltf - - - - - - iiwa_link_2 - iiwa_link_1 - - -0 1 0 - - -2.09439510239 - 2.09439510239 - 320 - 1.4835298641951802 - 8.57 - - - 0 - 0 - 0 - 0 - - - 160.0 - 0.0001321 - - - 0 0 0.5645 0 0 0 - - 0 0.03 0.13 0 0 0 - 3.5 - - 0.025 - 0 - 0 - 0.0238 - 0 - 0.0076 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_3.gltf - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/band.gltf - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/kuka.gltf - - - - - - iiwa_link_3 - iiwa_link_2 - - 0 0 1 - - -2.96705972839 - 2.96705972839 - 176 - 1.7453292519943295 - 8.74 - - - 0 - 0 - 0 - 0 - - - 160.0 - 0.0001321 - - - 0 0 0.78 1.5708 0 0 - - 0 0.067 0.034 0 0 0 - 3.5 - - 0.017 - 0 - 0 - 0.006 - 0 - 0.0164 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_4_grey.gltf - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_4_orange.gltf - - - - - - iiwa_link_4 - iiwa_link_3 - - 0 -1 0 - - -2.09439510239 - 2.09439510239 - 176 - 1.3089969389957472 - 11.36 - - - 0 - 0 - 0 - 0 - - - 160.0 - 0.0001321 - - - 0 0 0.9645 0 0 -3.14159 - - 0.0001 0.021 0.076 0 0 0 - 3.5 - - 0.01 - 0 - 0 - 0.0087 - 0 - 0.00449 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_5.gltf - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/band.gltf - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/kuka.gltf - - - - - - iiwa_link_5 - iiwa_link_4 - - 0 0 1 - - -2.96705972839 - 2.96705972839 - 110 - 2.2689280275926285 - 12.23 - - - 0 - 0 - 0 - 0 - - - 100.0 - 0.0001321 - - - 0 0 1.18 1.5708 0 -3.14159 - - 0 0.0006 0.0004 0 0 0 - 1.8 - - 0.0049 - 0 - 0 - 0.0047 - 0 - 0.0036 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_6_grey.gltf - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_6_orange.gltf - - - - - - iiwa_link_6 - iiwa_link_5 - - -0 1 -0 - - -2.09439510239 - 2.09439510239 - 40 - 2.356194490192345" - 15.72 - - - 0 - 0 - 0 - 0 - - - 160.0 - 0.0000454 - - - 0 0 1.261 0 0 0 - - 0 0 0.02 0 0 0 - 1.2 - - 0.001 - 0 - 0 - 0.001 - 0 - 0.001 - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/collision/link_7_polytope.obj - - - - - - - - - 0.2 - 0.2 - - - - - - - - 1 1 1 - package://drake_models/iiwa_description/meshes/iiwa14/visual/link_7.gltf - - - - - - iiwa_link_7 - iiwa_link_6 - - 0 0 1 - - -3.05432619099 - 3.05432619099 - 40 - 2.356194490192345" - 15.72 - - - 0 - 0 - 0 - 0 - - - 160.0 - 0.0000454 - - 0 - - diff --git a/manipulation/models/iiwa_description/urdf/dual_iiwa14_polytope_collision.urdf b/manipulation/models/iiwa_description/urdf/dual_iiwa14_polytope_collision.urdf deleted file mode 100644 index 86dcb3555f8a..000000000000 --- a/manipulation/models/iiwa_description/urdf/dual_iiwa14_polytope_collision.urdf +++ /dev/null @@ -1,864 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - /left_iiwa - - - - - Gazebo/Grey - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Grey - 0.2 - 0.2 - - - /left_iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /left_iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /left_iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /left_iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /left_iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /left_iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /left_iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - /right_iiwa - - - - - Gazebo/Grey - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Grey - 0.2 - 0.2 - - - /right_iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /right_iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /right_iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /right_iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /right_iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /right_iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /right_iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - diff --git a/manipulation/models/iiwa_description/urdf/dual_iiwa14_polytope_collision.urdf.xacro b/manipulation/models/iiwa_description/urdf/dual_iiwa14_polytope_collision.urdf.xacro deleted file mode 100644 index 9272c599f0a1..000000000000 --- a/manipulation/models/iiwa_description/urdf/dual_iiwa14_polytope_collision.urdf.xacro +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/manipulation/models/iiwa_description/urdf/iiwa.gazebo.xacro b/manipulation/models/iiwa_description/urdf/iiwa.gazebo.xacro deleted file mode 100644 index 88a49dcbe097..000000000000 --- a/manipulation/models/iiwa_description/urdf/iiwa.gazebo.xacro +++ /dev/null @@ -1,59 +0,0 @@ - - - - - - - /${robot_name} - - - - - Gazebo/Grey - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Grey - 0.2 - 0.2 - - - diff --git a/manipulation/models/iiwa_description/urdf/iiwa.transmission.xacro b/manipulation/models/iiwa_description/urdf/iiwa.transmission.xacro deleted file mode 100644 index 0da9fe60078f..000000000000 --- a/manipulation/models/iiwa_description/urdf/iiwa.transmission.xacro +++ /dev/null @@ -1,82 +0,0 @@ - - - - - /${robot_name} - transmission_interface/SimpleTransmission - - ${hardware_interface} - - - ${hardware_interface} - 1 - - - - /${robot_name} - transmission_interface/SimpleTransmission - - ${hardware_interface} - - - ${hardware_interface} - 1 - - - - /${robot_name} - transmission_interface/SimpleTransmission - - ${hardware_interface} - - - ${hardware_interface} - 1 - - - - /${robot_name} - transmission_interface/SimpleTransmission - - ${hardware_interface} - - - ${hardware_interface} - 1 - - - - /${robot_name} - transmission_interface/SimpleTransmission - - ${hardware_interface} - - - ${hardware_interface} - 1 - - - - /${robot_name} - transmission_interface/SimpleTransmission - - ${hardware_interface} - - - ${hardware_interface} - 1 - - - - /${robot_name} - transmission_interface/SimpleTransmission - - ${hardware_interface} - - - ${hardware_interface} - 1 - - - - diff --git a/manipulation/models/iiwa_description/urdf/iiwa14.xacro b/manipulation/models/iiwa_description/urdf/iiwa14.xacro deleted file mode 100644 index ad6ea9387c42..000000000000 --- a/manipulation/models/iiwa_description/urdf/iiwa14.xacro +++ /dev/null @@ -1,465 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 0.0001321 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 0.0001321 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 0.0001321 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 0.0001321 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 0.0001321 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 0.0000454 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 0.0000454 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/manipulation/models/iiwa_description/urdf/iiwa14_no_collision.urdf b/manipulation/models/iiwa_description/urdf/iiwa14_no_collision.urdf deleted file mode 100644 index 445f337df5c9..000000000000 --- a/manipulation/models/iiwa_description/urdf/iiwa14_no_collision.urdf +++ /dev/null @@ -1,431 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - /iiwa - - - - - Gazebo/Grey - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Grey - 0.2 - 0.2 - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - diff --git a/manipulation/models/iiwa_description/urdf/iiwa14_polytope_collision.urdf b/manipulation/models/iiwa_description/urdf/iiwa14_polytope_collision.urdf deleted file mode 100644 index f586da8a1f57..000000000000 --- a/manipulation/models/iiwa_description/urdf/iiwa14_polytope_collision.urdf +++ /dev/null @@ -1,451 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - /iiwa - - - - - Gazebo/Grey - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Grey - 0.2 - 0.2 - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - diff --git a/manipulation/models/iiwa_description/urdf/iiwa14_polytope_collision.urdf.xacro b/manipulation/models/iiwa_description/urdf/iiwa14_polytope_collision.urdf.xacro deleted file mode 100644 index 3de1a8193220..000000000000 --- a/manipulation/models/iiwa_description/urdf/iiwa14_polytope_collision.urdf.xacro +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - diff --git a/manipulation/models/iiwa_description/urdf/iiwa14_primitive_collision.urdf b/manipulation/models/iiwa_description/urdf/iiwa14_primitive_collision.urdf deleted file mode 100644 index 7cb6fef8f3ae..000000000000 --- a/manipulation/models/iiwa_description/urdf/iiwa14_primitive_collision.urdf +++ /dev/null @@ -1,497 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - /iiwa - - - - - Gazebo/Grey - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Grey - 0.2 - 0.2 - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - diff --git a/manipulation/models/iiwa_description/urdf/iiwa14_primitive_collision.urdf.xacro b/manipulation/models/iiwa_description/urdf/iiwa14_primitive_collision.urdf.xacro deleted file mode 100644 index b8d5bf9f5ae8..000000000000 --- a/manipulation/models/iiwa_description/urdf/iiwa14_primitive_collision.urdf.xacro +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - diff --git a/manipulation/models/iiwa_description/urdf/iiwa14_spheres_collision.urdf b/manipulation/models/iiwa_description/urdf/iiwa14_spheres_collision.urdf deleted file mode 100644 index fddaaf299e37..000000000000 --- a/manipulation/models/iiwa_description/urdf/iiwa14_spheres_collision.urdf +++ /dev/null @@ -1,523 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - /iiwa - - - - - Gazebo/Grey - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Grey - 0.2 - 0.2 - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - - - - - - diff --git a/manipulation/models/iiwa_description/urdf/iiwa14_spheres_dense_collision.urdf b/manipulation/models/iiwa_description/urdf/iiwa14_spheres_dense_collision.urdf deleted file mode 100644 index 5c83b7b04109..000000000000 --- a/manipulation/models/iiwa_description/urdf/iiwa14_spheres_dense_collision.urdf +++ /dev/null @@ -1,721 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - /iiwa - - - - - Gazebo/Grey - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Grey - 0.2 - 0.2 - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - - - - - - diff --git a/manipulation/models/iiwa_description/urdf/iiwa14_spheres_dense_elbow_collision.urdf b/manipulation/models/iiwa_description/urdf/iiwa14_spheres_dense_elbow_collision.urdf deleted file mode 100644 index b32b36aa73ab..000000000000 --- a/manipulation/models/iiwa_description/urdf/iiwa14_spheres_dense_elbow_collision.urdf +++ /dev/null @@ -1,577 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - /iiwa - - - - - Gazebo/Grey - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Grey - 0.2 - 0.2 - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - - - - - - diff --git a/manipulation/models/iiwa_description/urdf/materials.xacro b/manipulation/models/iiwa_description/urdf/materials.xacro deleted file mode 100644 index 31389da440ad..000000000000 --- a/manipulation/models/iiwa_description/urdf/materials.xacro +++ /dev/null @@ -1,28 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/manipulation/models/iiwa_description/urdf/planar_iiwa14_spheres_dense_elbow_collision.urdf b/manipulation/models/iiwa_description/urdf/planar_iiwa14_spheres_dense_elbow_collision.urdf deleted file mode 100644 index 57b3fa573aea..000000000000 --- a/manipulation/models/iiwa_description/urdf/planar_iiwa14_spheres_dense_elbow_collision.urdf +++ /dev/null @@ -1,488 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - /iiwa - - - - - Gazebo/Grey - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Orange - 0.2 - 0.2 - - - - Gazebo/Grey - 0.2 - 0.2 - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - /iiwa - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - - - - - - diff --git a/manipulation/models/iiwa_description/urdf/utilities.xacro b/manipulation/models/iiwa_description/urdf/utilities.xacro deleted file mode 100644 index ced3278a883e..000000000000 --- a/manipulation/models/iiwa_description/urdf/utilities.xacro +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - - diff --git a/manipulation/models/jaco_description/BUILD.bazel b/manipulation/models/jaco_description/BUILD.bazel deleted file mode 100644 index de408d02fa57..000000000000 --- a/manipulation/models/jaco_description/BUILD.bazel +++ /dev/null @@ -1,40 +0,0 @@ -load("//tools/skylark:drake_data.bzl", "models_filegroup") -load("//tools/lint:lint.bzl", "add_lint_tests") - -package(default_visibility = [":__subpackages__"]) - -models_filegroup( - name = "glob_models", - extra_srcs = [ - "LICENSE.TXT", - "README.md", - ], - visibility = ["//visibility:private"], -) - -filegroup( - name = "models", - srcs = [ - ":glob_models", - "@drake_models//:jaco_description/meshes/arm.obj", - "@drake_models//:jaco_description/meshes/arm_half_1.obj", - "@drake_models//:jaco_description/meshes/arm_half_2.obj", - "@drake_models//:jaco_description/meshes/arm_mico.obj", - "@drake_models//:jaco_description/meshes/base.obj", - "@drake_models//:jaco_description/meshes/finger_distal.obj", - "@drake_models//:jaco_description/meshes/finger_proximal.obj", - "@drake_models//:jaco_description/meshes/forearm.obj", - "@drake_models//:jaco_description/meshes/forearm_mico.obj", - "@drake_models//:jaco_description/meshes/hand_2finger.obj", - "@drake_models//:jaco_description/meshes/hand_3finger.obj", - "@drake_models//:jaco_description/meshes/ring_big.obj", - "@drake_models//:jaco_description/meshes/ring_small.obj", - "@drake_models//:jaco_description/meshes/shoulder.obj", - "@drake_models//:jaco_description/meshes/wrist.obj", - "@drake_models//:jaco_description/meshes/wrist_spherical_1.obj", - "@drake_models//:jaco_description/meshes/wrist_spherical_2.obj", - ], - visibility = ["//visibility:public"], -) - -add_lint_tests() diff --git a/manipulation/models/jaco_description/LICENSE.TXT b/manipulation/models/jaco_description/LICENSE.TXT deleted file mode 100644 index 53338215082b..000000000000 --- a/manipulation/models/jaco_description/LICENSE.TXT +++ /dev/null @@ -1,16 +0,0 @@ -This folder contains models of the 6-dof and 7-dof 3-finger Kinova -Jaco arms. The files were originally taken from the Kinova ROS -package, which is available at: -https://github.com/Kinovarobotics/kinova-ros/tree/kinova-ros-beta/ -kinova_description/urdf, SHA 006c2e1. - -The original license for these files is covered under the BSD license terms, -as stated in the upstream package file: -https://github.com/Kinovarobotics/kinova-ros/blob/kinova-ros-beta/kinova_description/package.xml - -Since obtaining the model files from the above source, they were modified for -use by Drake. For example, the original DAE and STL mesh files were converted -to OBJ files, and various collision models were modified. Color values in the -URDF were taken directly from the diffuse values in the .dae files contributed -upstream in https://github.com/Kinovarobotics/kinova-ros/pull/222. Our changes -are covered by Drake's license terms (see LICENSE.TXT in Drake's root folder). diff --git a/manipulation/models/jaco_description/README.md b/manipulation/models/jaco_description/README.md deleted file mode 100644 index 369120a69d5c..000000000000 --- a/manipulation/models/jaco_description/README.md +++ /dev/null @@ -1,20 +0,0 @@ -# Jaco models - -This folder contains models of Kinova Jaco robots, based originally on models -from Kinova (see [`LICENSE.TXT`](./LICENSE.TXT) for more information). - -`urdf/j2n6s300*` are models related to the Jaco v2 6DOF non-spherical robot. - -`urdf/j2s7s300.urdf` is a model of the full Jaco v2 7DOF spherical -robot using mesh collision geometry as originally supplied by Kinova. -The versions with `_arm` and `_hand` suffixes are the arm only and -hand only. - -The versions with the `_sphere_collision` suffix use collision -geometry defined entirely by sphere primitives. These models were -created by hand editing the urdf and verifying the results using a -visualization tool such as `//manipulation/util:show_model`. - -In addition, some tags unsupported by Drake have been removed, to reduce the -burden of warning output. For URDF support details, see: -https://drake.mit.edu/doxygen_cxx/group__multibody__parsing.html diff --git a/manipulation/models/jaco_description/VESTIGIAL.md b/manipulation/models/jaco_description/VESTIGIAL.md deleted file mode 120000 index 32d46ee883b5..000000000000 --- a/manipulation/models/jaco_description/VESTIGIAL.md +++ /dev/null @@ -1 +0,0 @@ -../README.md \ No newline at end of file diff --git a/manipulation/models/jaco_description/urdf/j2n6s300.urdf b/manipulation/models/jaco_description/urdf/j2n6s300.urdf deleted file mode 100644 index 6bec22079664..000000000000 --- a/manipulation/models/jaco_description/urdf/j2n6s300.urdf +++ /dev/null @@ -1,555 +0,0 @@ - - - - - - - - - - - - - - j2n6s300 - gazebo_ros_control/DefaultRobotHWSim - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/manipulation/models/jaco_description/urdf/j2n6s300_col.urdf b/manipulation/models/jaco_description/urdf/j2n6s300_col.urdf deleted file mode 100644 index a608a5dbba4d..000000000000 --- a/manipulation/models/jaco_description/urdf/j2n6s300_col.urdf +++ /dev/null @@ -1,525 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - j2n6s300 - gazebo_ros_control/DefaultRobotHWSim - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 160 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 160 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 160 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 160 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 160 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 160 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/manipulation/models/jaco_description/urdf/j2s7s300.urdf b/manipulation/models/jaco_description/urdf/j2s7s300.urdf deleted file mode 100644 index 23b2f0a3c676..000000000000 --- a/manipulation/models/jaco_description/urdf/j2s7s300.urdf +++ /dev/null @@ -1,583 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/manipulation/models/jaco_description/urdf/j2s7s300_arm.urdf b/manipulation/models/jaco_description/urdf/j2s7s300_arm.urdf deleted file mode 100644 index 89be3e58f6d9..000000000000 --- a/manipulation/models/jaco_description/urdf/j2s7s300_arm.urdf +++ /dev/null @@ -1,352 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - diff --git a/manipulation/models/jaco_description/urdf/j2s7s300_arm_sphere_collision.urdf b/manipulation/models/jaco_description/urdf/j2s7s300_arm_sphere_collision.urdf deleted file mode 100644 index cf9159ca8ed8..000000000000 --- a/manipulation/models/jaco_description/urdf/j2s7s300_arm_sphere_collision.urdf +++ /dev/null @@ -1,623 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - diff --git a/manipulation/models/jaco_description/urdf/j2s7s300_hand.urdf b/manipulation/models/jaco_description/urdf/j2s7s300_hand.urdf deleted file mode 100644 index 8e39232ee1de..000000000000 --- a/manipulation/models/jaco_description/urdf/j2s7s300_hand.urdf +++ /dev/null @@ -1,247 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/manipulation/models/jaco_description/urdf/j2s7s300_hand_sphere_collision.urdf b/manipulation/models/jaco_description/urdf/j2s7s300_hand_sphere_collision.urdf deleted file mode 100644 index f85fcbce0b13..000000000000 --- a/manipulation/models/jaco_description/urdf/j2s7s300_hand_sphere_collision.urdf +++ /dev/null @@ -1,422 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/manipulation/models/jaco_description/urdf/j2s7s300_sphere_collision.urdf b/manipulation/models/jaco_description/urdf/j2s7s300_sphere_collision.urdf deleted file mode 100644 index 7135126c2a9c..000000000000 --- a/manipulation/models/jaco_description/urdf/j2s7s300_sphere_collision.urdf +++ /dev/null @@ -1,1029 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - EffortJointInterface - - - EffortJointInterface - 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/manipulation/models/ur3e/BUILD.bazel b/manipulation/models/ur3e/BUILD.bazel deleted file mode 100644 index daf232e8de2a..000000000000 --- a/manipulation/models/ur3e/BUILD.bazel +++ /dev/null @@ -1,57 +0,0 @@ -load("//tools/lint:lint.bzl", "add_lint_tests") -load("//tools/workspace/ros_xacro_internal:defs.bzl", "xacro_file") - -package(default_visibility = ["//visibility:public"]) - -xacro_file( - name = "ur3e_spheres_collision.urdf", - src = "ur3e_spheres_collision.urdf.xacro", - data = [ - "ur.transmission.xacro", - "ur3e.urdf.xacro", - ], -) - -xacro_file( - name = "ur3e_cylinders_collision.urdf", - src = "ur3e_cylinders_collision.urdf.xacro", - data = [ - "ur.transmission.xacro", - "ur3e.urdf.xacro", - ], -) - -filegroup( - name = "glob_models", - srcs = [ - "ur3e_cylinders_collision.urdf", - "ur3e_spheres_collision.urdf", - ], - visibility = ["//visibility:private"], -) - -filegroup( - name = "models", - srcs = [ - ":glob_models", - "@drake_models//:ur3e/base.mtl", - "@drake_models//:ur3e/base.obj", - "@drake_models//:ur3e/forearm.mtl", - "@drake_models//:ur3e/forearm.obj", - "@drake_models//:ur3e/shoulder.mtl", - "@drake_models//:ur3e/shoulder.obj", - "@drake_models//:ur3e/upperarm.mtl", - "@drake_models//:ur3e/upperarm.obj", - "@drake_models//:ur3e/ur3e_color.png", - "@drake_models//:ur3e/ur3e_normal.png", - "@drake_models//:ur3e/ur3e_occlusion_roughness_metallic.png", - "@drake_models//:ur3e/wrist1.mtl", - "@drake_models//:ur3e/wrist1.obj", - "@drake_models//:ur3e/wrist2.mtl", - "@drake_models//:ur3e/wrist2.obj", - "@drake_models//:ur3e/wrist3.mtl", - "@drake_models//:ur3e/wrist3.obj", - ], -) - -add_lint_tests() diff --git a/manipulation/models/ur3e/README.md b/manipulation/models/ur3e/README.md deleted file mode 100644 index 9fec3a09b190..000000000000 --- a/manipulation/models/ur3e/README.md +++ /dev/null @@ -1,12 +0,0 @@ -# ur3e model - -The UR3e models were originally imported from , -exact commit unknown but probably near -. - -High-level changes: -- Converted the mesh format from DAE to OBJ. -- Added two new sets of collision geometries (which can be selected via xacro): - - Cylinders + spheres - - Spheres only (which works better w/ some collision checking frameworks) - \ No newline at end of file diff --git a/manipulation/models/ur3e/VESTIGIAL.md b/manipulation/models/ur3e/VESTIGIAL.md deleted file mode 120000 index 32d46ee883b5..000000000000 --- a/manipulation/models/ur3e/VESTIGIAL.md +++ /dev/null @@ -1 +0,0 @@ -../README.md \ No newline at end of file diff --git a/manipulation/models/ur3e/ur.transmission.xacro b/manipulation/models/ur3e/ur.transmission.xacro deleted file mode 100644 index 4b2d12630765..000000000000 --- a/manipulation/models/ur3e/ur.transmission.xacro +++ /dev/null @@ -1,68 +0,0 @@ - - - - - - - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - 1 - - - - - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - 1 - - - - - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - 1 - - - - - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - 1 - - - - - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - 1 - - - - - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - 1 - - - - - - diff --git a/manipulation/models/ur3e/ur3e.urdf.xacro b/manipulation/models/ur3e/ur3e.urdf.xacro deleted file mode 100644 index 26b92e408544..000000000000 --- a/manipulation/models/ur3e/ur3e.urdf.xacro +++ /dev/null @@ -1,687 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/manipulation/models/ur3e/ur3e_cylinders_collision.urdf.xacro b/manipulation/models/ur3e/ur3e_cylinders_collision.urdf.xacro deleted file mode 100644 index 0e8cff642210..000000000000 --- a/manipulation/models/ur3e/ur3e_cylinders_collision.urdf.xacro +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - diff --git a/manipulation/models/ur3e/ur3e_spheres_collision.urdf.xacro b/manipulation/models/ur3e/ur3e_spheres_collision.urdf.xacro deleted file mode 100644 index a32ade5ac2c0..000000000000 --- a/manipulation/models/ur3e/ur3e_spheres_collision.urdf.xacro +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - diff --git a/manipulation/models/wsg_50_description/BUILD.bazel b/manipulation/models/wsg_50_description/BUILD.bazel deleted file mode 100644 index 14fbe3463cec..000000000000 --- a/manipulation/models/wsg_50_description/BUILD.bazel +++ /dev/null @@ -1,22 +0,0 @@ -load("//tools/skylark:drake_data.bzl", "models_filegroup") -load("//tools/lint:lint.bzl", "add_lint_tests") - -package(default_visibility = [":__subpackages__"]) - -models_filegroup( - name = "glob_models", - visibility = ["//visibility:private"], -) - -filegroup( - name = "models", - srcs = [ - ":glob_models", - "@drake_models//:wsg_50_description/meshes/finger_with_tip.obj", - "@drake_models//:wsg_50_description/meshes/finger_without_tip.obj", - "@drake_models//:wsg_50_description/meshes/wsg_body.obj", - ], - visibility = ["//visibility:public"], -) - -add_lint_tests() diff --git a/manipulation/models/wsg_50_description/README.md b/manipulation/models/wsg_50_description/README.md deleted file mode 100644 index 30f5e3fc6f31..000000000000 --- a/manipulation/models/wsg_50_description/README.md +++ /dev/null @@ -1,4 +0,0 @@ -This folder contains a model of the Schunk WSG 50 gripper. - -Is was created from scratch for use in Drake, and is not based on any other -original SDFormat file from somewhere else. diff --git a/manipulation/models/wsg_50_description/VESTIGIAL.md b/manipulation/models/wsg_50_description/VESTIGIAL.md deleted file mode 120000 index 32d46ee883b5..000000000000 --- a/manipulation/models/wsg_50_description/VESTIGIAL.md +++ /dev/null @@ -1 +0,0 @@ -../README.md \ No newline at end of file diff --git a/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf b/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf deleted file mode 100644 index 51baa4c76d3f..000000000000 --- a/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf +++ /dev/null @@ -1,288 +0,0 @@ - - - - - 0 -0.049133 0 0 0 0 - - 0.988882 - - 0.162992 - 0 - 0 - 0.162992 - 0 - 0.164814 - - - - - - 0.146 0.0725 0.049521 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - - - 0.146 0.0725 0.049521 - - - - - - 1 - 1 - 0 0 0 - 0 - 0 - - - 1 - 0 - 0 - 1 - - 0 - - - - - 0 - 1e+06 - - - 0 - 1 - 1 - - 0 - 0.2 - 1e+13 - 1 - 0.01 - 0 - - - 1 - -0.01 - 0 - 0.2 - 1e+13 - 1 - - - - - - - - - - -0.008 0.025 0 0 0 0 - - 0.05 - - 0.16 - 0 - 0 - 0.16 - 0 - 0.16 - - - - - - 0.016 0.075 0.02 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - - - 0.016 0.075 0.02 - - - - - - 1 - 1 - 0 0 0 - 0 - 0 - - - 1 - 0 - 0 - 1 - - 0 - - - - - 0 - 1e+06 - - - 0 - 1 - 1 - - 0 - 0.2 - 1e+13 - 1 - 0.01 - 0 - - - 1 - -0.01 - 0 - 0.2 - 1e+13 - 1 - - - - - - - 0.008 0.025 0 0 0 0 - - 0.05 - - 0.16 - 0 - 0 - 0.16 - 0 - 0.16 - - - - - - 0.016 0.075 0.02 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - - - 0.016 0.075 0.02 - - - - - - 1 - 1 - 0 0 0 - 0 - 0 - - - 1 - 0 - 0 - 1 - - 0 - - - - - 0 - 1e+06 - - - 0 - 1 - 1 - - 0 - 0.2 - 1e+13 - 1 - 0.01 - 0 - - - 1 - -0.01 - 0 - 0.2 - 1e+13 - 1 - - - - - - - body - left_finger - - 1 0 0 - - - -0.055 - 0 - 80 - 15000 - - - 0 - 0 - 0 - 0 - - - - - body - right_finger - - 1 0 0 - - - 0 - 0.055 - 80 - 15000 - - - 0 - 0 - 0 - 0 - - - - 0 - - diff --git a/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_ball_contact.sdf b/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_ball_contact.sdf deleted file mode 100644 index 60687b161283..000000000000 --- a/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_ball_contact.sdf +++ /dev/null @@ -1,296 +0,0 @@ - - - - - - 0 -0.049133 0 0 0 0 - - 0.988882 - - 0.162992 - 0 - 0 - 0.162992 - 0 - 0.164814 - - - 0 - - - - 0.146 0.0725 0.049521 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - 0 - - - 0.146 0.0725 0.049521 - - - - - - 1 - 1 - 0 0 0 - 0 - 0 - - - 1 - 0 - 0 - 1 - - 0 - - - - - 0 - 1e+06 - - - 0 - 1 - 1 - - 0 - 0.2 - 1e+13 - 1 - 0.01 - 0 - - - 1 - -0.01 - 0 - 0.2 - 1e+13 - 1 - - - - - - - - - - -0.008 0.029 0 0 0 0 - - 0.05 - - 0.16 - 0 - 0 - 0.16 - 0 - 0.16 - - - 0 - - - - 0.016 0.083 0.02 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - - 0 -0.0209 0 0 0 0 - - - 0.008 - - - - - 0 -0.0049 0 0 0 0 - - - 0.008 - - - - - 0 0.0112 0 0 0 0 - - - 0.008 - - - - - 0 0.0271 0 0 0 0 - - - 0.008 - - - - - - 0.0040 0.0375 0.0060 0 0 0 - - - 0.004 - - - - - 0.0040 0.0375 -0.0060 0 0 0 - - - 0.004 - - - - - - 0.008 0.029 0 0 0 0 - - 0.05 - - 0.16 - 0 - 0 - 0.16 - 0 - 0.16 - - - 0 - - - - 0.016 0.083 0.02 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - - 0 -0.0209 0 0 0 0 - - - 0.008 - - - - - 0 -0.0049 0 0 0 0 - - - 0.008 - - - - - 0 0.0112 0 0 0 0 - - - 0.008 - - - - - 0 0.0271 0 0 0 0 - - - 0.008 - - - - - - -0.004 0.0375 0.0060 0 0 0 - - - 0.004 - - - - - -0.004 0.0375 -0.0060 0 0 0 - - - 0.004 - - - - - - body - left_finger - - 1 0 0 - - - -0.055 - 0 - 80 - 15000 - - - 0 - 0 - 0 - 0 - - - - - body - right_finger - - 1 0 0 - - - 0 - 0.055 - 80 - 15000 - - - 0 - 0 - 0 - 0 - - - - 0 - - diff --git a/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_no_tip.sdf b/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_no_tip.sdf deleted file mode 100644 index 408cd8a08141..000000000000 --- a/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_no_tip.sdf +++ /dev/null @@ -1,283 +0,0 @@ - - - - - - 0 -0.049133 0 0 0 0 - - 0.988882 - - 0.162992 - 0 - 0 - 0.162992 - 0 - 0.164814 - - - - - - 1 1 1 - package://drake_models/wsg_50_description/meshes/wsg_body.obj - - - - 0.7 0.7 0.7 1 - - - - - - 0.146 0.0725 0.05 - - - - - - 1 - 1 - 0 0 0 - 0 - 0 - - - 1 - 0 - 0 - 1 - - 0 - - - - - 0 - 1e+06 - - - 0 - 1 - 1 - - 0 - 0.2 - 1e+13 - 1 - 0.01 - 0 - - - 1 - -0.01 - 0 - 0.2 - 1e+13 - 1 - - - - - - - - - - -0.006 0.028 0 0 3.141592 0 - - 0.05 - - 0.16 - 0 - 0 - 0.16 - 0 - 0.16 - - - - - - 1 1 1 - package://drake_models/wsg_50_description/meshes/finger_without_tip.obj - - - - 0.2 0.2 0.2 1 - - - - - - 0.012 0.082 0.02 - - - - - - 1 - 1 - 0 0 0 - 0 - 0 - - - 1 - 0 - 0 - 1 - - 0 - - - - - 0 - 1e+06 - - - 0 - 1 - 1 - - 0 - 0.2 - 1e+13 - 1 - 0.01 - 0 - - - 1 - -0.01 - 0 - 0.2 - 1e+13 - 1 - - - - - - - 0.006 0.028 0 0 0 0 - - 0.05 - - 0.16 - 0 - 0 - 0.16 - 0 - 0.16 - - - - - - 1 1 1 - package://drake_models/wsg_50_description/meshes/finger_without_tip.obj - - - - 0.2 0.2 0.2 1 - - - - - - 0.012 0.082 0.02 - - - - - - 1 - 1 - 0 0 0 - 0 - 0 - - - 1 - 0 - 0 - 1 - - 0 - - - - - 0 - 1e+06 - - - 0 - 1 - 1 - - 0 - 0.2 - 1e+13 - 1 - 0.01 - 0 - - - 1 - -0.01 - 0 - 0.2 - 1e+13 - 1 - - - - - - - body - left_finger - - -1 0 0 - - - -0.055 - 0 - 80 - 15000 - - - 0 - 0 - 0 - 0 - - - - - body - right_finger - - 1 0 0 - - - 0 - 0.055 - 80 - 15000 - - - 0 - 0 - 0 - 0 - - - - 0 - - diff --git a/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_welded_fingers.sdf b/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_welded_fingers.sdf deleted file mode 100644 index 45419b25fe5b..000000000000 --- a/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_welded_fingers.sdf +++ /dev/null @@ -1,113 +0,0 @@ - - - - - - 0 -0.049133 0 0 0 0 - - 0.988882 - - 0.162992 - 0 - 0 - 0.162992 - 0 - 0.164814 - - - - - - 1 1 1 - package://drake_models/wsg_50_description/meshes/wsg_body.obj - - - - 0.7 0.7 0.7 1 - - - - - - 0.146 0.0725 0.05 - - - - - - - - - -0.06 0.028 0 0 3.141592 0 - - 0.05 - - 0.16 - 0 - 0 - 0.16 - 0 - 0.16 - - - - - - 1 1 1 - package://drake_models/wsg_50_description/meshes/finger_without_tip.obj - - - - 0.2 0.2 0.2 1 - - - - - - 0.012 0.082 0.02 - - - - - - 0.06 0.028 0 0 0 0 - - 0.05 - - 0.16 - 0 - 0 - 0.16 - 0 - 0.16 - - - - - - 1 1 1 - package://drake_models/wsg_50_description/meshes/finger_without_tip.obj - - - - 0.2 0.2 0.2 1 - - - - - - 0.012 0.082 0.02 - - - - - - body - left_finger - - - body - right_finger - - - diff --git a/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_with_tip.sdf b/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_with_tip.sdf deleted file mode 100644 index 56f3eb76ddb7..000000000000 --- a/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_with_tip.sdf +++ /dev/null @@ -1,353 +0,0 @@ - - - - - - 0 -0.049133 0 0 0 0 - - 0.988882 - - 0.162992 - 0 - 0 - 0.162992 - 0 - 0.164814 - - - 0 - - - - 1 1 1 - package://drake_models/wsg_50_description/meshes/wsg_body.obj - - - - 0.7 0.7 0.7 1 - - - - 0 - - - 0.146 0.0725 0.05 - - - - - - 1 - 1 - 0 0 0 - 0 - 0 - - - 1 - 0 - 0 - 1 - - 0 - - - - - 0 - 1e+06 - - - 0 - 1 - 1 - - 0 - 0.2 - 1e+13 - 1 - 0.01 - 0 - - - 1 - -0.01 - 0 - 0.2 - 1e+13 - 1 - - - - - - - - - - -0.0115 0.028 0 0 3.141592 0 - - 0.05 - - 0.16 - 0 - 0 - 0.16 - 0 - 0.16 - - - 0 - - - - 1 1 1 - package://drake_models/wsg_50_description/meshes/finger_with_tip.obj - - - - 0.2 0.2 0.2 1 - - - - -0.008 0.021 0 0 0 0 - - - 0.001 - - - - - -0.008 0.041 0 0 0 0 - - - 0.001 - - - - - -0.008 0.031 -0.01 0 0 0 - - - 0.001 - - - - - -0.008 0.031 0.01 0 0 0 - - - 0.001 - - - - - 0 - - - 0.012 0.082 0.02 - - - - - - 1 - 1 - 0 0 0 - 0 - 0 - - - 1 - 0 - 0 - 1 - - 0 - - - - - 0 - 1e+06 - - - 0 - 1 - 1 - - 0 - 0.2 - 1e+13 - 1 - 0.01 - 0 - - - 1 - -0.01 - 0 - 0.2 - 1e+13 - 1 - - - - - - - 0.0115 0.028 0 0 0 0 - - 0.05 - - 0.16 - 0 - 0 - 0.16 - 0 - 0.16 - - - 0 - - - - 1 1 1 - package://drake_models/wsg_50_description/meshes/finger_with_tip.obj - - - - 0.2 0.2 0.2 1 - - - - -0.008 0.021 0 0 0 0 - - - 0.001 - - - - - -0.008 0.041 0 0 0 0 - - - 0.001 - - - - - -0.008 0.031 -0.01 0 0 0 - - - 0.001 - - - - - -0.008 0.031 0.01 0 0 0 - - - 0.001 - - - - - 0 - - - 0.012 0.082 0.02 - - - - - - 1 - 1 - 0 0 0 - 0 - 0 - - - 1 - 0 - 0 - 1 - - 0 - - - - - 0 - 1e+06 - - - 0 - 1 - 1 - - 0 - 0.2 - 1e+13 - 1 - 0.01 - 0 - - - 1 - -0.01 - 0 - 0.2 - 1e+13 - 1 - - - - - - - body - left_finger - - -1 0 0 - - - -0.055 - 0 - 80 - 15000 - - - 0 - 0 - 0 - 0 - - - - - body - right_finger - - 1 0 0 - - - 0 - 0.055 - 80 - 15000 - - - 0 - 0 - 0 - 0 - - - - 0 - - diff --git a/manipulation/schunk_wsg/BUILD.bazel b/manipulation/schunk_wsg/BUILD.bazel index 04eced7fc840..e19a3c6a98de 100644 --- a/manipulation/schunk_wsg/BUILD.bazel +++ b/manipulation/schunk_wsg/BUILD.bazel @@ -154,11 +154,10 @@ drake_cc_library( drake_cc_googletest( name = "schunk_wsg_constants_test", data = [ - "//manipulation/models/wsg_50_description:models", + "@drake_models//:wsg_50_description", ], deps = [ ":schunk_wsg_constants", - "//common:find_resource", "//multibody/parsing", "//multibody/plant", ], @@ -176,7 +175,7 @@ drake_cc_googletest( drake_cc_googletest( name = "schunk_wsg_position_controller_test", data = [ - "//manipulation/models/wsg_50_description:models", + "@drake_models//:wsg_50_description", ], deps = [ ":schunk_wsg_position_controller", @@ -190,7 +189,7 @@ drake_cc_googletest( drake_cc_googletest( name = "schunk_wsg_lcm_test", data = [ - "//manipulation/models/wsg_50_description:models", + "@drake_models//:wsg_50_description", ], deps = [ ":schunk_wsg_lcm", @@ -202,7 +201,7 @@ drake_cc_googletest( drake_cc_googletest( name = "schunk_wsg_trajectory_generator_test", data = [ - "//manipulation/models/wsg_50_description:models", + "@drake_models//:wsg_50_description", ], deps = [ ":schunk_wsg_trajectory_generator", @@ -213,12 +212,11 @@ drake_cc_googletest( drake_cc_googletest( name = "build_schunk_wsg_control_test", data = [ - "//manipulation/models/wsg_50_description:models", + "@drake_models//:wsg_50_description", ], deps = [ ":build_schunk_wsg_control", ":schunk_wsg_lcm", - "//common:find_resource", "//lcm", "//multibody/parsing:parser", "//multibody/plant", @@ -231,11 +229,10 @@ drake_cc_googletest( drake_cc_googletest( name = "schunk_wsg_driver_functions_test", data = [ - "//manipulation/models/wsg_50_description:models", + "@drake_models//:wsg_50_description", ], deps = [ ":schunk_wsg_driver_functions", - "//common:find_resource", "//lcm:drake_lcm_params", "//multibody/parsing:parser", "//multibody/plant", diff --git a/manipulation/schunk_wsg/test/build_schunk_wsg_control_test.cc b/manipulation/schunk_wsg/test/build_schunk_wsg_control_test.cc index 1db264a8154b..145863ebc1a5 100644 --- a/manipulation/schunk_wsg/test/build_schunk_wsg_control_test.cc +++ b/manipulation/schunk_wsg/test/build_schunk_wsg_control_test.cc @@ -5,7 +5,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/lcm/drake_lcm.h" #include "drake/manipulation/schunk_wsg/schunk_wsg_lcm.h" #include "drake/multibody/parsing/parser.h" @@ -33,9 +32,9 @@ class BuildSchunkWsgControlTest : public ::testing::Test { void SetUp() { sim_plant_ = builder_.AddSystem>(0.001); Parser parser{sim_plant_}; - const std::string wsg_file = FindResourceOrThrow( - "drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"); - wsg_instance_ = parser.AddModels(wsg_file).at(0); + const std::string wsg_url = + "package://drake_models/wsg_50_description/sdf/schunk_wsg_50.sdf"; + wsg_instance_ = parser.AddModelsFromUrl(wsg_url).at(0); // Weld the gripper to the world frame. sim_plant_->WeldFrames(sim_plant_->world_frame(), diff --git a/manipulation/schunk_wsg/test/schunk_wsg_constants_test.cc b/manipulation/schunk_wsg/test/schunk_wsg_constants_test.cc index 2a1cf8aa2e5b..f1fc5ac18955 100644 --- a/manipulation/schunk_wsg/test/schunk_wsg_constants_test.cc +++ b/manipulation/schunk_wsg/test/schunk_wsg_constants_test.cc @@ -2,7 +2,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/multibody/parsing/parser.h" #include "drake/multibody/plant/multibody_plant.h" @@ -16,8 +15,8 @@ namespace { GTEST_TEST(SchunkWsgConstantTest, ConstantTest) { multibody::MultibodyPlant plant(0.0); multibody::Parser parser(&plant); - parser.AddModels(FindResourceOrThrow( - "drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf")); + parser.AddModelsFromUrl( + "package://drake_models/wsg_50_description/sdf/schunk_wsg_50.sdf"); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("body")); plant.Finalize(); diff --git a/manipulation/schunk_wsg/test/schunk_wsg_driver_functions_test.cc b/manipulation/schunk_wsg/test/schunk_wsg_driver_functions_test.cc index c1c5080be631..763cf503ee62 100644 --- a/manipulation/schunk_wsg/test/schunk_wsg_driver_functions_test.cc +++ b/manipulation/schunk_wsg/test/schunk_wsg_driver_functions_test.cc @@ -2,7 +2,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/lcm/drake_lcm_params.h" #include "drake/manipulation/schunk_wsg/schunk_wsg_driver.h" #include "drake/multibody/parsing/parser.h" @@ -31,10 +30,10 @@ GTEST_TEST(SchunkWsgDriverFunctionsTest, ApplyDriverConfig) { DiagramBuilder builder; MultibodyPlant& plant = AddMultibodyPlant(MultibodyPlantConfig{}, &builder); - const std::string filename = FindResourceOrThrow( - "drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"); + const std::string url = + "package://drake_models/wsg_50_description/sdf/schunk_wsg_50.sdf"; const ModelInstanceIndex schunk_wsg = - Parser(&plant).AddModels(filename).at(0); + Parser(&plant).AddModelsFromUrl(url).at(0); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("body", schunk_wsg)); plant.Finalize(); diff --git a/manipulation/schunk_wsg/test/schunk_wsg_position_controller_test.cc b/manipulation/schunk_wsg/test/schunk_wsg_position_controller_test.cc index 41a25fae5ee6..1ef216046e46 100644 --- a/manipulation/schunk_wsg/test/schunk_wsg_position_controller_test.cc +++ b/manipulation/schunk_wsg/test/schunk_wsg_position_controller_test.cc @@ -5,7 +5,6 @@ #include #include "drake/common/eigen_types.h" -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/multibody/parsing/parser.h" #include "drake/multibody/plant/multibody_plant.h" @@ -74,10 +73,10 @@ GTEST_TEST(SchunkWsgPositionControllerTest, SimTest) { const auto wsg = builder.AddSystem(kTimeStep); // Add the Schunk gripper and weld it to the world. - const std::string wsg_sdf_path = FindResourceOrThrow( - "drake/manipulation/models/" - "wsg_50_description/sdf/schunk_wsg_50.sdf"); - const auto wsg_model = Parser(wsg).AddModels(wsg_sdf_path).at(0); + const std::string wsg_sdf_url = + "package://drake_models/" + "wsg_50_description/sdf/schunk_wsg_50.sdf"; + const auto wsg_model = Parser(wsg).AddModelsFromUrl(wsg_sdf_url).at(0); wsg->WeldFrames(wsg->world_frame(), wsg->GetFrameByName("body", wsg_model), math::RigidTransformd::Identity()); wsg->Finalize(); diff --git a/manipulation/util/BUILD.bazel b/manipulation/util/BUILD.bazel index 296ee0aa0f36..e77857cae684 100644 --- a/manipulation/util/BUILD.bazel +++ b/manipulation/util/BUILD.bazel @@ -134,7 +134,7 @@ drake_cc_library( drake_py_binary( name = "show_model", srcs = ["show_model.py"], - data = ["//manipulation/models/jaco_description:models"], + data = ["@drake_models//:jaco_description"], deps = ["//bindings/pydrake"], ) @@ -161,7 +161,7 @@ drake_cc_binary( drake_cc_googletest( name = "move_ik_demo_base_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":move_ik_demo_base", @@ -172,7 +172,7 @@ drake_cc_googletest( drake_cc_googletest( name = "robot_plan_utils_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":robot_plan_utils", @@ -194,7 +194,7 @@ drake_cc_googletest( drake_cc_googletest( name = "zero_force_driver_functions_test", data = [ - "//manipulation/models/wsg_50_description:models", + "@drake_models//:wsg_50_description", ], deps = [ ":zero_force_driver_functions", @@ -208,7 +208,7 @@ filegroup( testonly = 1, srcs = [ ":test/panda_arm_and_hand.dmd.yaml", - "//manipulation/models/franka_description:models", + "@drake_models//:franka_description", ], visibility = ["//multibody/parsing:__pkg__"], ) @@ -219,8 +219,8 @@ drake_cc_googletest( ":test/fake_camera.sdf", ":test/iiwa7_wsg.dmd.yaml", ":test/iiwa7_wsg_cameras.dmd.yaml", - "//manipulation/models/iiwa_description:models", - "//manipulation/models/wsg_50_description:models", + "@drake_models//:iiwa_description", + "@drake_models//:wsg_50_description", ], deps = [ ":make_arm_controller_model", @@ -239,11 +239,10 @@ drake_cc_googletest( name = "robot_plan_interpolator_test", data = [ "//examples/kuka_iiwa_arm:models", - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":robot_plan_interpolator", - "//common:find_resource", "//systems/framework", ], ) diff --git a/manipulation/util/test/iiwa7_wsg.dmd.yaml b/manipulation/util/test/iiwa7_wsg.dmd.yaml index fbdf9e16c3f0..210ddefe32d7 100644 --- a/manipulation/util/test/iiwa7_wsg.dmd.yaml +++ b/manipulation/util/test/iiwa7_wsg.dmd.yaml @@ -1,10 +1,10 @@ directives: - add_model: name: iiwa7 - file: package://drake/manipulation/models/iiwa_description/iiwa7/iiwa7_no_collision.sdf + file: package://drake_models/iiwa_description/sdf/iiwa7_no_collision.sdf - add_model: name: schunk_wsg - file: package://drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50_with_tip.sdf + file: package://drake_models/wsg_50_description/sdf/schunk_wsg_50_with_tip.sdf # Weld iiwa7 to the world frame. - add_weld: parent: world diff --git a/manipulation/util/test/make_arm_controller_model_test.cc b/manipulation/util/test/make_arm_controller_model_test.cc index d8634134f465..9e21ca7de3ee 100644 --- a/manipulation/util/test/make_arm_controller_model_test.cc +++ b/manipulation/util/test/make_arm_controller_model_test.cc @@ -26,6 +26,7 @@ using multibody::BodyIndex; using multibody::Frame; using multibody::ModelInstanceIndex; using multibody::MultibodyPlant; +using multibody::PackageMap; using multibody::Parser; using multibody::RigidBody; using multibody::SpatialInertia; @@ -43,11 +44,11 @@ class MakeArmControllerModelTest : public ::testing::Test { MakeArmControllerModelTest() : builder_{}, sim_plant_{builder_.AddSystem>(0.001)}, - iiwa7_model_path_(FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/iiwa7" - "/iiwa7_no_collision.sdf")), - wsg_model_path_(FindResourceOrThrow( - "drake/manipulation/models/wsg_50_description/sdf/" + iiwa7_model_path_(PackageMap{}.ResolveUrl( + "package://drake_models/iiwa_description/sdf/" + "iiwa7_no_collision.sdf")), + wsg_model_path_(PackageMap{}.ResolveUrl( + "package://drake_models/wsg_50_description/sdf/" "schunk_wsg_50.sdf")) { // Add an `empty` model instance to ensure model instance lookups are // correct between this plant and the newly constructed control plant. diff --git a/manipulation/util/test/move_ik_demo_base_test.cc b/manipulation/util/test/move_ik_demo_base_test.cc index c5c5cc19c41d..1478ac37d189 100644 --- a/manipulation/util/test/move_ik_demo_base_test.cc +++ b/manipulation/util/test/move_ik_demo_base_test.cc @@ -2,22 +2,23 @@ #include -#include "drake/common/find_resource.h" #include "drake/manipulation/kuka_iiwa/iiwa_constants.h" +#include "drake/multibody/parsing/package_map.h" namespace drake { namespace manipulation { namespace util { +using multibody::PackageMap; + const char kIiwaUrdf[] = - "drake/manipulation/models/iiwa_description/urdf/" - "iiwa14_no_collision.urdf"; + "package://drake_models/iiwa_description/urdf/iiwa14_no_collision.urdf"; GTEST_TEST(MoveIkDemoBaseTest, IiwaTest) { math::RigidTransformd pose(math::RollPitchYawd(0, 0, -1.57), Eigen::Vector3d(0.8, -0.3, 0.25)); - MoveIkDemoBase dut(FindResourceOrThrow(kIiwaUrdf), "base", "iiwa_link_ee", + MoveIkDemoBase dut(PackageMap{}.ResolveUrl(kIiwaUrdf), "base", "iiwa_link_ee", 100); dut.set_joint_velocity_limits(kuka_iiwa::get_iiwa_max_joint_velocities()); dut.HandleStatus(Eigen::VectorXd::Ones(7)); diff --git a/manipulation/util/test/panda_arm_and_hand.dmd.yaml b/manipulation/util/test/panda_arm_and_hand.dmd.yaml index 55e1d3f0061a..a68c4dfffc02 100644 --- a/manipulation/util/test/panda_arm_and_hand.dmd.yaml +++ b/manipulation/util/test/panda_arm_and_hand.dmd.yaml @@ -1,13 +1,13 @@ directives: - add_model: name: panda - file: package://drake/manipulation/models/franka_description/urdf/panda_arm.urdf + file: package://drake_models/franka_description/urdf/panda_arm.urdf - add_weld: parent: world child: panda::panda_link0 - add_model: name: panda_hand - file: package://drake/manipulation/models/franka_description/urdf/panda_hand.urdf + file: package://drake_models/franka_description/urdf/panda_hand.urdf - add_weld: parent: panda::panda_link8 child: panda_hand::panda_hand diff --git a/manipulation/util/test/robot_plan_interpolator_test.cc b/manipulation/util/test/robot_plan_interpolator_test.cc index 5c3dd9496cfd..409f351860d0 100644 --- a/manipulation/util/test/robot_plan_interpolator_test.cc +++ b/manipulation/util/test/robot_plan_interpolator_test.cc @@ -2,26 +2,28 @@ #include -#include "drake/common/find_resource.h" #include "drake/lcmt_robot_plan.hpp" +#include "drake/multibody/parsing/package_map.h" namespace drake { namespace manipulation { namespace util { namespace { +using multibody::PackageMap; + static const int kNumJoints = 7; const char* const kIiwaUrdf = - "drake/manipulation/models/iiwa_description/urdf/" + "package://drake_models/iiwa_description/urdf/" "iiwa14_polytope_collision.urdf"; const char* const kDualIiwaUrdf = - "drake/manipulation/models/iiwa_description/urdf/" + "package://drake_models/iiwa_description/urdf/" "dual_iiwa14_polytope_collision.urdf"; GTEST_TEST(RobotPlanInterpolatorTest, InstanceTest) { // Test that the constructor works and that the expected ports are // present. - RobotPlanInterpolator dut(FindResourceOrThrow(kIiwaUrdf)); + RobotPlanInterpolator dut(PackageMap{}.ResolveUrl(kIiwaUrdf)); EXPECT_EQ(dut.get_plan_input_port().get_data_type(), systems::kAbstractValued); EXPECT_EQ(dut.get_state_output_port().get_data_type(), @@ -35,7 +37,7 @@ GTEST_TEST(RobotPlanInterpolatorTest, InstanceTest) { GTEST_TEST(RobotPlanInterpolatorTest, DualInstanceTest) { // Check that the port sizes come out appropriately for a dual armed // model. - RobotPlanInterpolator dut(FindResourceOrThrow(kDualIiwaUrdf)); + RobotPlanInterpolator dut(PackageMap{}.ResolveUrl(kDualIiwaUrdf)); EXPECT_EQ(dut.plant().num_positions(), kNumJoints * 2); EXPECT_EQ(dut.plant().num_velocities(), kNumJoints * 2); @@ -64,7 +66,7 @@ struct TrajectoryTestCase { }; void DoTrajectoryTest(InterpolatorType interp_type) { - RobotPlanInterpolator dut(FindResourceOrThrow(kIiwaUrdf), interp_type); + RobotPlanInterpolator dut(PackageMap{}.ResolveUrl(kIiwaUrdf), interp_type); std::vector t{0, 1, 2, 3, 4}; Eigen::MatrixXd q = Eigen::MatrixXd::Zero(kNumJoints, t.size()); diff --git a/manipulation/util/test/robot_plan_utils_test.cc b/manipulation/util/test/robot_plan_utils_test.cc index 514d11559c8c..29c32379db54 100644 --- a/manipulation/util/test/robot_plan_utils_test.cc +++ b/manipulation/util/test/robot_plan_utils_test.cc @@ -4,7 +4,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/multibody/parsing/parser.h" namespace drake { @@ -12,12 +11,11 @@ namespace manipulation { namespace util { const char kIiwaUrdf[] = - "drake/manipulation/models/iiwa_description/urdf/" - "iiwa14_no_collision.urdf"; + "package://drake_models/iiwa_description/urdf/iiwa14_no_collision.urdf"; GTEST_TEST(RobotPlanUtilsTest, GetJointNamesTest) { multibody::MultibodyPlant plant(0.001); - multibody::Parser(&plant).AddModels(FindResourceOrThrow(kIiwaUrdf)); + multibody::Parser(&plant).AddModelsFromUrl(kIiwaUrdf); plant.WeldFrames(plant.world_frame(), plant.GetBodyByName("base").body_frame()); plant.Finalize(); @@ -46,7 +44,7 @@ GTEST_TEST(RobotPlanUtilsTest, ApplyJointVelocityLimitsTest) { GTEST_TEST(RobotPlanUtilsTest, EncodeKeyFramesTest) { multibody::MultibodyPlant plant(0.001); - multibody::Parser(&plant).AddModels(FindResourceOrThrow(kIiwaUrdf)); + multibody::Parser(&plant).AddModelsFromUrl(kIiwaUrdf); plant.WeldFrames(plant.world_frame(), plant.GetBodyByName("base").body_frame()); plant.Finalize(); diff --git a/manipulation/util/test/zero_force_driver_functions_test.cc b/manipulation/util/test/zero_force_driver_functions_test.cc index 60e51a886bb9..9428d106d818 100644 --- a/manipulation/util/test/zero_force_driver_functions_test.cc +++ b/manipulation/util/test/zero_force_driver_functions_test.cc @@ -2,7 +2,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/multibody/parsing/parser.h" #include "drake/multibody/plant/multibody_plant_config_functions.h" #include "drake/systems/analysis/simulator.h" @@ -22,9 +21,8 @@ GTEST_TEST(ZeroForceDriverFunctionsTest, SmokeTest) { DiagramBuilder builder; MultibodyPlant& plant = AddMultibodyPlant(MultibodyPlantConfig{}, &builder); - const std::string filename = FindResourceOrThrow( - "drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"); - Parser(&plant).AddModels(filename); + Parser(&plant).AddModelsFromUrl( + "package://drake_models/wsg_50_description/sdf/schunk_wsg_50.sdf"); plant.Finalize(); // Apply zero actuation input. diff --git a/multibody/benchmarking/BUILD.bazel b/multibody/benchmarking/BUILD.bazel index b6445d5485ad..d5da709521df 100644 --- a/multibody/benchmarking/BUILD.bazel +++ b/multibody/benchmarking/BUILD.bazel @@ -58,11 +58,10 @@ drake_cc_googlebench_binary( srcs = ["iiwa_relaxed_pos_ik.cc"], add_test_rule = True, data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ "//common:add_text_logging_gflags", - "//common:find_resource", "//multibody/inverse_kinematics", "//multibody/parsing", "//solvers:solve", @@ -106,10 +105,9 @@ drake_cc_googlebench_binary( srcs = ["position_constraint.cc"], add_test_rule = True, data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ - "//common:find_resource", "//multibody/inverse_kinematics:kinematic_evaluators", "//multibody/parsing", "//multibody/plant", diff --git a/multibody/benchmarking/iiwa_relaxed_pos_ik.cc b/multibody/benchmarking/iiwa_relaxed_pos_ik.cc index 7a160dfff655..bc48514ebce0 100644 --- a/multibody/benchmarking/iiwa_relaxed_pos_ik.cc +++ b/multibody/benchmarking/iiwa_relaxed_pos_ik.cc @@ -4,7 +4,6 @@ // This benchmark is intended to analyze the performance of nonlinear // optimization with position constraints. -#include "drake/common/find_resource.h" #include "drake/multibody/inverse_kinematics/inverse_kinematics.h" #include "drake/multibody/inverse_kinematics/position_constraint.h" #include "drake/multibody/parsing/parser.h" @@ -41,15 +40,14 @@ BENCHMARK_F(RelaxedPosIkBenchmark, Iiwa)(benchmark::State& state) { // NOLINT const int kNumRandInitGuess = 2; // Find the model file for Kuka iiwa. - const std::string iiwa_path = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/iiwa7/" - "iiwa7_no_collision.sdf"); + const std::string iiwa_url = + "package://drake_models/iiwa_description/sdf/iiwa7_no_collision.sdf"; // Create a continuous-time plant. multibody::MultibodyPlant plant(0.0); // Create a parser for the plant. multibody::Parser parser{&plant}; // Load the model into the parser. - parser.AddModels(iiwa_path); + parser.AddModelsFromUrl(iiwa_url); // Attach the base of the robot into the world frame. plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("iiwa_link_0")); // Finalize the plant. diff --git a/multibody/benchmarking/position_constraint.cc b/multibody/benchmarking/position_constraint.cc index c8e7e91ee904..a79f0383da23 100644 --- a/multibody/benchmarking/position_constraint.cc +++ b/multibody/benchmarking/position_constraint.cc @@ -8,7 +8,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/multibody/parsing/parser.h" #include "drake/tools/performance/fixture_common.h" @@ -28,15 +27,14 @@ class IiwaPositionConstraintFixture : public benchmark::Fixture { const int kNumIiwas = 10; - const std::string iiwa_path = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"); + const std::string iiwa_url = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; plant_ = std::make_unique>(0.0); multibody::Parser parser{plant_.get()}; parser.SetAutoRenaming(true); for (int i = 0; i < kNumIiwas; ++i) { const ModelInstanceIndex model_instance = - parser.AddModels(iiwa_path).at(0); + parser.AddModelsFromUrl(iiwa_url).at(0); plant_->WeldFrames(plant_->world_frame(), plant_->GetFrameByName("iiwa_link_0", model_instance)); } diff --git a/multibody/inverse_kinematics/BUILD.bazel b/multibody/inverse_kinematics/BUILD.bazel index 0f207c1bc1bd..d28dc988a0cf 100644 --- a/multibody/inverse_kinematics/BUILD.bazel +++ b/multibody/inverse_kinematics/BUILD.bazel @@ -154,19 +154,18 @@ drake_cc_googletest( name = "constraint_relaxing_ik_test", srcs = ["test/constraint_relaxing_ik_test.cc"], data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], tags = ["snopt"], deps = [ ":constraint_relaxing_ik", - "//common:find_resource", ], ) drake_cc_googletest( name = "differential_inverse_kinematics_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":differential_inverse_kinematics", @@ -180,7 +179,7 @@ drake_cc_googletest( drake_cc_googletest( name = "differential_inverse_kinematics_integrator_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":differential_inverse_kinematics_integrator", @@ -191,17 +190,18 @@ drake_cc_googletest( ], ) +# TODO(jwnimmer-tri) Test utilities with public visibility are supposed to be +# in a 'test_utilities' subdir, not a 'test' subdir. Move these files. drake_cc_library( name = "inverse_kinematics_test_utilities", testonly = 1, srcs = ["test/inverse_kinematics_test_utilities.cc"], hdrs = ["test/inverse_kinematics_test_utilities.h"], data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ "//common:default_scalars", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//math:compute_numerical_gradient", "//math:gradient", @@ -362,12 +362,14 @@ drake_cc_library( srcs = ["test/global_inverse_kinematics_test_util.cc"], hdrs = ["test/global_inverse_kinematics_test_util.h"], data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", + ], + visibility = [ + "//visibility:private", ], deps = [ ":global_inverse_kinematics", ":inverse_kinematics", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//multibody/benchmarks/kuka_iiwa_robot", "//multibody/parsing", diff --git a/multibody/inverse_kinematics/test/com_in_polyhedron_constraint_test.cc b/multibody/inverse_kinematics/test/com_in_polyhedron_constraint_test.cc index 6ad5ad911fe1..78c76fd10b6f 100644 --- a/multibody/inverse_kinematics/test/com_in_polyhedron_constraint_test.cc +++ b/multibody/inverse_kinematics/test/com_in_polyhedron_constraint_test.cc @@ -133,11 +133,10 @@ TEST_F(IiwaKinematicConstraintTest, } GTEST_TEST(DualIiwaTest, ComInPolyhedronConstraintModelInstance) { - const std::string iiwa_path = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"); + const std::string iiwa_url = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; auto plant = - ConstructIiwaPlant(iiwa_path, 0.1 /* time step */, 2 /* num_iiwa */); + ConstructIiwaPlant(iiwa_url, 0.1 /* time step */, 2 /* num_iiwa */); auto plant_context = plant->CreateDefaultContext(); auto plant_autodiff = systems::System::ToAutoDiffXd(*plant); diff --git a/multibody/inverse_kinematics/test/com_position_constraint_test.cc b/multibody/inverse_kinematics/test/com_position_constraint_test.cc index b5c5b8954787..e5aeec25ead2 100644 --- a/multibody/inverse_kinematics/test/com_position_constraint_test.cc +++ b/multibody/inverse_kinematics/test/com_position_constraint_test.cc @@ -2,7 +2,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/multibody/inverse_kinematics/test/inverse_kinematics_test_utilities.h" using drake::systems::Context; @@ -123,11 +122,10 @@ TEST_F(IiwaKinematicConstraintTest, } GTEST_TEST(DualIiwaTest, ComPositionConstraint_model_instance) { - const std::string iiwa_path = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"); + const std::string iiwa_url = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; auto plant = - ConstructIiwaPlant(iiwa_path, 0.1 /* time step */, 2 /* num_iiwa */); + ConstructIiwaPlant(iiwa_url, 0.1 /* time step */, 2 /* num_iiwa */); auto plant_context = plant->CreateDefaultContext(); auto plant_autodiff = systems::System::ToAutoDiffXd(*plant); diff --git a/multibody/inverse_kinematics/test/constraint_relaxing_ik_test.cc b/multibody/inverse_kinematics/test/constraint_relaxing_ik_test.cc index 82a50fab6177..c2650d19a256 100644 --- a/multibody/inverse_kinematics/test/constraint_relaxing_ik_test.cc +++ b/multibody/inverse_kinematics/test/constraint_relaxing_ik_test.cc @@ -2,7 +2,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/common/random.h" #include "drake/multibody/parsing/parser.h" @@ -16,8 +15,8 @@ namespace multibody { // an IK solution can be computed, and that the resulting pose lies // within the given tolerance from the forward kinematics poses. GTEST_TEST(ConstraintRelaxingIkTest, SolveIkFromFk) { - const std::string kModelPath = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/urdf/" + const std::string kModelPath = PackageMap{}.ResolveUrl( + "package://drake_models/iiwa_description/urdf/" "iiwa14_polytope_collision.urdf"); MultibodyPlant iiwa(0); Parser(&iiwa).AddModels(kModelPath); diff --git a/multibody/inverse_kinematics/test/differential_inverse_kinematics_integrator_test.cc b/multibody/inverse_kinematics/test/differential_inverse_kinematics_integrator_test.cc index 4af06de8e5c0..757fc3c156e5 100644 --- a/multibody/inverse_kinematics/test/differential_inverse_kinematics_integrator_test.cc +++ b/multibody/inverse_kinematics/test/differential_inverse_kinematics_integrator_test.cc @@ -18,10 +18,8 @@ std::unique_ptr> MakeIiwa(void) { // Load the IIWA SDF, welding link_0 to the world. auto robot = std::make_unique>(0.01); multibody::Parser parser(robot.get()); - const std::string filename = FindResourceOrThrow( - "drake/manipulation/models/" - "iiwa_description/sdf/iiwa14_no_collision.sdf"); - parser.AddModels(filename); + parser.AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"); robot->WeldFrames(robot->world_frame(), robot->GetFrameByName("iiwa_link_0")); robot->Finalize(); return robot; @@ -107,10 +105,8 @@ GTEST_TEST(DifferentialInverseKinematicsIntegratorTest, FrameATest) { // This time the iiwa will _not_ be welded to the world. auto robot = std::make_unique>(0.01); multibody::Parser parser(robot.get()); - const std::string filename = FindResourceOrThrow( - "drake/manipulation/models/" - "iiwa_description/sdf/iiwa14_no_collision.sdf"); - parser.AddModels(filename); + parser.AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"); robot->Finalize(); auto robot_context = robot->CreateDefaultContext(); diff --git a/multibody/inverse_kinematics/test/differential_inverse_kinematics_test.cc b/multibody/inverse_kinematics/test/differential_inverse_kinematics_test.cc index 0ce00703013b..7f9e67f81797 100644 --- a/multibody/inverse_kinematics/test/differential_inverse_kinematics_test.cc +++ b/multibody/inverse_kinematics/test/differential_inverse_kinematics_test.cc @@ -8,7 +8,6 @@ #include #include "drake/common/eigen_types.h" -#include "drake/common/find_resource.h" #include "drake/common/fmt_eigen.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/common/test_utilities/expect_throws_message.h" @@ -39,10 +38,8 @@ class DifferentialInverseKinematicsTest : public ::testing::Test { // Load the IIWA SDF, welding link_0 to the world if floating==false. plant_ = std::make_unique>(0.0); multibody::Parser parser(plant_.get()); - const std::string filename = FindResourceOrThrow( - "drake/manipulation/models/" - "iiwa_description/sdf/iiwa14_no_collision.sdf"); - parser.AddModels(filename); + parser.AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"); if (!floating) { math::RigidTransform X_WA = math::RigidTransform( @@ -441,10 +438,9 @@ GTEST_TEST(DifferentialInverseKinematicsParametersTest, TestMutators) { GTEST_TEST(AdditionalDifferentialInverseKinematicsTests, TestLinearObjective) { MultibodyPlant plant(0.0); multibody::Parser parser(&plant); - const std::string filename = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/urdf/" + parser.AddModelsFromUrl( + "package://drake_models/iiwa_description/urdf/" "planar_iiwa14_spheres_dense_elbow_collision.urdf"); - parser.AddModels(filename); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("iiwa_link_0")); plant.Finalize(); const multibody::Frame& frame_7 = plant.GetFrameByName("iiwa_link_7"); diff --git a/multibody/inverse_kinematics/test/global_inverse_kinematics_test_util.cc b/multibody/inverse_kinematics/test/global_inverse_kinematics_test_util.cc index f0331d6a6267..406903f96daf 100644 --- a/multibody/inverse_kinematics/test/global_inverse_kinematics_test_util.cc +++ b/multibody/inverse_kinematics/test/global_inverse_kinematics_test_util.cc @@ -3,7 +3,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/common/fmt_eigen.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/math/roll_pitch_yaw.h" @@ -24,12 +23,11 @@ using drake::solvers::SolutionResult; namespace drake { namespace multibody { std::unique_ptr> ConstructKuka() { - const std::string iiwa_path = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"); + const std::string iiwa_url = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; auto plant = std::make_unique>(0.1); multibody::Parser parser{plant.get()}; - parser.AddModels(iiwa_path); + parser.AddModelsFromUrl(iiwa_url); plant->WeldFrames(plant->world_frame(), plant->GetFrameByName("iiwa_link_0")); plant->Finalize(); diff --git a/multibody/inverse_kinematics/test/inverse_kinematics_test.cc b/multibody/inverse_kinematics/test/inverse_kinematics_test.cc index b1df18887bdb..379b81e5632a 100644 --- a/multibody/inverse_kinematics/test/inverse_kinematics_test.cc +++ b/multibody/inverse_kinematics/test/inverse_kinematics_test.cc @@ -71,8 +71,7 @@ GTEST_TEST(InverseKinematicsTest, ConstructorWithJointLimits) { // the joint limits are imposed when with_joint_limits=true, and the joint // limits are ignored when with_joint_limits=false. auto plant = ConstructIiwaPlant( - FindResourceOrThrow("drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"), + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf", 0.01); InverseKinematics ik_with_joint_limits(*plant); diff --git a/multibody/inverse_kinematics/test/inverse_kinematics_test_utilities.cc b/multibody/inverse_kinematics/test/inverse_kinematics_test_utilities.cc index 4d264566e054..83a15e8db29b 100644 --- a/multibody/inverse_kinematics/test/inverse_kinematics_test_utilities.cc +++ b/multibody/inverse_kinematics/test/inverse_kinematics_test_utilities.cc @@ -24,15 +24,14 @@ namespace multibody { using math::RigidTransformd; IiwaKinematicConstraintTest::IiwaKinematicConstraintTest() { - const std::string iiwa_path = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"); + const std::string iiwa_url = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; systems::DiagramBuilder builder{}; plant_ = builder.AddSystem>(0.1); plant_->RegisterAsSourceForSceneGraph( builder.AddSystem>()); multibody::Parser parser{plant_}; - parser.AddModels(iiwa_path); + parser.AddModelsFromUrl(iiwa_url); plant_->WeldFrames(plant_->world_frame(), plant_->GetFrameByName("iiwa_link_0")); plant_->Finalize(); @@ -43,7 +42,7 @@ IiwaKinematicConstraintTest::IiwaKinematicConstraintTest() { &diagram_->GetMutableSubsystemContext(*plant_, diagram_context_.get()); plant_autodiff_ = systems::System::ToAutoDiffXd( - *ConstructIiwaPlant(iiwa_path, 0.1)); + *ConstructIiwaPlant(iiwa_url, 0.1)); plant_context_autodiff_ = plant_autodiff_->CreateDefaultContext(); } @@ -82,12 +81,12 @@ std::unique_ptr> ConstructTwoFreeBodiesPlant() { } std::unique_ptr> ConstructIiwaPlant( - const std::string& file_path, double time_step, int num_iiwa) { + const std::string& url, double time_step, int num_iiwa) { auto plant = std::make_unique>(time_step); Parser parser(plant.get()); parser.SetAutoRenaming(true); for (int i = 0; i < num_iiwa; ++i) { - const auto iiwa_instance = parser.AddModels(file_path).at(0); + const auto iiwa_instance = parser.AddModelsFromUrl(url).at(0); plant->WeldFrames(plant->world_frame(), plant->GetFrameByName("iiwa_link_0", iiwa_instance)); } diff --git a/multibody/inverse_kinematics/test/inverse_kinematics_test_utilities.h b/multibody/inverse_kinematics/test/inverse_kinematics_test_utilities.h index e7af1d81dcd3..d98c407de067 100644 --- a/multibody/inverse_kinematics/test/inverse_kinematics_test_utilities.h +++ b/multibody/inverse_kinematics/test/inverse_kinematics_test_utilities.h @@ -38,7 +38,7 @@ std::unique_ptr> ConstructTwoFreeBodiesPlant(); * Constructs a MultibodyPlant consisting of an Iiwa robot. */ std::unique_ptr> ConstructIiwaPlant( - const std::string& file_path, double time_step, int num_iiwa = 1); + const std::string& url, double time_step, int num_iiwa = 1); /** * Compares if two eigen matrices of AutoDiff have the same values and diff --git a/multibody/meshcat/BUILD.bazel b/multibody/meshcat/BUILD.bazel index 776495edcc57..24e973f3eb7c 100644 --- a/multibody/meshcat/BUILD.bazel +++ b/multibody/meshcat/BUILD.bazel @@ -96,9 +96,9 @@ drake_cc_googletest( name = "joint_sliders_test", data = [ ":test/universal_joint.sdf", - "//manipulation/models/iiwa_description:models", "//multibody:models", "//multibody/benchmarks/acrobot:models", + "@drake_models//:iiwa_description", ], deps = [ ":joint_sliders", diff --git a/multibody/meshcat/test/joint_sliders_test.cc b/multibody/meshcat/test/joint_sliders_test.cc index a6bbcbd5ae89..11b175271bc0 100644 --- a/multibody/meshcat/test/joint_sliders_test.cc +++ b/multibody/meshcat/test/joint_sliders_test.cc @@ -3,7 +3,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/common/test_utilities/expect_throws_message.h" #include "drake/geometry/meshcat_visualizer.h" @@ -33,14 +32,14 @@ class JointSlidersTest : public ::testing::Test { plant_{plant_and_scene_graph_.plant}, scene_graph_{plant_and_scene_graph_.scene_graph} {} - void Add(const std::string& resource_path, + void Add(const std::string& url, const std::string& model_name = {}) { Parser parser(&plant_, model_name); - parser.AddModels(FindResourceOrThrow(resource_path)); + parser.AddModelsFromUrl(url); } void AddAcrobot() { - Add("drake/multibody/benchmarks/acrobot/acrobot.urdf"); + Add("package://drake/multibody/benchmarks/acrobot/acrobot.urdf"); plant_.Finalize(); } @@ -206,8 +205,8 @@ TEST_F(JointSlidersTest, WrongNumPositions) { // Test robots with overlapping joint names, in which case the model name must // be used to disambiguate them. TEST_F(JointSlidersTest, DuplicatedJointNames) { - Add("drake/multibody/benchmarks/acrobot/acrobot.urdf", "alpha"); - Add("drake/multibody/benchmarks/acrobot/acrobot.urdf", "bravo"); + Add("package://drake/multibody/benchmarks/acrobot/acrobot.urdf", "alpha"); + Add("package://drake/multibody/benchmarks/acrobot/acrobot.urdf", "bravo"); plant_.Finalize(); // Add the sliders. @@ -226,7 +225,7 @@ TEST_F(JointSlidersTest, DuplicatedJointNames) { // Test a multi-dof joint. TEST_F(JointSlidersTest, MultiDofJoint) { - Add("drake/multibody/meshcat/test/universal_joint.sdf"); + Add("package://drake/multibody/meshcat/test/universal_joint.sdf"); plant_.Finalize(); const JointSliders dut(meshcat_, &plant_); @@ -239,7 +238,7 @@ TEST_F(JointSlidersTest, MultiDofJoint) { // for this, which is fine (and thus we'd change this test), but at least for // now we should confirm that nothing crashes in this case. TEST_F(JointSlidersTest, FreeBody) { - Add("drake/multibody/models/box.urdf"); + Add("package://drake/multibody/models/box.urdf"); plant_.Finalize(); const JointSliders dut(meshcat_, &plant_); EXPECT_EQ(dut.get_output_port().size(), 7); @@ -377,7 +376,7 @@ TEST_F(JointSlidersTest, SetPositionsKukaIiwaRobot) { static constexpr char kKukaIiwaJoint5[] = "iiwa_joint_5"; // Index: 11 static constexpr char kKukaIiwaJoint6[] = "iiwa_joint_6"; // Index: 12 static constexpr char kKukaIiwaJoint7[] = "iiwa_joint_7"; // Index: 13 - Add("drake/manipulation/models/iiwa_description/urdf/" + Add("package://drake_models/iiwa_description/urdf/" "iiwa14_primitive_collision.urdf"); plant_.Finalize(); JointSliders dut(meshcat_, &plant_); diff --git a/multibody/optimization/BUILD.bazel b/multibody/optimization/BUILD.bazel index 4ebb236dfe81..6cdc5a5831da 100644 --- a/multibody/optimization/BUILD.bazel +++ b/multibody/optimization/BUILD.bazel @@ -300,7 +300,7 @@ drake_cc_googletest( drake_cc_googletest( name = "toppra_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], use_default_main = False, deps = [ diff --git a/multibody/optimization/test/centroidal_momentum_constraint_test.cc b/multibody/optimization/test/centroidal_momentum_constraint_test.cc index aece0d29a052..098b548634ed 100644 --- a/multibody/optimization/test/centroidal_momentum_constraint_test.cc +++ b/multibody/optimization/test/centroidal_momentum_constraint_test.cc @@ -2,9 +2,9 @@ #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/multibody/inverse_kinematics/test/inverse_kinematics_test_utilities.h" +#include "drake/multibody/parsing/package_map.h" namespace drake { namespace multibody { @@ -102,12 +102,12 @@ void CentroidalMomentumConstraintTester( } GTEST_TEST(CentroidalMomentumConstraintTest, TestDualIiwas) { - const std::string iiwa_path = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"); + const std::string iiwa_url = + "package://drake_models/iiwa_description/sdf/" + "iiwa14_no_collision.sdf"; auto plant = - ConstructIiwaPlant(iiwa_path, 0.1 /* time step */, 2 /* num_iiwa */); + ConstructIiwaPlant(iiwa_url, 0.1 /* time step */, 2 /* num_iiwa */); auto plant_context = plant->CreateDefaultContext(); auto plant_autodiff = systems::System::ToAutoDiffXd(*plant); auto plant_context_autodiff = plant_autodiff->CreateDefaultContext(); diff --git a/multibody/optimization/test/toppra_test.cc b/multibody/optimization/test/toppra_test.cc index 07ec4f0e21e6..8d0cffbe274a 100644 --- a/multibody/optimization/test/toppra_test.cc +++ b/multibody/optimization/test/toppra_test.cc @@ -22,7 +22,7 @@ class IiwaToppraTest : public ::testing::Test { IiwaToppraTest() : iiwa_plant_(std::make_unique>(0)) { multibody::Parser(iiwa_plant_.get()) .AddModelsFromUrl( - "package://drake/manipulation/models/iiwa_description/iiwa7/" + "package://drake_models/iiwa_description/sdf/" "iiwa7_no_collision.sdf"); iiwa_plant_->WeldFrames( iiwa_plant_->world_frame(), iiwa_plant_->GetFrameByName("iiwa_link_0")); diff --git a/multibody/parsing/BUILD.bazel b/multibody/parsing/BUILD.bazel index fe6fd1999d5b..445d21537a7d 100644 --- a/multibody/parsing/BUILD.bazel +++ b/multibody/parsing/BUILD.bazel @@ -580,8 +580,8 @@ drake_cc_googletest( name = "detail_sdf_parser_test", data = [ ":test_models", - "//manipulation/models/iiwa_description:models", "//multibody/benchmarks/acrobot:models", + "@drake_models//:iiwa_description", ], deps = [ ":detail_mujoco_parser", @@ -595,9 +595,9 @@ drake_cc_googletest( name = "detail_urdf_parser_test", data = [ ":test_models", - "//manipulation/models/iiwa_description:models", "//multibody/benchmarks/acrobot:models", "@drake_models//:atlas", + "@drake_models//:iiwa_description", ], deps = [ ":detail_urdf_parser", diff --git a/multibody/parsing/test/process_model_directives_test/flattened.dmd.yaml b/multibody/parsing/test/process_model_directives_test/flattened.dmd.yaml index ec4b5009d542..3edc65ac412e 100644 --- a/multibody/parsing/test/process_model_directives_test/flattened.dmd.yaml +++ b/multibody/parsing/test/process_model_directives_test/flattened.dmd.yaml @@ -4,7 +4,7 @@ directives: name: right - add_model: name: right::panda - file: package://drake/manipulation/models/franka_description/urdf/panda_arm.urdf + file: package://drake_models/franka_description/urdf/panda_arm.urdf - add_collision_filter_group: name: panda_wrist_filter_group model_namespace: right @@ -24,7 +24,7 @@ directives: name: left - add_model: name: left::panda - file: package://drake/manipulation/models/franka_description/urdf/panda_arm.urdf + file: package://drake_models/franka_description/urdf/panda_arm.urdf - add_collision_filter_group: name: panda_wrist_filter_group model_namespace: left diff --git a/multibody/parsing/test/process_model_directives_test/unflattened_arm.dmd.yaml b/multibody/parsing/test/process_model_directives_test/unflattened_arm.dmd.yaml index acd71baf446c..7e414e4ef79b 100644 --- a/multibody/parsing/test/process_model_directives_test/unflattened_arm.dmd.yaml +++ b/multibody/parsing/test/process_model_directives_test/unflattened_arm.dmd.yaml @@ -7,7 +7,7 @@ directives: - add_model: name: panda - file: package://drake/manipulation/models/franka_description/urdf/panda_arm.urdf + file: package://drake_models/franka_description/urdf/panda_arm.urdf - add_collision_filter_group: name: panda_wrist_filter_group members: diff --git a/multibody/plant/BUILD.bazel b/multibody/plant/BUILD.bazel index 1407162cadbc..e5a60dc277b6 100644 --- a/multibody/plant/BUILD.bazel +++ b/multibody/plant/BUILD.bazel @@ -473,14 +473,13 @@ drake_cc_library( drake_cc_googletest( name = "actuated_models_test", data = [ - "//manipulation/models/iiwa_description:models", - "//manipulation/models/wsg_50_description:models", "//multibody:models", "//multibody/benchmarks/acrobot:models", + "@drake_models//:iiwa_description", + "@drake_models//:wsg_50_description", ], deps = [ ":plant", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//common/test_utilities:expect_throws_message", "//multibody/parsing", @@ -503,7 +502,6 @@ drake_cc_googletest( ":compliant_contact_manager_tester", ":plant", ":spheres_stack", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//common/test_utilities:expect_throws_message", "//multibody/parsing", @@ -565,13 +563,12 @@ drake_cc_googletest( drake_cc_googletest( name = "sap_driver_joint_limits_test", data = [ - "//manipulation/models/iiwa_description:models", - "//manipulation/models/wsg_50_description:models", + "@drake_models//:iiwa_description", + "@drake_models//:wsg_50_description", ], deps = [ ":compliant_contact_manager_tester", ":plant", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//multibody/parsing", ], @@ -600,7 +597,6 @@ drake_cc_googletest( ], deps = [ ":hydroelastic_traction", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//math:autodiff", "//math:gradient", @@ -629,11 +625,10 @@ drake_cc_googletest( drake_cc_googletest( name = "applied_generalized_force_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":plant", - "//common:find_resource", "//multibody/parsing", "//systems/controllers:inverse_dynamics_controller", ], @@ -646,7 +641,6 @@ drake_cc_googletest( ], deps = [ ":plant", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//multibody/parsing", "//systems/primitives:constant_vector_source", @@ -664,11 +658,10 @@ drake_cc_googletest( drake_cc_googletest( name = "gravity_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":plant", - "//common:find_resource", "//common/test_utilities:expect_throws_message", "//multibody/parsing", ], @@ -680,16 +673,15 @@ drake_cc_googletest( "test/split_pendulum.sdf", "//examples/kuka_iiwa_arm/models", "//examples/simple_gripper:simple_gripper_models", - "//manipulation/models/iiwa_description:models", - "//manipulation/models/wsg_50_description:models", "//multibody/benchmarks/acrobot:models", "//multibody/benchmarks/free_body:models", "//multibody/parsing:test_models", + "@drake_models//:iiwa_description", + "@drake_models//:wsg_50_description", ], deps = [ ":plant", "//common:autodiff", - "//common:find_resource", "//common/test_utilities", "//common/test_utilities:limit_malloc", "//geometry/test_utilities", @@ -714,7 +706,6 @@ drake_cc_googletest( ], deps = [ ":plant", - "//common:find_resource", "//common/test_utilities:expect_throws_message", "//multibody/parsing", ], @@ -748,7 +739,6 @@ drake_cc_googletest( ], deps = [ ":plant", - "//common:find_resource", "//common/test_utilities:expect_no_throw", "//math:geometric_transform", "//multibody/parsing", @@ -771,13 +761,12 @@ drake_cc_library( hdrs = ["test/kuka_iiwa_model_tests.h"], data = [ "//examples/kuka_iiwa_arm/models", - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], visibility = ["//visibility:private"], deps = [ ":plant", "//common:autodiff", - "//common:find_resource", "//math:geometric_transform", "//multibody/parsing", ], @@ -818,13 +807,12 @@ drake_cc_googletest( name = "multibody_plant_jacobians_test", data = [ "//examples/kuka_iiwa_arm/models", - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":kuka_iiwa_model_tests", ":plant", "//common:autodiff", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//math:geometric_transform", "//math:gradient", @@ -836,13 +824,12 @@ drake_cc_googletest( name = "multibody_plant_mass_matrix_test", data = [ "test/atlas_with_fixed_joints.urdf", - "//manipulation/models/iiwa_description:models", - "//manipulation/models/wsg_50_description:models", "@drake_models//:atlas", + "@drake_models//:iiwa_description", + "@drake_models//:wsg_50_description", ], deps = [ ":plant", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//common/test_utilities:limit_malloc", "//multibody/parsing", @@ -852,12 +839,11 @@ drake_cc_googletest( drake_cc_googletest( name = "multibody_plant_reflected_inertia_test", data = [ - "//manipulation/models/iiwa_description:models", - "//manipulation/models/wsg_50_description:models", + "@drake_models//:iiwa_description", + "@drake_models//:wsg_50_description", ], deps = [ ":plant", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//multibody/parsing", ], @@ -924,7 +910,6 @@ drake_cc_googletest( data = ["test/box.sdf"], deps = [ ":plant", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//multibody/parsing", "//systems/analysis:implicit_euler_integrator", @@ -1123,12 +1108,11 @@ drake_cc_googletest( name = "joint_limits_test", timeout = "long", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], shard_count = 3, deps = [ ":plant", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//multibody/parsing", "//systems/analysis:simulator", @@ -1269,13 +1253,12 @@ drake_cc_googletest( drake_cc_googletest( name = "sap_driver_pd_controller_constraints_test", data = [ - "//manipulation/models/iiwa_description:models", - "//manipulation/models/wsg_50_description:models", + "@drake_models//:iiwa_description", + "@drake_models//:wsg_50_description", ], deps = [ ":compliant_contact_manager_tester", ":plant", - "//common:find_resource", "//multibody/parsing", ], ) diff --git a/multibody/plant/multibody_plant.h b/multibody/plant/multibody_plant.h index 20d5340e21d8..2a5459c44d77 100644 --- a/multibody/plant/multibody_plant.h +++ b/multibody/plant/multibody_plant.h @@ -529,10 +529,9 @@ files. Consider the example below which loads an acrobot model: MultibodyPlant acrobot; SceneGraph scene_graph; Parser parser(&acrobot, &scene_graph); - const std::string relative_name = - "drake/multibody/benchmarks/acrobot/acrobot.sdf"; - const std::string full_name = FindResourceOrThrow(relative_name); - parser.AddModels(full_name); + const std::string url = + "package://drake/multibody/benchmarks/acrobot/acrobot.sdf"; + parser.AddModelsFromUrl(url); @endcode As in the example above, for models including visual geometry, collision geometry or both, the user must specify a SceneGraph for geometry handling. diff --git a/multibody/plant/test/actuated_models_test.cc b/multibody/plant/test/actuated_models_test.cc index 6c93411d3319..bac530056742 100644 --- a/multibody/plant/test/actuated_models_test.cc +++ b/multibody/plant/test/actuated_models_test.cc @@ -5,7 +5,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/common/test_utilities/expect_throws_message.h" #include "drake/multibody/parsing/parser.h" @@ -64,12 +63,10 @@ class ActuatedIiiwaArmTest : public ::testing::Test { ModelConfiguration model_config = ModelConfiguration::kArmIsNotControlled, const MultibodyPlantConfig& config = MultibodyPlantConfig{ .time_step = 0.01, .discrete_contact_approximation = "sap"}) { - const char kArmSdfPath[] = - "drake/manipulation/models/iiwa_description/iiwa7/" - "iiwa7_no_collision.sdf"; - - const char kWsg50SdfPath[] = - "drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"; + const char kArmSdfUrl[] = + "package://drake_models/iiwa_description/sdf/iiwa7_no_collision.sdf"; + const char kWsg50SdfUrl[] = + "package://drake_models/wsg_50_description/sdf/schunk_wsg_50.sdf"; // Make a discrete model. plant_ = std::make_unique>(config.time_step); @@ -78,20 +75,21 @@ class ActuatedIiiwaArmTest : public ::testing::Test { Parser parser(plant_.get()); // Add the arm. - arm_model_ = parser.AddModels(FindResourceOrThrow(kArmSdfPath)).at(0); + arm_model_ = parser.AddModelsFromUrl(kArmSdfUrl).at(0); // A model of an underactuated robot. - acrobot_model_ = parser - .AddModels(FindResourceOrThrow( - "drake/multibody/benchmarks/acrobot/acrobot.sdf")) - .at(0); + acrobot_model_ = + parser + .AddModelsFromUrl( + "package://drake/multibody/benchmarks/acrobot/acrobot.sdf") + .at(0); // Add the gripper. - gripper_model_ = parser.AddModels(FindResourceOrThrow(kWsg50SdfPath)).at(0); + gripper_model_ = parser.AddModelsFromUrl(kWsg50SdfUrl).at(0); // A model of a (non-actuated) plate. box_model_ = - parser.AddModels(FindResourceOrThrow("drake/multibody/models/box.urdf")) + parser.AddModelsFromUrl("package://drake/multibody/models/box.urdf") .at(0); const auto& base_body = plant_->GetBodyByName("iiwa_link_0", arm_model_); diff --git a/multibody/plant/test/applied_generalized_force_test.cc b/multibody/plant/test/applied_generalized_force_test.cc index 88d8fdd6199d..248892ba1eb9 100644 --- a/multibody/plant/test/applied_generalized_force_test.cc +++ b/multibody/plant/test/applied_generalized_force_test.cc @@ -4,7 +4,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/multibody/parsing/parser.h" #include "drake/multibody/plant/multibody_plant.h" #include "drake/multibody/tree/rigid_body.h" @@ -29,16 +28,15 @@ class MultibodyPlantGeneralizedAppliedForceTest public: void SetUp() override { // Load two Iiwa models. - const std::string full_name = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"); + const std::string url = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; systems::DiagramBuilder builder; const double dt = GetParam(); plant_ = builder.AddSystem>(dt); // Add the model twice. - auto iiwa1 = Parser(plant_, "iiwa1").AddModels(full_name).at(0); - auto iiwa2 = Parser(plant_, "iiwa2").AddModels(full_name).at(0); + auto iiwa1 = Parser(plant_, "iiwa1").AddModelsFromUrl(url).at(0); + auto iiwa2 = Parser(plant_, "iiwa2").AddModelsFromUrl(url).at(0); plant_->WeldFrames(plant_->world_frame(), plant_->GetFrameByName("iiwa_link_0", iiwa1)); plant_->WeldFrames(plant_->world_frame(), diff --git a/multibody/plant/test/box_test.cc b/multibody/plant/test/box_test.cc index a29ffb568360..c9dceab33872 100644 --- a/multibody/plant/test/box_test.cc +++ b/multibody/plant/test/box_test.cc @@ -3,7 +3,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/geometry/scene_graph.h" #include "drake/multibody/parsing/parser.h" @@ -162,12 +161,11 @@ class SlidingBoxTest : public ::testing::Test { // (discrete_period = 0 for a continuous model). std::unique_ptr> MakeBoxDiagram(double time_step) { DiagramBuilder builder; - const std::string full_name = - FindResourceOrThrow("drake/multibody/plant/test/box.sdf"); MultibodyPlant& plant = AddMultibodyPlantSceneGraph( &builder, std::make_unique>(time_step)); plant.set_name("plant"); - Parser(&plant).AddModels(full_name); + Parser(&plant).AddModelsFromUrl( + "package://drake/multibody/plant/test/box.sdf"); // Add gravity to the model. plant.mutable_gravity_field().set_gravity_vector(-g_ * diff --git a/multibody/plant/test/compliant_contact_manager_test.cc b/multibody/plant/test/compliant_contact_manager_test.cc index 6f0b86048b92..61faad1aff57 100644 --- a/multibody/plant/test/compliant_contact_manager_test.cc +++ b/multibody/plant/test/compliant_contact_manager_test.cc @@ -5,7 +5,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/common/test_utilities/expect_throws_message.h" #include "drake/geometry/proximity/volume_mesh_field.h" diff --git a/multibody/plant/test/externally_applied_spatial_force_test.cc b/multibody/plant/test/externally_applied_spatial_force_test.cc index 889137e94a29..386b01f97b30 100644 --- a/multibody/plant/test/externally_applied_spatial_force_test.cc +++ b/multibody/plant/test/externally_applied_spatial_force_test.cc @@ -6,7 +6,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/math/rigid_transform.h" #include "drake/multibody/parsing/parser.h" @@ -111,11 +110,10 @@ class ExternallyAppliedForcesTest : public ::testing::Test { protected: void MakePlantWithGravityCompensator(double time_step) { // Load the acrobot model. - const std::string full_name = - FindResourceOrThrow("drake/multibody/benchmarks/acrobot/acrobot.sdf"); systems::DiagramBuilder builder; plant_ = builder.AddSystem>(time_step); - Parser(plant_).AddModels(full_name); + Parser(plant_).AddModelsFromUrl( + "package://drake/multibody/benchmarks/acrobot/acrobot.sdf"); plant_->Finalize(); // Add the system that applies inverse gravitational forces to the link diff --git a/multibody/plant/test/gravity_test.cc b/multibody/plant/test/gravity_test.cc index e489f78baf40..deee0f7eb59e 100644 --- a/multibody/plant/test/gravity_test.cc +++ b/multibody/plant/test/gravity_test.cc @@ -2,7 +2,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/expect_throws_message.h" #include "drake/multibody/parsing/parser.h" #include "drake/multibody/plant/multibody_plant.h" @@ -22,14 +21,13 @@ class MultibodyPlantGravityForceTest : public ::testing::Test { public: void SetUp() override { // Load two Iiwa models. - const std::string full_name = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"); + const std::string url = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; plant_ = std::make_unique>(0.0); // Add the model twice. - iiwa1_ = Parser(plant_.get(), "iiwa1").AddModels(full_name).at(0); - iiwa2_ = Parser(plant_.get(), "iiwa2").AddModels(full_name).at(0); + iiwa1_ = Parser(plant_.get(), "iiwa1").AddModelsFromUrl(url).at(0); + iiwa2_ = Parser(plant_.get(), "iiwa2").AddModelsFromUrl(url).at(0); plant_->WeldFrames(plant_->world_frame(), plant_->GetFrameByName("iiwa_link_0", iiwa1_)); plant_->WeldFrames(plant_->world_frame(), diff --git a/multibody/plant/test/hydroelastic_traction_test.cc b/multibody/plant/test/hydroelastic_traction_test.cc index 4ff35164ec08..88533efbb315 100644 --- a/multibody/plant/test/hydroelastic_traction_test.cc +++ b/multibody/plant/test/hydroelastic_traction_test.cc @@ -4,7 +4,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/geometry/proximity/polygon_surface_mesh.h" #include "drake/geometry/proximity/triangle_surface_mesh.h" @@ -335,9 +334,9 @@ class MultibodyPlantHydroelasticTractionTests SceneGraph* scene_graph; std::tie(plant_, scene_graph) = AddMultibodyPlantSceneGraph(&builder, 0.0); MultibodyPlant& plant = *plant_; - const std::string full_name = FindResourceOrThrow( - "drake/multibody/plant/test/block_on_halfspace.sdf"); - Parser(&plant, scene_graph).AddModels(full_name); + Parser(&plant, scene_graph) + .AddModelsFromUrl( + "package://drake/multibody/plant/test/block_on_halfspace.sdf"); plant.Finalize(); diagram_ = builder.Build(); diff --git a/multibody/plant/test/internal_geometry_names_test.cc b/multibody/plant/test/internal_geometry_names_test.cc index 16f3f5ef3ac1..83c5e3c427d3 100644 --- a/multibody/plant/test/internal_geometry_names_test.cc +++ b/multibody/plant/test/internal_geometry_names_test.cc @@ -3,7 +3,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/multibody/parsing/parser.h" namespace drake { diff --git a/multibody/plant/test/joint_limits_test.cc b/multibody/plant/test/joint_limits_test.cc index 59bab7b47df2..eeff6d43ef1d 100644 --- a/multibody/plant/test/joint_limits_test.cc +++ b/multibody/plant/test/joint_limits_test.cc @@ -3,7 +3,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/multibody/parsing/parser.h" #include "drake/multibody/plant/multibody_plant.h" @@ -22,8 +21,8 @@ using systems::Simulator; namespace multibody { namespace { -const char kIiwaFilePath[] = - "drake/manipulation/models/iiwa_description/sdf/iiwa14_no_collision.sdf"; +const char kIiwaUrl[] = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; // These unit tests verify the convergence of the joint limits as the time step // is decreased. A constant force is applied at the joint to drive its state to @@ -230,7 +229,7 @@ GTEST_TEST(JointLimitsTest, KukaArm) { const double kRelativePositionTolerance = 0.055; MultibodyPlant plant(time_step); - Parser(&plant).AddModels(FindResourceOrThrow(kIiwaFilePath)); + Parser(&plant).AddModelsFromUrl(kIiwaUrl); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("iiwa_link_0")); plant.mutable_gravity_field().set_gravity_vector(Vector3::Zero()); SetReflectedInertiaToZero(&plant); @@ -303,7 +302,7 @@ GTEST_TEST(JointLimitsTest, KukaArm) { GTEST_TEST(JointLimitsTest, KukaArmFloating) { // Check limits for a model with a floating base. MultibodyPlant plant(0.0); - Parser(&plant).AddModels(FindResourceOrThrow(kIiwaFilePath)); + Parser(&plant).AddModelsFromUrl(kIiwaUrl); plant.Finalize(); const int nq = 14; const int nq_floating = 7; @@ -326,7 +325,7 @@ GTEST_TEST(JointLimitsTest, KukaArmFloating) { // for a continuous plant. This is merely to confirm that nothing crashes. GTEST_TEST(JointLimitsTest, ContinuousLimitsDoNotFault) { MultibodyPlant plant(0.0); - Parser(&plant).AddModels(FindResourceOrThrow(kIiwaFilePath)); + Parser(&plant).AddModelsFromUrl(kIiwaUrl); plant.Finalize(); auto context = plant.CreateDefaultContext(); plant.get_actuation_input_port().FixValue(context.get(), diff --git a/multibody/plant/test/kuka_iiwa_model_tests.h b/multibody/plant/test/kuka_iiwa_model_tests.h index a4a56bcd03e9..a4389f2d8c1c 100644 --- a/multibody/plant/test/kuka_iiwa_model_tests.h +++ b/multibody/plant/test/kuka_iiwa_model_tests.h @@ -8,7 +8,6 @@ #include #include "drake/common/autodiff.h" -#include "drake/common/find_resource.h" #include "drake/math/rigid_transform.h" #include "drake/math/roll_pitch_yaw.h" #include "drake/math/rotation_matrix.h" @@ -34,17 +33,14 @@ class KukaIiwaModelTests : public ::testing::Test { public: // Creates MultibodyTree for a KUKA Iiwa robot arm. void SetUp() override { - const std::string kArmSdfPath = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"); - // Create a model of a Kuka arm. Notice we do not weld the robot's base to // the world and therefore the model is free floating in space. This makes // for a more interesting setup to test the computation of Jacobians with // respect to q̇ (time-derivative of generalized positions). plant_ = std::make_unique>(0.0); Parser parser(plant_.get()); - parser.AddModels(kArmSdfPath); + parser.AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"); // Add a frame H with a fixed pose X_EH in the end effector frame E. end_effector_link_ = &plant_->GetBodyByName("iiwa_link_7"); frame_H_ = &plant_->AddFrame(std::make_unique>( diff --git a/multibody/plant/test/multibody_plant_forward_dynamics_test.cc b/multibody/plant/test/multibody_plant_forward_dynamics_test.cc index a2dedcd81a43..112a572a49d0 100644 --- a/multibody/plant/test/multibody_plant_forward_dynamics_test.cc +++ b/multibody/plant/test/multibody_plant_forward_dynamics_test.cc @@ -242,11 +242,9 @@ GTEST_TEST(WeldedBoxesTest, ForwardDynamicsViaArticulatedBodyAlgorithm) { std::unique_ptr> MakeLinearizedCartPole( double time_step) { - const std::string sdf_file = - FindResourceOrThrow("drake/examples/multibody/cart_pole/cart_pole.sdf"); - MultibodyPlant plant(time_step); - Parser(&plant).AddModels(sdf_file); + Parser(&plant).AddModelsFromUrl( + "package://drake/examples/multibody/cart_pole/cart_pole.sdf"); plant.Finalize(); auto context = plant.CreateDefaultContext(); diff --git a/multibody/plant/test/multibody_plant_introspection_test.cc b/multibody/plant/test/multibody_plant_introspection_test.cc index d2ebc926aee1..77fbbdd0d450 100644 --- a/multibody/plant/test/multibody_plant_introspection_test.cc +++ b/multibody/plant/test/multibody_plant_introspection_test.cc @@ -8,7 +8,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/expect_throws_message.h" #include "drake/multibody/parsing/parser.h" #include "drake/multibody/plant/multibody_plant.h" @@ -32,19 +31,19 @@ GTEST_TEST(MultibodyPlantIntrospection, FloatingBodies) { const std::string atlas_url = "package://drake_models/atlas/atlas_convex_hull.urdf"; - const std::string table_sdf_path = FindResourceOrThrow( - "drake/examples/kuka_iiwa_arm/models/table/" - "extra_heavy_duty_table_surface_only_collision.sdf"); + const std::string table_url = + "package://drake/examples/kuka_iiwa_arm/models/table/" + "extra_heavy_duty_table_surface_only_collision.sdf"; - const std::string mug_sdf_path = - FindResourceOrThrow("drake/examples/simple_gripper/simple_mug.sdf"); + const std::string mug_url = + "package://drake/examples/simple_gripper/simple_mug.sdf"; MultibodyPlant plant(0.0); // Load a model of a table for the environment around the robot. Parser parser(&plant); const ModelInstanceIndex robot_table_model = - parser.AddModels(table_sdf_path).at(0); + parser.AddModelsFromUrl(table_url).at(0); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link", robot_table_model)); @@ -59,7 +58,7 @@ GTEST_TEST(MultibodyPlantIntrospection, FloatingBodies) { plant.GetBodyByName("pelvis", atlas_model2); // Add a floating mug. - const ModelInstanceIndex mug_model = parser.AddModels(mug_sdf_path).at(0); + const ModelInstanceIndex mug_model = parser.AddModelsFromUrl(mug_url).at(0); const RigidBody& mug = plant.GetBodyByName("simple_mug", mug_model); // Introspection of the underlying mathematical model is not available until diff --git a/multibody/plant/test/multibody_plant_jacobians_test.cc b/multibody/plant/test/multibody_plant_jacobians_test.cc index bdc1254032dd..1984879a9831 100644 --- a/multibody/plant/test/multibody_plant_jacobians_test.cc +++ b/multibody/plant/test/multibody_plant_jacobians_test.cc @@ -5,7 +5,6 @@ #include #include "drake/common/autodiff.h" -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/math/autodiff_gradient.h" #include "drake/math/rigid_transform.h" diff --git a/multibody/plant/test/multibody_plant_mass_matrix_test.cc b/multibody/plant/test/multibody_plant_mass_matrix_test.cc index c412b9d9ecae..73b777b0a6b1 100644 --- a/multibody/plant/test/multibody_plant_mass_matrix_test.cc +++ b/multibody/plant/test/multibody_plant_mass_matrix_test.cc @@ -4,7 +4,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/common/test_utilities/limit_malloc.h" #include "drake/multibody/parsing/parser.h" @@ -29,13 +28,6 @@ namespace { // column of the mass matrix at a time. class MultibodyPlantMassMatrixTests : public ::testing::Test { public: - void LoadModel(const std::string& file_path) { - const std::string model_path = FindResourceOrThrow(file_path); - Parser parser(&plant_); - parser.AddModels(model_path); - plant_.Finalize(); - } - void LoadUrl(const std::string& url) { Parser parser(&plant_); parser.AddModelsFromUrl(url); @@ -43,20 +35,18 @@ class MultibodyPlantMassMatrixTests : public ::testing::Test { } void LoadIiwaWithGripper() { - const char kArmSdfPath[] = - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"; - - const char kWsg50SdfPath[] = - "drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"; + const char kArmSdfUrl[] = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; + const char kWsg50SdfUrl[] = + "package://drake_models/wsg_50_description/sdf/schunk_wsg_50.sdf"; Parser parser(&plant_); const ModelInstanceIndex arm_model = - parser.AddModels(FindResourceOrThrow(kArmSdfPath)).at(0); + parser.AddModelsFromUrl(kArmSdfUrl).at(0); // Add the gripper. const ModelInstanceIndex gripper_model = - parser.AddModels(FindResourceOrThrow(kWsg50SdfPath)).at(0); + parser.AddModelsFromUrl(kWsg50SdfUrl).at(0); const auto& base_body = plant_.GetBodyByName("iiwa_link_0", arm_model); const auto& end_effector = plant_.GetBodyByName("iiwa_link_7", arm_model); @@ -98,8 +88,8 @@ class MultibodyPlantMassMatrixTests : public ::testing::Test { }; TEST_F(MultibodyPlantMassMatrixTests, IiwaRobot) { - LoadModel( - "drake/manipulation/models/iiwa_description/sdf/iiwa14_no_collision.sdf"); + LoadUrl( + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"); // We did not weld the arm to the world, therefore we expect it to be free. EXPECT_EQ(plant_.num_velocities(), 13); @@ -139,7 +129,7 @@ TEST_F(MultibodyPlantMassMatrixTests, AtlasRobot) { TEST_F(MultibodyPlantMassMatrixTests, AtlasRobotWithFixedJoints) { // TODO(sherm1) Replace this large copied file with the original Atlas urdf // plus a patch or in-memory edit (issue #13954). - LoadModel("drake/multibody/plant/test/atlas_with_fixed_joints.urdf"); + LoadUrl("package://drake/multibody/plant/test/atlas_with_fixed_joints.urdf"); // Create a context and store an arbitrary configuration. std::unique_ptr> context = plant_.CreateDefaultContext(); diff --git a/multibody/plant/test/multibody_plant_reflected_inertia_test.cc b/multibody/plant/test/multibody_plant_reflected_inertia_test.cc index 51af99118a56..32bb3f332908 100644 --- a/multibody/plant/test/multibody_plant_reflected_inertia_test.cc +++ b/multibody/plant/test/multibody_plant_reflected_inertia_test.cc @@ -4,7 +4,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/multibody/parsing/parser.h" #include "drake/multibody/plant/multibody_plant.h" @@ -113,18 +112,16 @@ class MultibodyPlantReflectedInertiaTests : public ::testing::Test { private: void LoadIiwaWithGripper(MultibodyPlant* plant) { DRAKE_DEMAND(plant != nullptr); - const char kArmSdfPath[] = - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"; - - const char kWsg50SdfPath[] = - "drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"; + const char kArmSdfUrl[] = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; + const char kWsg50SdfUrl[] = + "package://drake_models/wsg_50_description/sdf/schunk_wsg_50.sdf"; Parser parser(plant); - arm_model = parser.AddModels(FindResourceOrThrow(kArmSdfPath)).at(0); + arm_model = parser.AddModelsFromUrl(kArmSdfUrl).at(0); // Add the gripper. - gripper_model = parser.AddModels(FindResourceOrThrow(kWsg50SdfPath)).at(0); + gripper_model = parser.AddModelsFromUrl(kWsg50SdfUrl).at(0); const auto& base_body = plant->GetBodyByName("iiwa_link_0", arm_model); const auto& end_effector = plant->GetBodyByName("iiwa_link_7", arm_model); diff --git a/multibody/plant/test/multibody_plant_tamsi_test.cc b/multibody/plant/test/multibody_plant_tamsi_test.cc index 55e94959d442..0afc7139747c 100644 --- a/multibody/plant/test/multibody_plant_tamsi_test.cc +++ b/multibody/plant/test/multibody_plant_tamsi_test.cc @@ -3,7 +3,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/expect_no_throw.h" #include "drake/math/rigid_transform.h" #include "drake/math/rotation_matrix.h" diff --git a/multibody/plant/test/multibody_plant_test.cc b/multibody/plant/test/multibody_plant_test.cc index 429b1083e633..360b4e3be986 100644 --- a/multibody/plant/test/multibody_plant_test.cc +++ b/multibody/plant/test/multibody_plant_test.cc @@ -11,7 +11,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/common/nice_type_name.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/common/test_utilities/expect_no_throw.h" @@ -140,8 +139,8 @@ GTEST_TEST(MultibodyPlant, SimpleModelCreation) { // Add a split pendulum to the plant. const ModelInstanceIndex pendulum_model_instance = Parser(plant.get()) - .AddModels(FindResourceOrThrow( - "drake/multibody/plant/test/split_pendulum.sdf")) + .AddModelsFromUrl( + "package://drake/multibody/plant/test/split_pendulum.sdf") .at(0); EXPECT_EQ(plant->num_model_instances(), 3); @@ -441,14 +440,13 @@ GTEST_TEST(MultibodyPlantTest, AddMultibodyPlantSceneGraph) { // historical reason). GTEST_TEST(MultibodyPlantTest, NoHeapAllocOnStringQueries) { // Construct a plant with an Iiwa. - const char kSdfPath[] = - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"; + const char kSdfUrl[] = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; auto plant = std::make_unique>(0 /* plant type irrelevant */); Parser parser(plant.get()); multibody::ModelInstanceIndex iiwa_instance = - parser.AddModels(FindResourceOrThrow(kSdfPath)).at(0); + parser.AddModelsFromUrl(kSdfUrl).at(0); plant->Finalize(); // Use string to ensure that there is no heap allocation in the implicit @@ -561,13 +559,14 @@ GTEST_TEST(ActuationPortsTest, CheckActuation) { // Create a MultibodyPlant consisting of two model instances, one actuated // and the other unactuated. MultibodyPlant plant(0.0); - const std::string acrobot_path = - FindResourceOrThrow("drake/multibody/benchmarks/acrobot/acrobot.sdf"); - const std::string cylinder_path = FindResourceOrThrow( - "drake/multibody/benchmarks/free_body/uniform_solid_cylinder.urdf"); + const std::string acrobot_url = + "package://drake/multibody/benchmarks/acrobot/acrobot.sdf"; + const std::string cylinder_url = + "package://drake/multibody/benchmarks/free_body/" + "uniform_solid_cylinder.urdf"; Parser parser(&plant); - auto acrobot_instance = parser.AddModels(acrobot_path).at(0); - auto cylinder_instance = parser.AddModels(cylinder_path).at(0); + auto acrobot_instance = parser.AddModelsFromUrl(acrobot_url).at(0); + auto cylinder_instance = parser.AddModelsFromUrl(cylinder_url).at(0); plant.Finalize(); // Verify the number of actuators. @@ -650,10 +649,10 @@ class AcrobotPlantTests : public ::testing::Test { systems::DiagramBuilder builder; // Make a non-finalized plant so that we can tests methods with pre/post // Finalize() conditions. - const std::string full_name = - FindResourceOrThrow("drake/multibody/benchmarks/acrobot/acrobot.sdf"); + const std::string url = + "package://drake/multibody/benchmarks/acrobot/acrobot.sdf"; std::tie(plant_, scene_graph_) = AddMultibodyPlantSceneGraph(&builder, 0.0); - Parser(plant_).AddModels(full_name); + Parser(plant_).AddModelsFromUrl(url); // Sanity check on the availability of the optional source id before using // it. DRAKE_DEMAND(plant_->get_source_id() != std::nullopt); @@ -700,10 +699,10 @@ class AcrobotPlantTests : public ::testing::Test { void SetUpDiscreteAcrobotPlant(double time_step) { systems::DiagramBuilder builder; - const std::string full_name = - FindResourceOrThrow("drake/multibody/benchmarks/acrobot/acrobot.sdf"); + const std::string url = + "package://drake/multibody/benchmarks/acrobot/acrobot.sdf"; discrete_plant_ = std::make_unique>(time_step); - Parser(discrete_plant_.get()).AddModels(full_name); + Parser(discrete_plant_.get()).AddModelsFromUrl(url); discrete_plant_->Finalize(); discrete_context_ = discrete_plant_->CreateDefaultContext(); @@ -1177,13 +1176,14 @@ TEST_F(AcrobotPlantTests, ContextClone) { GTEST_TEST(MultibodyPlantTest, Graphviz) { MultibodyPlant plant(0.0); - const std::string acrobot_path = - FindResourceOrThrow("drake/multibody/benchmarks/acrobot/acrobot.sdf"); - const std::string cylinder_path = FindResourceOrThrow( - "drake/multibody/benchmarks/free_body/uniform_solid_cylinder.urdf"); - Parser(&plant).AddModels(acrobot_path); - Parser(&plant).AddModels(cylinder_path); - Parser(&plant, "cylinder2").AddModels(cylinder_path); + const std::string acrobot_url = + "package://drake/multibody/benchmarks/acrobot/acrobot.sdf"; + const std::string cylinder_url = + "package://drake/multibody/benchmarks/free_body/" + "uniform_solid_cylinder.urdf"; + Parser(&plant).AddModelsFromUrl(acrobot_url); + Parser(&plant).AddModelsFromUrl(cylinder_url); + Parser(&plant, "cylinder2").AddModelsFromUrl(cylinder_url); plant.set_name("MyTestMBP"); const std::string dot = std::regex_replace(plant.GetTopologyGraphvizString(), @@ -1612,10 +1612,10 @@ GTEST_TEST(MultibodyPlantTest, GetBodiesWeldedTo) { using ::testing::UnorderedElementsAre; // This test expects that the following model has a world body and a pair of // welded-together bodies. - const std::string sdf_file = - FindResourceOrThrow("drake/multibody/plant/test/split_pendulum.sdf"); + const std::string sdf_url = + "package://drake/multibody/plant/test/split_pendulum.sdf"; MultibodyPlant plant(0.0); - Parser(&plant).AddModels(sdf_file); + Parser(&plant).AddModelsFromUrl(sdf_url); const RigidBody& upper = plant.GetBodyByName("upper_section"); const RigidBody& lower = plant.GetBodyByName("lower_section"); @@ -1658,10 +1658,10 @@ GTEST_TEST(MultibodyPlantTest, GetBodiesWeldedTo) { GTEST_TEST(MultibodyPlantTest, GetBodiesKinematicallyAffectedBy) { // This test expects that the following model has a world body and a pair of // welded-together bodies. - const std::string sdf_file = - FindResourceOrThrow("drake/multibody/plant/test/split_pendulum.sdf"); + const std::string sdf_url = + "package://drake/multibody/plant/test/split_pendulum.sdf"; MultibodyPlant plant(0.0); - Parser(&plant).AddModels(sdf_file); + Parser(&plant).AddModelsFromUrl(sdf_url); const RigidBody& upper = plant.GetBodyByName("upper_section"); const RigidBody& lower = plant.GetBodyByName("lower_section"); const JointIndex shoulder = plant.GetJointByName("pin").index(); @@ -1697,10 +1697,10 @@ GTEST_TEST(MultibodyPlantTest, GetBodiesKinematicallyAffectedBy) { GTEST_TEST(MultibodyPlantTest, ReversedWeldError) { // This test expects that the following model has a world body and a pair of // welded-together bodies. - const std::string sdf_file = - FindResourceOrThrow("drake/multibody/plant/test/split_pendulum.sdf"); + const std::string sdf_url = + "package://drake/multibody/plant/test/split_pendulum.sdf"; MultibodyPlant plant(0.0); - Parser(&plant).AddModels(sdf_file); + Parser(&plant).AddModelsFromUrl(sdf_url); // Add a new body, and weld it in the wrong direction using `WeldFrames`. const RigidBody& extra = plant.AddRigidBody( @@ -2265,9 +2265,8 @@ class SplitPendulum : public ::testing::Test { public: void SetUp() override { // Make the cart_pole model. - const std::string full_name = - FindResourceOrThrow("drake/multibody/plant/test/split_pendulum.sdf"); - Parser(&plant_).AddModels(full_name); + Parser(&plant_).AddModelsFromUrl( + "package://drake/multibody/plant/test/split_pendulum.sdf"); plant_.Finalize(); // Get pin joint so that we can set the state. @@ -2333,12 +2332,12 @@ TEST_F(SplitPendulum, GetMultibodyPlantFromElement) { // Verifies we can parse link collision geometries and surface friction. GTEST_TEST(MultibodyPlantTest, ScalarConversionConstructor) { - const std::string full_name = drake::FindResourceOrThrow( - "drake/multibody/parsing/test/" - "links_with_visuals_and_collisions.sdf"); MultibodyPlant plant(0.0); SceneGraph scene_graph; - Parser(&plant, &scene_graph).AddModels(full_name); + Parser(&plant, &scene_graph) + .AddModelsFromUrl( + "package://drake/multibody/parsing/test/" + "links_with_visuals_and_collisions.sdf"); // Try scalar-converting pre-finalize - error. DRAKE_EXPECT_THROWS_MESSAGE(systems::System::ToAutoDiffXd(plant), @@ -2694,12 +2693,9 @@ class MultibodyPlantContactJacobianTests : public ::testing::Test { // in the world, joints, and their degrees of freedom, are numbered from root // (world) in increasing order towards the end effector. GTEST_TEST(KukaModel, JointIndexes) { - const char kSdfPath[] = - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"; - MultibodyPlant plant(0.0); - Parser(&plant).AddModels(FindResourceOrThrow(kSdfPath)); + Parser(&plant).AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"); const auto& base_link_frame = plant.GetFrameByName("iiwa_link_0"); const Joint& weld = plant.WeldFrames(plant.world_frame(), base_link_frame); @@ -2775,12 +2771,9 @@ GTEST_TEST(KukaModel, JointIndexes) { } GTEST_TEST(KukaModel, ActuationMatrix) { - const char kSdfPath[] = - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"; - MultibodyPlant plant(0.0); - Parser(&plant).AddModels(FindResourceOrThrow(kSdfPath)); + Parser(&plant).AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("iiwa_link_0")); plant.Finalize(); @@ -2805,11 +2798,11 @@ GTEST_TEST(KukaModel, ActuationMatrix) { class KukaArmTest : public ::testing::TestWithParam { protected: void SetUp() override { - const char kSdfPath[] = - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"; plant_ = std::make_unique>(this->GetParam()); - Parser(plant_.get()).AddModels(FindResourceOrThrow(kSdfPath)); + Parser(plant_.get()) + .AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/" + "iiwa14_no_collision.sdf"); const Joint& weld = plant_->WeldFrames( plant_->world_frame(), plant_->GetFrameByName("iiwa_link_0")); plant_->Finalize(); @@ -2912,16 +2905,14 @@ TEST_P(KukaArmTest, StateAccess) { TEST_P(KukaArmTest, InstanceStateAccess) { // Redo the setup process, now with two Iiwa's. - const char kSdfPath[] = - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"; + const char kSdfUrl[] = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; plant_ = std::make_unique>(this->GetParam()); Parser parser(plant_.get()); - const std::string sdf_resource = FindResourceOrThrow(kSdfPath); multibody::ModelInstanceIndex arm1 = - Parser(plant_.get(), "arm1").AddModels(sdf_resource).at(0); + Parser(plant_.get(), "arm1").AddModelsFromUrl(kSdfUrl).at(0); multibody::ModelInstanceIndex arm2 = - Parser(plant_.get(), "arm2").AddModels(sdf_resource).at(0); + Parser(plant_.get(), "arm2").AddModelsFromUrl(kSdfUrl).at(0); plant_->WeldFrames(plant_->world_frame(), plant_->GetFrameByName("iiwa_link_0", arm1)); plant_->WeldFrames(plant_->world_frame(), @@ -3066,10 +3057,9 @@ INSTANTIATE_TEST_SUITE_P(Blank, KukaArmTest, 1e-3 /* discrete state */)); GTEST_TEST(StateSelection, JointHasNoActuator) { - const std::string file_name = - "drake/multibody/benchmarks/acrobot/acrobot.sdf"; MultibodyPlant plant(0.0); - Parser(&plant).AddModels(FindResourceOrThrow(file_name)); + Parser(&plant).AddModelsFromUrl( + "package://drake/multibody/benchmarks/acrobot/acrobot.sdf"); plant.Finalize(); // Sanity checks. @@ -3087,12 +3077,10 @@ GTEST_TEST(StateSelection, JointHasNoActuator) { } GTEST_TEST(StateSelection, KukaWithSimpleGripper) { - const char kArmSdfPath[] = - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"; - - const char kWsg50SdfPath[] = - "drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"; + const char kArmSdfUrl[] = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; + const char kWsg50SdfUrl[] = + "package://drake_models/wsg_50_description/sdf/schunk_wsg_50.sdf"; // We make a "floating" model of a Kuka arm with a Schunk WSG 50 gripper at // the end effector. The purpose of having this floating model is to unit test @@ -3101,11 +3089,11 @@ GTEST_TEST(StateSelection, KukaWithSimpleGripper) { MultibodyPlant plant(0.0); Parser parser(&plant); const ModelInstanceIndex arm_model = - parser.AddModels(FindResourceOrThrow(kArmSdfPath)).at(0); + parser.AddModelsFromUrl(kArmSdfUrl).at(0); // Add the gripper. const ModelInstanceIndex gripper_model = - parser.AddModels(FindResourceOrThrow(kWsg50SdfPath)).at(0); + parser.AddModelsFromUrl(kWsg50SdfUrl).at(0); const auto& end_effector = plant.GetBodyByName("iiwa_link_7", arm_model); const auto& gripper_body = plant.GetBodyByName("body", gripper_model); // We don't care for the actual pose of the gripper in the end effector frame @@ -3322,29 +3310,29 @@ GTEST_TEST(StateSelection, KukaWithSimpleGripper) { // its origin located a the -x, -y corner of the objects table. With this setup, // we test we can set the pose X_OM of the mug frame M in the objects frame O. GTEST_TEST(StateSelection, FloatingBodies) { - const std::string iiwa_sdf_path = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"); + const std::string iiwa_sdf_url = + "package://drake_models/iiwa_description/sdf/" + "iiwa14_no_collision.sdf"; - const std::string table_sdf_path = FindResourceOrThrow( - "drake/examples/kuka_iiwa_arm/models/table/" - "extra_heavy_duty_table_surface_only_collision.sdf"); + const std::string table_sdf_url = + "package://drake/examples/kuka_iiwa_arm/models/table/" + "extra_heavy_duty_table_surface_only_collision.sdf"; - const std::string mug_sdf_path = - FindResourceOrThrow("drake/examples/simple_gripper/simple_mug.sdf"); + const std::string mug_sdf_url = + "package://drake/examples/simple_gripper/simple_mug.sdf"; MultibodyPlant plant(0.0); // Load a model of a table for the robot. Parser robot_parser(&plant, "robot"); const ModelInstanceIndex robot_table_model = - robot_parser.AddModels(table_sdf_path).at(0); + robot_parser.AddModelsFromUrl(table_sdf_url).at(0); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link", robot_table_model)); // Load the robot and weld it on top of the robot table. const ModelInstanceIndex arm_model = - robot_parser.AddModels(iiwa_sdf_path).at(0); + robot_parser.AddModelsFromUrl(iiwa_sdf_url).at(0); const double table_top_z_in_world = // table's top height @@ -3358,7 +3346,7 @@ GTEST_TEST(StateSelection, FloatingBodies) { // Load a second table for objects. Parser objects_parser(&plant, "objects"); const ModelInstanceIndex objects_table_model = - objects_parser.AddModels(table_sdf_path).at(0); + objects_parser.AddModelsFromUrl(table_sdf_url).at(0); const RigidTransformd X_WT(Vector3d(0.8, 0.0, 0.0)); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link", objects_table_model), X_WT); @@ -3372,7 +3360,7 @@ GTEST_TEST(StateSelection, FloatingBodies) { X_TO)); // Add a floating mug. - objects_parser.AddModels(mug_sdf_path); + objects_parser.AddModelsFromUrl(mug_sdf_url); const RigidBody& mug = plant.GetBodyByName("simple_mug"); plant.Finalize(); @@ -3526,10 +3514,10 @@ GTEST_TEST(SetRandomTest, SetDefaultWhenNoDistributionSpecified) { plant.AddRigidBody("free body 1", SpatialInertia::MakeUnitary()); plant.AddJoint("" + body1.name(), plant.world_body(), {}, body1, {}); - const std::string acrobot_file_name = - "drake/multibody/benchmarks/acrobot/acrobot.sdf"; + const std::string acrobot_url = + "package://drake/multibody/benchmarks/acrobot/acrobot.sdf"; const ModelInstanceIndex acrobot = - Parser(&plant).AddModels(FindResourceOrThrow(acrobot_file_name))[0]; + Parser(&plant).AddModelsFromUrl(acrobot_url)[0]; plant.Finalize(); // Set default positions through two different code paths. @@ -4132,8 +4120,8 @@ GTEST_TEST(MultibodyPlant, CombinePointContactParameters) { GTEST_TEST(MultibodyPlant, FixInputPortsFrom) { systems::DiagramBuilder builder; MultibodyPlant& plant = AddMultibodyPlantSceneGraph(&builder, 0.0); - Parser(&plant).AddModels( - FindResourceOrThrow("drake/multibody/plant/test/split_pendulum.sdf")); + Parser(&plant).AddModelsFromUrl( + "package://drake/multibody/plant/test/split_pendulum.sdf"); plant.Finalize(); auto diagram = builder.Build(); @@ -4158,8 +4146,8 @@ GTEST_TEST(MultibodyPlantTests, ActuationPorts) { // Add a split pendulum to the plant. const ModelInstanceIndex pendulum_model_instance = Parser(plant.get()) - .AddModels(FindResourceOrThrow( - "drake/multibody/plant/test/split_pendulum.sdf")) + .AddModelsFromUrl( + "package://drake/multibody/plant/test/split_pendulum.sdf") .at(0); plant->Finalize(); ASSERT_EQ(plant->num_actuated_dofs(default_model_instance()), 1); @@ -4214,11 +4202,10 @@ GTEST_TEST(MultibodyPlantTests, AlgebraicLoopDetection) { systems::DiagramBuilder builder; MultibodyPlant* plant = builder.AddSystem>(dt); - const char kSdfPath[] = - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"; + const char kSdfUrl[] = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; Parser parser(plant); - auto iiwa_instance = parser.AddModels(FindResourceOrThrow(kSdfPath)).at(0); + auto iiwa_instance = parser.AddModelsFromUrl(kSdfUrl).at(0); plant->Finalize(); auto feedback = builder.AddSystem>( plant->num_velocities()); @@ -4319,16 +4306,14 @@ GTEST_TEST(MultibodyPlantTest, ThrowIfSpatialForcePortContainsNaN) { GTEST_TEST(MultibodyPlantTest, SetDefaultPositions) { // Construct a plant with two Iiwas. - const char kSdfPath[] = - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"; + const char kSdfUrl[] = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; auto plant = std::make_unique>(0 /* plant type irrelevant */); - const std::string sdf_resource = FindResourceOrThrow(kSdfPath); multibody::ModelInstanceIndex iiwa0_instance = - Parser(plant.get(), "iiwa0").AddModels(sdf_resource).at(0); + Parser(plant.get(), "iiwa0").AddModelsFromUrl(kSdfUrl).at(0); multibody::ModelInstanceIndex iiwa1_instance = - Parser(plant.get(), "iiwa1").AddModels(sdf_resource).at(0); + Parser(plant.get(), "iiwa1").AddModelsFromUrl(kSdfUrl).at(0); // Weld iiwa0 to the world, leave iiwa1 to be floating. plant->WeldFrames(plant->world_frame(), plant->GetFrameByName("iiwa_link_0", iiwa0_instance)); @@ -4411,16 +4396,14 @@ GTEST_TEST(MultibodyPlantTest, SetDefaultPositions) { GTEST_TEST(MultibodyPlantTest, GetNames) { // Construct a plant with two Iiwas. - const char kSdfPath[] = - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"; + const char kSdfUrl[] = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; auto plant = std::make_unique>(0 /* plant type irrelevant */); - const std::string sdf_resource = FindResourceOrThrow(kSdfPath); multibody::ModelInstanceIndex iiwa0_instance = - Parser(plant.get(), "iiwa0").AddModels(sdf_resource).at(0); + Parser(plant.get(), "iiwa0").AddModelsFromUrl(kSdfUrl).at(0); multibody::ModelInstanceIndex iiwa1_instance = - Parser(plant.get(), "iiwa1").AddModels(sdf_resource).at(0); + Parser(plant.get(), "iiwa1").AddModelsFromUrl(kSdfUrl).at(0); // Weld iiwa0 to the world, leave iiwa1 to be floating. plant->WeldFrames(plant->world_frame(), plant->GetFrameByName("iiwa_link_0", iiwa0_instance)); diff --git a/multibody/plant/test/sap_driver_joint_limits_test.cc b/multibody/plant/test/sap_driver_joint_limits_test.cc index b913f45d341f..af62333e8497 100644 --- a/multibody/plant/test/sap_driver_joint_limits_test.cc +++ b/multibody/plant/test/sap_driver_joint_limits_test.cc @@ -3,7 +3,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/multibody/contact_solvers/contact_solver_results.h" #include "drake/multibody/contact_solvers/sap/sap_contact_problem.h" @@ -246,21 +245,17 @@ class KukaIiwaArmTests : public ::testing::Test { std::vector LoadIiwaWithGripper( MultibodyPlant* plant) const { DRAKE_DEMAND(plant != nullptr); - const char kArmFilePath[] = - "drake/manipulation/models/iiwa_description/urdf/" - "iiwa14_no_collision.urdf"; - - const char kWsg50FilePath[] = - "drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"; + const char kArmUrl[] = + "package://drake_models/iiwa_description/urdf/iiwa14_no_collision.urdf"; + const char kWsg50Url[] = + "package://drake_models/wsg_50_description/sdf/schunk_wsg_50.sdf"; Parser parser(plant); parser.SetAutoRenaming(true); - ModelInstanceIndex arm_model = - parser.AddModels(FindResourceOrThrow(kArmFilePath)).at(0); + ModelInstanceIndex arm_model = parser.AddModelsFromUrl(kArmUrl).at(0); // Add the gripper. - ModelInstanceIndex gripper_model = - parser.AddModels(FindResourceOrThrow(kWsg50FilePath)).at(0); + ModelInstanceIndex gripper_model = parser.AddModelsFromUrl(kWsg50Url).at(0); const auto& base_body = plant->GetBodyByName("base", arm_model); const auto& end_effector = plant->GetBodyByName("iiwa_link_7", arm_model); diff --git a/multibody/plant/test/sap_driver_pd_controller_constraints_test.cc b/multibody/plant/test/sap_driver_pd_controller_constraints_test.cc index edf1c0ca3c1c..4123c2e2b793 100644 --- a/multibody/plant/test/sap_driver_pd_controller_constraints_test.cc +++ b/multibody/plant/test/sap_driver_pd_controller_constraints_test.cc @@ -2,7 +2,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/math/rigid_transform.h" #include "drake/multibody/contact_solvers/sap/sap_contact_problem.h" #include "drake/multibody/contact_solvers/sap/sap_pd_controller_constraint.h" @@ -69,12 +68,10 @@ namespace kcov339_avoidance_magic { class ActuatedIiiwaArmTest : public ::testing::Test { public: void SetUp() override { - const char kArmSdfPath[] = - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"; - - const char kWsg50SdfPath[] = - "drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"; + const char kArmSdfUrl[] = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; + const char kWsg50SdfUrl[] = + "package://drake_models/wsg_50_description/sdf/schunk_wsg_50.sdf"; // Make a discrete model. plant_ = std::make_unique>(0.01 /* update period */); @@ -86,10 +83,10 @@ class ActuatedIiiwaArmTest : public ::testing::Test { Parser parser(plant_.get()); // Add the arm. - arm_model_ = parser.AddModels(FindResourceOrThrow(kArmSdfPath)).at(0); + arm_model_ = parser.AddModelsFromUrl(kArmSdfUrl).at(0); // Add the gripper. - gripper_model_ = parser.AddModels(FindResourceOrThrow(kWsg50SdfPath)).at(0); + gripper_model_ = parser.AddModelsFromUrl(kWsg50SdfUrl).at(0); const auto& base_body = plant_->GetBodyByName("iiwa_link_0", arm_model_); const auto& end_effector = plant_->GetBodyByName("iiwa_link_7", arm_model_); diff --git a/multibody/plant/test/wing_test.cc b/multibody/plant/test/wing_test.cc index f236a6ab4771..707f385a73ed 100644 --- a/multibody/plant/test/wing_test.cc +++ b/multibody/plant/test/wing_test.cc @@ -2,7 +2,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/common/test_utilities/expect_throws_message.h" #include "drake/multibody/parsing/parser.h" @@ -17,8 +16,7 @@ using Eigen::Vector3d; GTEST_TEST(WingTest, BasicTest) { MultibodyPlant plant(0.0); - Parser(&plant).AddModels( - FindResourceOrThrow("drake/multibody/models/box.urdf")); + Parser(&plant).AddModelsFromUrl("package://drake/multibody/models/box.urdf"); plant.Finalize(); const RigidBody& body = plant.GetBodyByName("box"); @@ -35,8 +33,7 @@ GTEST_TEST(WingTest, FallingFlatPlate) { systems::DiagramBuilder builder; auto* plant = builder.AddSystem>(0); - Parser(plant).AddModels( - FindResourceOrThrow("drake/multibody/models/box.urdf")); + Parser(plant).AddModelsFromUrl("package://drake/multibody/models/box.urdf"); plant->Finalize(); const RigidBody& body = plant->GetBodyByName("box"); @@ -147,8 +144,7 @@ GTEST_TEST(WingTest, ScalarConversion) { systems::DiagramBuilder builder; auto* plant = builder.AddSystem>(0); - Parser(plant).AddModels( - FindResourceOrThrow("drake/multibody/models/box.urdf")); + Parser(plant).AddModelsFromUrl("package://drake/multibody/models/box.urdf"); plant->Finalize(); const RigidBody& body = plant->GetBodyByName("box"); @@ -167,8 +163,7 @@ GTEST_TEST(WingTest, DerivativesAtZeroVelocity) { systems::DiagramBuilder builder; auto* plant = builder.AddSystem>(0); - Parser(plant).AddModels( - FindResourceOrThrow("drake/multibody/models/box.urdf")); + Parser(plant).AddModelsFromUrl("package://drake/multibody/models/box.urdf"); plant->Finalize(); plant->set_name("plant"); diff --git a/multibody/rational/BUILD.bazel b/multibody/rational/BUILD.bazel index efe7f495c866..570cc123ce20 100644 --- a/multibody/rational/BUILD.bazel +++ b/multibody/rational/BUILD.bazel @@ -44,12 +44,11 @@ drake_cc_library( hdrs = ["test/rational_forward_kinematics_test_utilities.h"], data = [ "//examples/kuka_iiwa_arm:models", - "//manipulation/models/iiwa_description:models", - "//manipulation/models/wsg_50_description:models", + "@drake_models//:iiwa_description", + "@drake_models//:wsg_50_description", ], visibility = ["//visibility:private"], deps = [ - "//common:find_resource", "//multibody/benchmarks/kuka_iiwa_robot", "//multibody/parsing:parser", "//multibody/plant", diff --git a/multibody/rational/test/rational_forward_kinematics_test_utilities.cc b/multibody/rational/test/rational_forward_kinematics_test_utilities.cc index 6645d9ff09a0..347ec7a536d3 100644 --- a/multibody/rational/test/rational_forward_kinematics_test_utilities.cc +++ b/multibody/rational/test/rational_forward_kinematics_test_utilities.cc @@ -4,7 +4,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/geometry/geometry_roles.h" #include "drake/multibody/benchmarks/kuka_iiwa_robot/make_kuka_iiwa_model.h" #include "drake/multibody/parsing/parser.h" @@ -21,12 +20,12 @@ using drake::multibody::Parser; std::unique_ptr> ConstructIiwaPlant( const std::string& iiwa_sdf_name, bool finalize) { - const std::string file_path = - "drake/manipulation/models/iiwa_description/sdf/" + iiwa_sdf_name; + const std::string url = + "package://drake_models/iiwa_description/sdf/" + iiwa_sdf_name; auto plant = std::make_unique>(0.); Parser parser(plant.get()); - parser.AddModels(drake::FindResourceOrThrow(file_path)); + parser.AddModelsFromUrl(url); plant->WeldFrames(plant->world_frame(), plant->GetFrameByName("iiwa_link_0")); if (finalize) { plant->Finalize(); @@ -56,11 +55,11 @@ std::unique_ptr> ConstructDualArmIiwaPlant( const std::string& iiwa_sdf_name, const RigidTransformd& X_WL, const RigidTransformd& X_WR, ModelInstanceIndex* left_iiwa_instance, ModelInstanceIndex* right_iiwa_instance) { - const std::string iiwa_path = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/" + iiwa_sdf_name); + const std::string url = + "package://drake_models/iiwa_description/sdf/" + iiwa_sdf_name; auto plant = std::make_unique>(0); - *left_iiwa_instance = Parser(&*plant, "left").AddModels(iiwa_path).at(0); - *right_iiwa_instance = Parser(&*plant, "right").AddModels(iiwa_path).at(0); + *left_iiwa_instance = Parser(&*plant, "left").AddModelsFromUrl(url).at(0); + *right_iiwa_instance = Parser(&*plant, "right").AddModelsFromUrl(url).at(0); plant->WeldFrames(plant->world_frame(), plant->GetFrameByName("iiwa_link_0", *left_iiwa_instance), X_WL); @@ -103,49 +102,16 @@ FinalizedIiwaTest::FinalizedIiwaTest() void AddIiwaWithSchunk(const RigidTransformd& X_7S, MultibodyPlant* plant) { DRAKE_DEMAND(plant != nullptr); - const std::string file_path = - "drake/manipulation/models/iiwa_description/sdf/" - "iiwa14_no_collision.sdf"; - Parser(plant).AddModels(drake::FindResourceOrThrow(file_path)); - Parser(plant).AddModels( - FindResourceOrThrow("drake/manipulation/models/wsg_50_description/sdf/" - "schunk_wsg_50_welded_fingers.sdf")); + Parser(plant).AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"); + Parser(plant).AddModelsFromUrl( + "package://drake_models/wsg_50_description/sdf/" + "schunk_wsg_50_welded_fingers.sdf"); plant->WeldFrames(plant->world_frame(), plant->GetFrameByName("iiwa_link_0")); // weld the schunk gripper to iiwa link 7. plant->WeldFrames(plant->GetFrameByName("iiwa_link_7"), plant->GetFrameByName("body"), X_7S); } -void AddDualArmIiwa(const RigidTransformd& X_WL, const RigidTransformd& X_WR, - const RigidTransformd& X_7S, MultibodyPlant* plant, - ModelInstanceIndex* left_iiwa_instance, - ModelInstanceIndex* right_iiwa_instance) { - DRAKE_DEMAND(plant != nullptr); - Parser left_parser(plant, "left"); - Parser right_parser(plant, "right"); - - const std::string iiwa_path = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/iiwa14_no_collision.sdf"); - *left_iiwa_instance = left_parser.AddModels(iiwa_path).at(0); - *right_iiwa_instance = right_parser.AddModels(iiwa_path).at(0); - - const std::string schunk_path = FindResourceOrThrow( - "models/schunk/schunk_wsg_50_welded_fingers.sdf"); - const auto left_schunk_instance = left_parser.AddModels(schunk_path).at(0); - const auto right_schunk_instance = right_parser.AddModels(schunk_path).at(0); - - plant->WeldFrames(plant->world_frame(), - plant->GetFrameByName("iiwa_link_0", *left_iiwa_instance), - X_WL); - plant->WeldFrames(plant->world_frame(), - plant->GetFrameByName("iiwa_link_0", *right_iiwa_instance), - X_WR); - // weld the schunk gripper to iiwa link 7. - plant->WeldFrames(plant->GetFrameByName("iiwa_link_7", *left_iiwa_instance), - plant->GetFrameByName("body", left_schunk_instance), X_7S); - plant->WeldFrames(plant->GetFrameByName("iiwa_link_7", *right_iiwa_instance), - plant->GetFrameByName("body", right_schunk_instance), X_7S); -} - } // namespace multibody } // namespace drake diff --git a/multibody/rational/test/rational_forward_kinematics_test_utilities.h b/multibody/rational/test/rational_forward_kinematics_test_utilities.h index de5ba4f4e026..f3090aab7249 100644 --- a/multibody/rational/test/rational_forward_kinematics_test_utilities.h +++ b/multibody/rational/test/rational_forward_kinematics_test_utilities.h @@ -76,17 +76,5 @@ class FinalizedIiwaTest : public ::testing::Test { void AddIiwaWithSchunk(const math::RigidTransformd& X_7S, MultibodyPlant* plant); -/* - * @param X_WL the pose of the left IIWA base in the world frame. - * @param X_WR the pose of the right IIWA base in the world frame. - * @param X_7S The weld pose of Schunk gripper in IIWA link 7 frame. - * @note `plant` is not finalized at the end of this function. - */ -void AddDualArmIiwa(const drake::math::RigidTransformd& X_WL, - const drake::math::RigidTransformd& X_WR, - const drake::math::RigidTransformd& X_7S, - MultibodyPlant* plant, - ModelInstanceIndex* left_iiwa_instance, - ModelInstanceIndex* right_iiwa_instance); } // namespace multibody } // namespace drake diff --git a/planning/BUILD.bazel b/planning/BUILD.bazel index 3e09bd616fe1..7b4cf85f9795 100644 --- a/planning/BUILD.bazel +++ b/planning/BUILD.bazel @@ -268,9 +268,9 @@ drake_cc_googletest( drake_cc_googletest( name = "linear_distance_and_interpolation_provider_test", data = [ - "//manipulation/models/iiwa_description:models", "//planning/test_utilities:collision_ground_plane.sdf", "//planning/test_utilities:flying_robot_base.sdf", + "@drake_models//:iiwa_description", ], deps = [ ":linear_distance_and_interpolation_provider", @@ -300,7 +300,7 @@ drake_cc_googletest( drake_cc_googletest( name = "robot_diagram_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":robot_diagram", diff --git a/planning/test/linear_distance_and_interpolation_provider_test.cc b/planning/test/linear_distance_and_interpolation_provider_test.cc index d565bb0c755a..6db7a966f4f9 100644 --- a/planning/test/linear_distance_and_interpolation_provider_test.cc +++ b/planning/test/linear_distance_and_interpolation_provider_test.cc @@ -180,7 +180,7 @@ GTEST_TEST(FixedIiwaTest, Test) { child: ground_plane_box::ground_plane_box - add_model: name: iiwa - file: package://drake/manipulation/models/iiwa_description/urdf/iiwa14_spheres_dense_collision.urdf + file: package://drake_models/iiwa_description/urdf/iiwa14_spheres_dense_collision.urdf - add_weld: parent: world child: iiwa::base @@ -317,7 +317,7 @@ GTEST_TEST(FloatingIiwaTest, Test) { file: package://drake/planning/test_utilities/flying_robot_base.sdf - add_model: name: iiwa - file: package://drake/manipulation/models/iiwa_description/urdf/iiwa14_spheres_dense_collision.urdf + file: package://drake_models/iiwa_description/urdf/iiwa14_spheres_dense_collision.urdf - add_weld: parent: flying_robot_base::flying_robot_base child: iiwa::base diff --git a/planning/test/robot_diagram_test.cc b/planning/test/robot_diagram_test.cc index bc3659960ca8..0940af072f70 100644 --- a/planning/test/robot_diagram_test.cc +++ b/planning/test/robot_diagram_test.cc @@ -7,7 +7,6 @@ #include #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/expect_throws_message.h" #include "drake/planning/robot_diagram_builder.h" #include "drake/systems/primitives/shared_pointer_system.h" @@ -27,9 +26,9 @@ using systems::System; std::unique_ptr> MakeSampleDut() { auto builder = std::make_unique>(); - builder->parser().AddModels( - FindResourceOrThrow("drake/manipulation/models/iiwa_description/urdf/" - "iiwa14_spheres_dense_collision.urdf")); + builder->parser().AddModelsFromUrl( + "package://drake_models/iiwa_description/urdf/" + "iiwa14_spheres_dense_collision.urdf"); return builder; } diff --git a/planning/test/scene_graph_collision_checker_test.cc b/planning/test/scene_graph_collision_checker_test.cc index 733267cd0663..6ec1ffb8a3cf 100644 --- a/planning/test/scene_graph_collision_checker_test.cc +++ b/planning/test/scene_graph_collision_checker_test.cc @@ -376,7 +376,7 @@ GTEST_TEST(SceneGraphCollisionCheckerTest, ClearanceFloatingBase) { file: package://drake_models/ycb/010_potted_meat_can.sdf - add_model: name: arm - file: package://drake/manipulation/models/iiwa_description/urdf/iiwa14_spheres_dense_collision.urdf + file: package://drake_models/iiwa_description/urdf/iiwa14_spheres_dense_collision.urdf - add_weld: parent: chassis::base_link_meat child: arm::base @@ -446,7 +446,7 @@ GTEST_TEST(SceneGraphCollisionCheckerTest, CollisionFilterUpdate) { file: package://drake_models/ycb/010_potted_meat_can.sdf - add_model: name: arm - file: package://drake/manipulation/models/iiwa_description/urdf/iiwa14_spheres_dense_collision.urdf + file: package://drake_models/iiwa_description/urdf/iiwa14_spheres_dense_collision.urdf - add_weld: parent: chassis::base_link_meat child: arm::base diff --git a/planning/test_utilities/BUILD.bazel b/planning/test_utilities/BUILD.bazel index f7e31166f7da..50b6972788cf 100644 --- a/planning/test_utilities/BUILD.bazel +++ b/planning/test_utilities/BUILD.bazel @@ -24,7 +24,7 @@ drake_cc_library( data = [ ":collision_ground_plane.sdf", ":flying_robot_base.sdf", - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ "//multibody/parsing", diff --git a/planning/test_utilities/collision_checker_abstract_test_suite.cc b/planning/test_utilities/collision_checker_abstract_test_suite.cc index 016864e203fe..64a6060c2379 100644 --- a/planning/test_utilities/collision_checker_abstract_test_suite.cc +++ b/planning/test_utilities/collision_checker_abstract_test_suite.cc @@ -27,7 +27,7 @@ multibody::parsing::ModelDirectives MakeCollisionCheckerTestScene() { multibody::parsing::ModelDirective add_robot_model; add_robot_model.add_model = multibody::parsing::AddModel{ - "package://drake/manipulation/models/iiwa_description/urdf/" + "package://drake_models/iiwa_description/urdf/" "iiwa14_spheres_dense_collision.urdf", "iiwa"}; multibody::parsing::ModelDirective add_robot_weld; diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index b6945ef04b50..c3946fff25bd 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -208,11 +208,10 @@ drake_cc_googletest( drake_cc_googletest( name = "inverse_dynamics_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":inverse_dynamics", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//common/test_utilities:expect_throws_message", "//multibody/parsing", @@ -223,11 +222,10 @@ drake_cc_googletest( drake_cc_googletest( name = "inverse_dynamics_controller_test", data = [ - "//manipulation/models/iiwa_description:models", + "@drake_models//:iiwa_description", ], deps = [ ":inverse_dynamics_controller", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//common/test_utilities:expect_throws_message", "//multibody/parsing", @@ -238,12 +236,11 @@ drake_cc_googletest( drake_cc_googletest( name = "joint_stiffness_controller_test", data = [ - "//manipulation/models/iiwa_description:models", "//multibody/benchmarks/acrobot:models", + "@drake_models//:iiwa_description", ], deps = [ ":joint_stiffness_controller", - "//common:find_resource", "//common/test_utilities:eigen_matrix_compare", "//common/test_utilities:expect_throws_message", "//multibody/parsing", diff --git a/systems/controllers/test/inverse_dynamics_controller_test.cc b/systems/controllers/test/inverse_dynamics_controller_test.cc index 8c88d827c27a..61edacb5549e 100644 --- a/systems/controllers/test/inverse_dynamics_controller_test.cc +++ b/systems/controllers/test/inverse_dynamics_controller_test.cc @@ -2,7 +2,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/common/test_utilities/expect_throws_message.h" #include "drake/multibody/parsing/parser.h" @@ -95,9 +94,8 @@ class InverseDynamicsControllerTest : public ::testing::Test { // the input robot plant. TEST_F(InverseDynamicsControllerTest, TestTorqueWithReferencedPlant) { auto robot = std::make_unique>(0.0); - const std::string full_name = drake::FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/iiwa14_no_collision.sdf"); - multibody::Parser(robot.get()).AddModels(full_name); + multibody::Parser(robot.get()).AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"); robot->WeldFrames(robot->world_frame(), robot->GetFrameByName("iiwa_link_0")); robot->Finalize(); @@ -117,9 +115,8 @@ TEST_F(InverseDynamicsControllerTest, TestTorqueWithReferencedPlant) { // input robot plant. TEST_F(InverseDynamicsControllerTest, TestTorqueWithOwnedPlant) { auto robot = std::make_unique>(0.0); - const std::string full_name = drake::FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/iiwa14_no_collision.sdf"); - multibody::Parser(robot.get()).AddModels(full_name); + multibody::Parser(robot.get()).AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"); robot->WeldFrames(robot->world_frame(), robot->GetFrameByName("iiwa_link_0")); robot->Finalize(); @@ -137,9 +134,8 @@ TEST_F(InverseDynamicsControllerTest, TestTorqueWithOwnedPlant) { GTEST_TEST(AdditionalInverseDynamicsTest, ScalarConversion) { auto mbp = std::make_unique>(0.0); - const std::string full_name = drake::FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/iiwa14_no_collision.sdf"); - multibody::Parser(mbp.get()).AddModels(full_name); + multibody::Parser(mbp.get()).AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"); mbp->WeldFrames(mbp->world_frame(), mbp->GetFrameByName("iiwa_link_0")); mbp->Finalize(); diff --git a/systems/controllers/test/inverse_dynamics_test.cc b/systems/controllers/test/inverse_dynamics_test.cc index 33f0975144cf..2b4ec2af52fe 100644 --- a/systems/controllers/test/inverse_dynamics_test.cc +++ b/systems/controllers/test/inverse_dynamics_test.cc @@ -8,7 +8,6 @@ #include "drake/common/drake_assert.h" #include "drake/common/eigen_types.h" -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/common/test_utilities/expect_throws_message.h" #include "drake/multibody/math/spatial_algebra.h" @@ -128,9 +127,8 @@ class InverseDynamicsTest : public ::testing::Test { // desired acceleration for the iiwa arm. TEST_F(InverseDynamicsTest, InverseDynamicsTest) { auto mbp = std::make_unique>(0.0); - const std::string full_name = drake::FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/iiwa14_no_collision.sdf"); - multibody::Parser(mbp.get()).AddModels(full_name); + multibody::Parser(mbp.get()).AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"); mbp->WeldFrames(mbp->world_frame(), mbp->GetFrameByName("iiwa_link_0")); @@ -161,9 +159,9 @@ TEST_F(InverseDynamicsTest, InverseDynamicsTest) { // for a given joint configuration of the KUKA IIWA Arm are identical. TEST_F(InverseDynamicsTest, GravityCompensationTest) { auto mbp = std::make_unique>(0.0); - const std::string full_name = drake::FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/iiwa14_no_collision.sdf"); - multibody::Parser(mbp.get()).AddModels(full_name); + const std::string url = + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"; + multibody::Parser(mbp.get()).AddModelsFromUrl(url); mbp->WeldFrames(mbp->world_frame(), mbp->GetFrameByName("iiwa_link_0")); @@ -183,7 +181,7 @@ TEST_F(InverseDynamicsTest, GravityCompensationTest) { // Re-initialize the model so we can add gravity. mbp = std::make_unique>(0.0); - multibody::Parser(mbp.get()).AddModels(full_name); + multibody::Parser(mbp.get()).AddModelsFromUrl(url); mbp->WeldFrames(mbp->world_frame(), mbp->GetFrameByName("iiwa_link_0")); @@ -202,11 +200,9 @@ TEST_F(InverseDynamicsTest, GravityCompensationTest) { GTEST_TEST(AdditionalInverseDynamicsTest, ScalarConversion) { auto mbp = std::make_unique>(0.0); - const std::string full_name = drake::FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/iiwa14_no_collision.sdf"); - multibody::Parser(mbp.get()).AddModels(full_name); - mbp->WeldFrames(mbp->world_frame(), - mbp->GetFrameByName("iiwa_link_0")); + multibody::Parser(mbp.get()).AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"); + mbp->WeldFrames(mbp->world_frame(), mbp->GetFrameByName("iiwa_link_0")); mbp->Finalize(); const int num_states = mbp->num_multibody_states(); diff --git a/systems/controllers/test/joint_stiffness_controller_test.cc b/systems/controllers/test/joint_stiffness_controller_test.cc index 6d9dd79d866c..b166964d61e2 100644 --- a/systems/controllers/test/joint_stiffness_controller_test.cc +++ b/systems/controllers/test/joint_stiffness_controller_test.cc @@ -2,7 +2,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/common/test_utilities/expect_throws_message.h" #include "drake/multibody/parsing/parser.h" @@ -20,9 +19,8 @@ using multibody::MultibodyPlant; GTEST_TEST(JointStiffnessControllerTest, SimpleDoublePendulum) { DiagramBuilder builder; auto plant = builder.AddSystem(0.0); - std::string full_name = FindResourceOrThrow( - "drake/multibody/benchmarks/acrobot/double_pendulum.urdf"); - multibody::Parser(plant).AddModels(full_name); + multibody::Parser(plant).AddModelsFromUrl( + "package://drake/multibody/benchmarks/acrobot/double_pendulum.urdf"); plant->WeldFrames(plant->world_frame(), plant->GetFrameByName("base")); plant->Finalize(); @@ -62,9 +60,8 @@ GTEST_TEST(JointStiffnessControllerTest, SimpleDoublePendulum) { GTEST_TEST(JointStiffnessControllerTest, ScalarConversion) { auto mbp = std::make_unique>(0.0); - const std::string full_name = FindResourceOrThrow( - "drake/manipulation/models/iiwa_description/sdf/iiwa14_no_collision.sdf"); - multibody::Parser(mbp.get()).AddModels(full_name); + multibody::Parser(mbp.get()).AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf"); mbp->WeldFrames(mbp->world_frame(), mbp->GetFrameByName("iiwa_link_0")); mbp->Finalize(); const int num_states = mbp->num_multibody_states(); diff --git a/systems/rendering/BUILD.bazel b/systems/rendering/BUILD.bazel index 6f45efe6957a..a33f04c39954 100644 --- a/systems/rendering/BUILD.bazel +++ b/systems/rendering/BUILD.bazel @@ -30,10 +30,9 @@ drake_cc_library( drake_cc_googletest( name = "multibody_position_to_geometry_pose_test", - data = ["//manipulation/models/iiwa_description:models"], + data = ["@drake_models//:iiwa_description"], deps = [ ":multibody_position_to_geometry_pose", - "//common:find_resource", "//common/test_utilities", "//multibody/parsing", "//systems/framework/test_utilities", diff --git a/systems/rendering/test/multibody_position_to_geometry_pose_test.cc b/systems/rendering/test/multibody_position_to_geometry_pose_test.cc index fe33c620cf5a..ab6bb9dd2e05 100644 --- a/systems/rendering/test/multibody_position_to_geometry_pose_test.cc +++ b/systems/rendering/test/multibody_position_to_geometry_pose_test.cc @@ -2,7 +2,6 @@ #include -#include "drake/common/find_resource.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/common/test_utilities/expect_throws_message.h" #include "drake/multibody/parsing/parser.h" @@ -34,9 +33,8 @@ GTEST_TEST(MultibodyPositionToGeometryPoseTest, BadConstruction) { MultibodyPlant mbp(0.0); SceneGraph scene_graph; mbp.RegisterAsSourceForSceneGraph(&scene_graph); - Parser(&mbp).AddModels( - FindResourceOrThrow("drake/manipulation/models/iiwa_description/iiwa7" - "/iiwa7_no_collision.sdf")); + Parser(&mbp).AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa7_no_collision.sdf"); DRAKE_EXPECT_THROWS_MESSAGE(MultibodyPositionToGeometryPose{mbp}, "MultibodyPositionToGeometryPose requires a " "MultibodyPlant that has been finalized"); @@ -48,9 +46,8 @@ GTEST_TEST(MultibodyPositionToGeometryPoseTest, Ownership) { auto raw_ptr = mbp.get(); SceneGraph scene_graph; mbp->RegisterAsSourceForSceneGraph(&scene_graph); - Parser(mbp.get()).AddModels( - FindResourceOrThrow("drake/manipulation/models/iiwa_description/iiwa7" - "/iiwa7_no_collision.sdf")); + Parser(mbp.get()).AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa7_no_collision.sdf"); mbp->Finalize(); const MultibodyPositionToGeometryPose dut(std::move(mbp)); @@ -85,9 +82,8 @@ GTEST_TEST(MultibodyPositionToGeometryPoseTest, InputOutput) { MultibodyPlant mbp(0.0); SceneGraph scene_graph; mbp.RegisterAsSourceForSceneGraph(&scene_graph); - Parser(&mbp).AddModels( - FindResourceOrThrow("drake/manipulation/models/iiwa_description/iiwa7" - "/iiwa7_no_collision.sdf")); + Parser(&mbp).AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa7_no_collision.sdf"); mbp.Finalize(); const MultibodyPositionToGeometryPose dut(mbp); @@ -124,9 +120,8 @@ GTEST_TEST(MultibodyPositionToGeometryPoseTest, FullStateInput) { auto mbp = make_unique>(0.0); SceneGraph scene_graph; mbp->RegisterAsSourceForSceneGraph(&scene_graph); - Parser(mbp.get()).AddModels( - FindResourceOrThrow("drake/manipulation/models/iiwa_description/iiwa7" - "/iiwa7_no_collision.sdf")); + Parser(mbp.get()).AddModelsFromUrl( + "package://drake_models/iiwa_description/sdf/iiwa7_no_collision.sdf"); mbp->Finalize(); const Eigen::VectorXd state = diff --git a/tools/install/bazel/generate_installed_files_manifest.bzl b/tools/install/bazel/generate_installed_files_manifest.bzl index f91f99dc1734..2dae090f6cd3 100644 --- a/tools/install/bazel/generate_installed_files_manifest.bzl +++ b/tools/install/bazel/generate_installed_files_manifest.bzl @@ -6,7 +6,6 @@ def _impl(ctx): known_non_runfiles = [ # These are installed in share/drake, but are not runfiles (at least, # not with these paths). - "manipulation/models/iiwa_description/iiwa_stack.LICENSE.txt", "setup/Brewfile", "setup/install_prereqs", "setup/packages-jammy.txt",