Skip to content

Commit

Permalink
[multibody] AddRigidBody offers a default inertia
Browse files Browse the repository at this point in the history
Deprecate the SpatialInertia default constructor.
  • Loading branch information
jwnimmer-tri committed Mar 27, 2024
1 parent 325f186 commit 202264f
Show file tree
Hide file tree
Showing 51 changed files with 222 additions and 194 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -28,16 +28,15 @@
"import matplotlib.pyplot as plt\n",
"from pydrake.multibody.plant import MultibodyPlant\n",
"from pydrake.multibody.tree import (\n",
" DoorHingeConfig, DoorHinge, RevoluteJoint, SpatialInertia\n",
" DoorHingeConfig, DoorHinge, RevoluteJoint\n",
")\n",
"\n",
"# Build a simple MultibodyPlant that contains two bodies and a revolute joint.\n",
"# Then add a DoorHinge ForceElement to the joint.\n",
"plant = MultibodyPlant(0.0)\n",
"spatial_inertia = SpatialInertia()\n",
"\n",
"body_a = plant.AddRigidBody(name=\"body_a\", M_BBo_B=spatial_inertia)\n",
"body_b = plant.AddRigidBody(name=\"body_b\", M_BBo_B=spatial_inertia)\n",
"body_a = plant.AddRigidBody(name=\"body_a\")\n",
"body_b = plant.AddRigidBody(name=\"body_b\")\n",
"\n",
"revolute_joint = plant.AddJoint(RevoluteJoint(\n",
" name=\"revolve_joint\", frame_on_parent=body_a.body_frame(),\n",
Expand Down
10 changes: 7 additions & 3 deletions bindings/pydrake/multibody/plant_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -241,12 +241,16 @@ void DoScalarDependentDefinitions(py::module m, T) {
const SpatialInertia<double>& s) -> auto& {
return self->AddRigidBody(name, s);
},
py::arg("name"), py::arg("M_BBo_B"), py_rvp::reference_internal,
cls_doc.AddRigidBody.doc_2args)
py::arg("name"),
py::arg("M_BBo_B") =
RigidBody<T>::MakeNominalSpatialInertiaForConstructor(),
py_rvp::reference_internal, cls_doc.AddRigidBody.doc_2args)
.def("AddRigidBody",
py::overload_cast<const std::string&, ModelInstanceIndex,
const SpatialInertia<double>&>(&Class::AddRigidBody),
py::arg("name"), py::arg("model_instance"), py::arg("M_BBo_B"),
py::arg("name"), py::arg("model_instance"),
py::arg("M_BBo_B") =
RigidBody<T>::MakeNominalSpatialInertiaForConstructor(),
py_rvp::reference_internal, cls_doc.AddRigidBody.doc_3args)
.def("WeldFrames", &Class::WeldFrames, py::arg("frame_on_parent_F"),
py::arg("frame_on_child_M"),
Expand Down
68 changes: 27 additions & 41 deletions bindings/pydrake/multibody/test/plant_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -201,7 +201,7 @@ def test_multibody_plant_construction_api(self, T):
builder = DiagramBuilder()
plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0)
self.assertEqual(plant.time_step(), 0.0)
spatial_inertia = SpatialInertia()
spatial_inertia = SpatialInertia.NaN()
body = plant.AddRigidBody(name="new_body",
M_BBo_B=spatial_inertia)
body_mass = body.default_mass()
Expand Down Expand Up @@ -786,7 +786,9 @@ def test_spatial_inertia_api(self, T):
SpatialForce = SpatialForce_[T]
SpatialVelocity = SpatialVelocity_[T]
SpatialMomentum = SpatialMomentum_[T]
SpatialInertia()
with catch_drake_warnings(expected_count=1) as w:
SpatialInertia()
SpatialInertia.NaN()
SpatialInertia.MakeFromCentralInertia(
mass=1.3, p_PScm_E=[0.1, -0.2, 0.3],
I_SScm_E=RotationalInertia(Ixx=2.0, Iyy=2.3, Izz=2.4))
Expand Down Expand Up @@ -897,8 +899,10 @@ def test_legacy_unpickle_plant_module(self):
@numpy_compare.check_all_types
def test_rigid_body_api(self, T):
TemplatedRigidBody = RigidBody_[T]
M = SpatialInertia_[float]()
M = SpatialInertia_[float].NaN()
i = ModelInstanceIndex(0)
TemplatedRigidBody(body_name="body_name")
TemplatedRigidBody(body_name="body_name", model_instance=i)
TemplatedRigidBody(body_name="body_name", M_BBo_B=M)
TemplatedRigidBody(body_name="body_name", model_instance=i, M_BBo_B=M)
# Make sure the default (float) version also works.
Expand Down Expand Up @@ -1378,7 +1382,7 @@ def set_zero():
@numpy_compare.check_all_types
def test_default_free_body_pose(self, T):
plant = MultibodyPlant_[T](0.0)
body = plant.AddRigidBody("body", SpatialInertia_[float]())
body = plant.AddRigidBody("body")
plant.Finalize()
# Test existence of default free body pose setting.
X_WB_default = RigidTransform_[float]()
Expand Down Expand Up @@ -1975,7 +1979,7 @@ def make_weld_joint(plant, P, C):

