Skip to content

Commit

Permalink
[examples] Copy quadrotor.urdf to drake_models (RobotLocomotion#21238)
Browse files Browse the repository at this point in the history
We'll remove the file from Drake after the next release, to provide a
smoother glide path for underactuated.csail.mit.edu.

[workspace] Upgrade drake_models to latest commit
  • Loading branch information
jwnimmer-tri authored and RussTedrake committed Dec 15, 2024
1 parent f037948 commit 64fd414
Show file tree
Hide file tree
Showing 7 changed files with 10 additions and 8 deletions.
3 changes: 1 addition & 2 deletions examples/quadrotor/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,7 @@ filegroup(
name = "models",
srcs = [
":glob_models",
"@drake_models//:skydio_2/skydio_2_1000_poly.mtl",
"@drake_models//:skydio_2/skydio_2_1000_poly.obj",
"@drake_models//:skydio_2",
],
)

Expand Down
3 changes: 3 additions & 0 deletions examples/quadrotor/quadrotor.urdf
Original file line number Diff line number Diff line change
@@ -1,4 +1,7 @@
<?xml version="1.0"?>
<!-- This model file is deprecated and should not be used in new code.
Instead, use the drake_models/skydio_2/quadrotor.urdf.
TODO(jwnimmer-tri) Delete this on 2024-05-01. -->
<!-- Mesh file and approximate numbers are from Abe Bachrach at Skdio. -->
<robot name="quadrotor">
<!--
Expand Down
2 changes: 1 addition & 1 deletion examples/quadrotor/quadrotor_geometry.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ QuadrotorGeometry::QuadrotorGeometry(
multibody::Parser parser(&mbp, scene_graph);

const auto model_instance_indices = parser.AddModelsFromUrl(
"package://drake/examples/quadrotor/quadrotor.urdf");
"package://drake_models/skydio_2/quadrotor.urdf");
mbp.Finalize();

// Identify the single quadrotor body and its frame.
Expand Down
2 changes: 1 addition & 1 deletion examples/quadrotor/quadrotor_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ namespace quadrotor {

/// The Quadrotor - an underactuated aerial vehicle. This version of the
/// Quadrotor is implemented to match the dynamics of the plant specified in
/// the `quadrotor.urdf` model file.
/// the `package://drake_models/skydio_2/quadrotor.urdf` model file.
///
/// @system
/// name: QuadrotorPlant
Expand Down
2 changes: 1 addition & 1 deletion examples/quadrotor/run_quadrotor_dynamics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class Quadrotor : public systems::Diagram<T> {
multibody::AddMultibodyPlantSceneGraph(&builder, 0.0);
multibody::Parser parser(&plant);
parser.AddModelsFromUrl(
"package://drake/examples/quadrotor/quadrotor.urdf");
"package://drake_models/skydio_2/quadrotor.urdf");
parser.AddModelsFromUrl(
"package://drake/examples/quadrotor/warehouse.sdf");
plant.Finalize();
Expand Down
2 changes: 1 addition & 1 deletion examples/quadrotor/test/quadrotor_dynamics_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ class MultibodyQuadrotor: public Diagram<double> {
auto owned_plant = std::make_unique<MultibodyPlant<double>>(0.0);
plant_ = owned_plant.get();
Parser(plant_).AddModelsFromUrl(
"package://drake/examples/quadrotor/quadrotor.urdf");
"package://drake_models/skydio_2/quadrotor.urdf");
plant_->Finalize();
body_ = &plant_->GetBodyByName("base_link");
DiagramBuilder<double> builder;
Expand Down
4 changes: 2 additions & 2 deletions tools/workspace/drake_models/repository.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@ def drake_models_repository(
github_archive(
name = name,
repository = "RobotLocomotion/models",
commit = "db9c78f538fb1cd519098a6d6422c3f179415eb6",
sha256 = "f3a630b78671f52412e2b5b54dc4ac26c855a88af8c49df0e2f9a9d36f20b570", # noqa
commit = "d2b82d335c4f19aa9b515b483c9d5e6dff0c8997",
sha256 = "6b7390b95bc7ab50c6bbbf05a07efa727965485d71c8c5b34998cfec44dbbc27", # noqa
build_file = ":package.BUILD.bazel",
mirrors = mirrors,
)

0 comments on commit 64fd414

Please sign in to comment.