def loop_body(make_joint, time_step):
plant = MultibodyPlant_[T](time_step)
child = plant.AddRigidBody("Child", SpatialInertia_[float]())
child = plant.AddRigidBody("Child")
joint = make_joint(
plant=plant, P=plant.world_frame(), C=child.body_frame())
joint_out = plant.AddJoint(joint)
Expand Down Expand Up @@ -2344,12 +2348,8 @@ def test_actuation_matrix(self):

def test_deprecated_weld_joint_api(self):
plant = MultibodyPlant_[float](0.01)
body1 = plant.AddRigidBody(
name="body1",
M_BBo_B=SpatialInertia_[float]())
body2 = plant.AddRigidBody(
name="body2",
M_BBo_B=SpatialInertia_[float]())
body1 = plant.AddRigidBody(name="body1")
body2 = plant.AddRigidBody(name="body2")

# No keywords defaults to the first constructor defined in the binding.
# No warning.
Expand All @@ -2361,12 +2361,8 @@ def test_deprecated_weld_joint_api(self):

def test_deprecated_weld_frames_api(self):
plant = MultibodyPlant_[float](0.01)
body1 = plant.AddRigidBody(
name="body1",
M_BBo_B=SpatialInertia_[float]())
body2 = plant.AddRigidBody(
name="body2",
M_BBo_B=SpatialInertia_[float]())
body1 = plant.AddRigidBody(name="body1")
body2 = plant.AddRigidBody(name="body2")

# No keywords defaults to the first function named `WeldFrames` defined
# in the binding. No warning.
Expand Down Expand Up @@ -2478,7 +2474,7 @@ def test_frame_context_methods(self, T):
def test_fixed_offset_frame_api(self, T):
FixedOffsetFrame = FixedOffsetFrame_[T]
P = MultibodyPlant_[T](0.0).world_frame()
B = RigidBody_[T]("body", SpatialInertia_[float]())
B = RigidBody_[T]("body", SpatialInertia_[float].NaN())
X = RigidTransform_[float].Identity()
FixedOffsetFrame(name="name", P=P, X_PF=X, model_instance=None)
FixedOffsetFrame(name="name", bodyB=B, X_BF=X)
Expand Down Expand Up @@ -2513,9 +2509,8 @@ def test_distance_constraint_api(self, T):

# Add a distance constraint. Since we won't be performing dynamics
# computations, using garbage inertia is ok for this test.
M_BBo_B = SpatialInertia_[float]()
body_A = plant.AddRigidBody(name="A", M_BBo_B=M_BBo_B)
body_B = plant.AddRigidBody(name="B", M_BBo_B=M_BBo_B)
body_A = plant.AddRigidBody(name="A")
body_B = plant.AddRigidBody(name="B")
p_AP = [0.0, 0.0, 0.0]
p_BQ = [0.0, 0.0, 0.0]
plant.AddDistanceConstraint(
Expand All @@ -2535,9 +2530,8 @@ def test_ball_constraint_api(self, T):

# Add ball constraint. Since we won't be performing dynamics
# computations, using garbage inertia is ok for this test.
M_BBo_B = SpatialInertia_[float]()
body_A = plant.AddRigidBody(name="A", M_BBo_B=M_BBo_B)
body_B = plant.AddRigidBody(name="B", M_BBo_B=M_BBo_B)
body_A = plant.AddRigidBody(name="A")
body_B = plant.AddRigidBody(name="B")
p_AP = [0.0, 0.0, 0.0]
p_BQ = [0.0, 0.0, 0.0]
plant.AddBallConstraint(
Expand All @@ -2554,11 +2548,8 @@ def test_constraint_active_status_api(self):
plant.set_discrete_contact_approximation(
DiscreteContactApproximation.kSap)

# Since we won't be performing dynamics computations,
# using garbage inertia is ok for this test.
M_BBo_B = SpatialInertia_[float]()
body_A = plant.AddRigidBody(name="A", M_BBo_B=M_BBo_B)
body_B = plant.AddRigidBody(name="B", M_BBo_B=M_BBo_B)
body_A = plant.AddRigidBody(name="A")
body_B = plant.AddRigidBody(name="B")

# Add ball and distance constraints.
p_AP = [0.0, 0.0, 0.0]
Expand Down Expand Up @@ -2645,11 +2636,9 @@ def test_weld_constraint_api(self, T):
plant.set_discrete_contact_approximation(
DiscreteContactApproximation.kSap)

# Add weld constraint. Since we won't be performing dynamics
# computations, using garbage inertia is ok for this test.
M = SpatialInertia_[float]()
body_A = plant.AddRigidBody(name="A", M_BBo_B=M)
body_B = plant.AddRigidBody(name="B", M_BBo_B=M)
# Add weld constraint.
body_A = plant.AddRigidBody(name="A")
body_B = plant.AddRigidBody(name="B")
X_AP = RigidTransform_[float]()
X_BQ = RigidTransform_[float]()
plant.AddWeldConstraint(
Expand All @@ -2667,11 +2656,9 @@ def test_remove_constraint(self, T):
plant.set_discrete_contact_approximation(
DiscreteContactApproximation.kSap)

# Add weld constraint. Since we won't be performing dynamics
# computations, using garbage inertia is ok for this test.
M = SpatialInertia_[float]()
body_A = plant.AddRigidBody(name="A", M_BBo_B=M)
body_B = plant.AddRigidBody(name="B", M_BBo_B=M)
# Add weld constraint.
body_A = plant.AddRigidBody(name="A")
body_B = plant.AddRigidBody(name="B")
X_AP = RigidTransform_[float]()
X_BQ = RigidTransform_[float]()
id = plant.AddWeldConstraint(
Expand Down Expand Up @@ -3203,8 +3190,7 @@ def test_free_base_bodies(self):
plant = MultibodyPlant_[float](time_step=0.01)
model_instance = plant.AddModelInstance("new instance")
added_body = plant.AddRigidBody(
name="body", model_instance=model_instance,
M_BBo_B=SpatialInertia_[float]())
name="body", model_instance=model_instance)
plant.Finalize()
self.assertTrue(plant.HasBodyNamed("body", model_instance))
self.assertTrue(plant.HasUniqueFreeBaseBody(model_instance))
Expand Down
17 changes: 13 additions & 4 deletions bindings/pydrake/multibody/tree_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -330,10 +330,15 @@ void DoScalarDependentDefinitions(py::module m, T) {
BindMultibodyElementMixin<T>(&cls);
cls // BR
.def(py::init<const std::string&, const SpatialInertia<double>&>(),
py::arg("body_name"), py::arg("M_BBo_B"), cls_doc.ctor.doc_2args)
py::arg("body_name"),
py::arg("M_BBo_B") =
Class::MakeNominalSpatialInertiaForConstructor(),
cls_doc.ctor.doc_2args)
.def(py::init<const std::string&, ModelInstanceIndex,
const SpatialInertia<double>&>(),
py::arg("body_name"), py::arg("model_instance"), py::arg("M_BBo_B"),
py::arg("body_name"), py::arg("model_instance"),
py::arg("M_BBo_B") =
Class::MakeNominalSpatialInertiaForConstructor(),
cls_doc.ctor.doc_3args)
.def("name", &Class::name, cls_doc.name.doc)
.def("scoped_name", &Class::scoped_name, cls_doc.scoped_name.doc)
Expand Down Expand Up @@ -1445,11 +1450,15 @@ void DoScalarDependentDefinitions(py::module m, T) {
.def_static("HollowSphereWithMass", &Class::HollowSphereWithMass,
py::arg("mass"), py::arg("radius"),
cls_doc.HollowSphereWithMass.doc)
.def(py::init(), cls_doc.ctor.doc_0args)
.def_static("NaN", &Class::NaN, cls_doc.NaN.doc)
// TODO(jwnimmer-tri) Remove this on 2024-10-01.
.def(py::init(WrapDeprecated(cls_doc.ctor.doc_deprecated,
[]() { return std::make_unique<Class>(Class::NaN()); })),
cls_doc.ctor.doc_deprecated)
.def(py::init<const T&, const Eigen::Ref<const Vector3<T>>&,
const UnitInertia<T>&, const bool>(),
py::arg("mass"), py::arg("p_PScm_E"), py::arg("G_SP_E"),
py::arg("skip_validity_check") = false, cls_doc.ctor.doc_4args)
py::arg("skip_validity_check") = false, cls_doc.ctor.doc)
// TODO(jwnimmer-tri) Need to bind cast<>.
.def("get_mass", &Class::get_mass, cls_doc.get_mass.doc)
.def("get_com", &Class::get_com, cls_doc.get_com.doc)
Expand Down
3 changes: 1 addition & 2 deletions bindings/pydrake/visualization/_model_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -293,8 +293,7 @@ def Finalize(self, position=None):
model_instance=default_model_instance()))
sensor_body = self._builder.plant().AddRigidBody(
name="$rgbd_sensor_body",
model_instance=default_model_instance(),
M_BBo_B=SpatialInertia())
model_instance=default_model_instance())
self._builder.plant().WeldFrames(
frame_on_parent_F=sensor_offset_frame,
frame_on_child_M=sensor_body.body_frame())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ struct SphereSpecification {
UnitInertia<double>(I, I, I));
}
double radius;
SpatialInertia<double> inertia;
SpatialInertia<double> inertia{SpatialInertia<double>::NaN()};
CoulombFriction<double> friction;
};

Expand All @@ -43,7 +43,7 @@ struct BoxSpecification {
}
// Full dimensions of a box (not the half dimensions).
Eigen::Vector3d size;
SpatialInertia<double> inertia;
SpatialInertia<double> inertia{SpatialInertia<double>::NaN()};
CoulombFriction<double> friction;
std::optional<math::RigidTransform<double>> X_WB;
};
Expand Down
11 changes: 6 additions & 5 deletions multibody/parsing/detail_mujoco_parser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -409,7 +409,7 @@ class MujocoParser {
private:
const std::map<std::string, SpatialInertia<double>>& mesh_inertia_;
std::string name_;
SpatialInertia<double> M_GG_G_;
SpatialInertia<double> M_GG_G_{SpatialInertia<double>::NaN()};
};

SpatialInertia<double> ParseInertial(XMLElement* node) {
Expand All @@ -419,7 +419,7 @@ class MujocoParser {
double mass;
if (!ParseScalarAttribute(node, "mass", &mass)) {
Error(*node, "The inertial tag must include the mass attribute.");
return {};
return SpatialInertia<double>::NaN();
}

// We interpret the MuJoCo XML documentation as saying that if a
Expand All @@ -441,7 +441,7 @@ class MujocoParser {
Error(*node,
"The inertial tag must include either the diaginertia or "
"fullinertia attribute.");
return {};
return SpatialInertia<double>::NaN();
}
}

Expand All @@ -457,7 +457,7 @@ class MujocoParser {
std::unique_ptr<geometry::Shape> shape{};
Vector4d rgba{.5, .5, .5, 1};
CoulombFriction<double> friction{1.0, 1.0};
SpatialInertia<double> M_GBo_B{};
SpatialInertia<double> M_GBo_B{SpatialInertia<double>::NaN()};
bool register_collision{true};
bool register_visual{true};
};
Expand Down Expand Up @@ -1080,7 +1080,8 @@ class MujocoParser {

if (std::filesystem::exists(filename)) {
mesh_[name] = std::make_unique<geometry::Mesh>(filename, scale[0]);
mesh_inertia_[name] = CalcSpatialInertia(*mesh_[name], 1);
mesh_inertia_.insert_or_assign(name,
CalcSpatialInertia(*mesh_[name], 1));
} else if (std::filesystem::exists(original_filename)) {
Warning(
*node,
Expand Down
2 changes: 1 addition & 1 deletion multibody/parsing/detail_urdf_parser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -214,7 +214,7 @@ void UrdfParser::ParseBody(XMLElement* node, MaterialMap* materials) {
" the world link. The <inertial> tag is being ignored.");
}
} else {
SpatialInertia<double> M_BBo_B;
auto M_BBo_B = SpatialInertia<double>::NaN();
XMLElement* inertial_node = node->FirstChildElement("inertial");
if (!inertial_node) {
M_BBo_B = SpatialInertia<double>(0, Vector3d::Zero(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ class CollisionFilterGroupResolverTest : public test::DiagnosticPolicyTestBase {
std::optional<ModelInstanceIndex> model_instance) {
auto model = model_instance.value_or(default_model_instance());
return plant_.RegisterCollisionGeometry(
plant_.AddRigidBody(name, model, SpatialInertia<double>()),
plant_.AddRigidBody(name, model, SpatialInertia<double>::NaN()),
RigidTransformd::Identity(), geometry::Sphere(1.0), name,
CoulombFriction<double>());
}
Expand Down
19 changes: 12 additions & 7 deletions multibody/plant/multibody_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -1159,12 +1159,14 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
/// @param[in] M_BBo_B
/// The SpatialInertia of the new rigid body to be added to `this`
/// %MultibodyPlant, computed about the body frame origin `Bo` and expressed
/// in the body frame B.
/// in the body frame B. When not provided, defaults to a nominal non-zero
/// value.
/// @returns A constant reference to the new RigidBody just added, which will
/// remain valid for the lifetime of `this` %MultibodyPlant.
const RigidBody<T>& AddRigidBody(const std::string& name,
ModelInstanceIndex model_instance,
const SpatialInertia<double>& M_BBo_B) {
const RigidBody<T>& AddRigidBody(
const std::string& name, ModelInstanceIndex model_instance,
const SpatialInertia<double>& M_BBo_B =
RigidBody<T>::MakeNominalSpatialInertiaForConstructor()) {
DRAKE_MBP_THROW_IF_FINALIZED();
// Add the actual rigid body to the model.
const RigidBody<T>& body =
Expand Down Expand Up @@ -1204,13 +1206,16 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
/// @param[in] M_BBo_B
/// The SpatialInertia of the new rigid body to be added to `this`
/// %MultibodyPlant, computed about the body frame origin `Bo` and expressed
/// in the body frame B.
/// in the body frame B. When not provided, defaults to a nominal non-zero
/// value.
/// @returns A constant reference to the new RigidBody just added, which will
/// remain valid for the lifetime of `this` %MultibodyPlant.
/// @throws std::exception if additional model instances have been created
/// beyond the world and default instances.
const RigidBody<T>& AddRigidBody(const std::string& name,
const SpatialInertia<double>& M_BBo_B) {
const RigidBody<T>& AddRigidBody(
const std::string& name,
const SpatialInertia<double>& M_BBo_B =
RigidBody<T>::MakeNominalSpatialInertiaForConstructor()) {
if (num_model_instances() != 2) {
throw std::logic_error(
"This model has more model instances than the default. Please "
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ class DeformableDriverContactKinematicsTest
Fz and the contact normal is defined to point into the rigid body (in the
-Fz direction), so Cz = -Fz. */
const RigidBody<double>& rigid_body =
plant_->AddRigidBody("rigid_body", SpatialInertia<double>());
plant_->AddRigidBody("rigid_body", SpatialInertia<double>::NaN());
rigid_geometry_id_ = plant_->RegisterCollisionGeometry(
rigid_body, X_BR, geometry::Box(10, 10, 1),
"dynamic_collision_geometry", rigid_proximity_props);
Expand Down
Loading

0 comments on commit 202264f

Please sign in to comment.