Skip to content

Commit

Permalink
[multibody] AddRigidBody defaults to zero inertia when not specified
Browse files Browse the repository at this point in the history
Deprecate the SpatialInertia default constructor.
  • Loading branch information
jwnimmer-tri committed Mar 28, 2024
1 parent b29351f commit d1d0b09
Show file tree
Hide file tree
Showing 57 changed files with 273 additions and 284 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
8 changes: 5 additions & 3 deletions bindings/pydrake/multibody/plant_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -241,12 +241,14 @@ 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") = SpatialInertia<double>::Zero(),
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") = SpatialInertia<double>::Zero(),
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
75 changes: 30 additions & 45 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,10 @@ def test_spatial_inertia_api(self, T):
SpatialForce = SpatialForce_[T]
SpatialVelocity = SpatialVelocity_[T]
SpatialMomentum = SpatialMomentum_[T]
SpatialInertia()
SpatialInertia.Zero()
SpatialInertia.NaN()
with catch_drake_warnings(expected_count=1) as w:
SpatialInertia()
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 +900,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 +1383,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 +1980,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 +2349,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 +2362,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 +2475,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")
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 @@ -2511,11 +2508,9 @@ def test_distance_constraint_api(self, T):
plant.set_discrete_contact_approximation(
DiscreteContactApproximation.kSap)

# 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)
# Add a distance constraint.
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 @@ -2533,11 +2528,9 @@ def test_ball_constraint_api(self, T):
plant.set_discrete_contact_approximation(
DiscreteContactApproximation.kSap)

# 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)
# Add ball constraint.
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 +2547,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 +2635,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 +2655,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 +3189,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
7 changes: 5 additions & 2 deletions bindings/pydrake/multibody/tree_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -319,10 +319,13 @@ 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") = SpatialInertia<double>::Zero(),
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") = SpatialInertia<double>::Zero(),
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
10 changes: 8 additions & 2 deletions bindings/pydrake/multibody/tree_py_inertia.cc
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#include "drake/bindings/pydrake/common/cpp_template_pybind.h"
#include "drake/bindings/pydrake/common/default_scalars_pybind.h"
#include "drake/bindings/pydrake/common/deprecation_pybind.h"
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/pydrake_pybind.h"
#include "drake/multibody/tree/geometry_spatial_inertia.h"
Expand Down Expand Up @@ -254,11 +255,16 @@ 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("Zero", &Class::Zero, cls_doc.Zero.doc)
.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
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
from pydrake.multibody.parsing import Parser
from pydrake.multibody.plant import (
AddMultibodyPlantSceneGraph, CoulombFriction)
from pydrake.multibody.tree import SpatialInertia, UnitInertia
from pydrake.systems.analysis import Simulator
from pydrake.systems.framework import DiagramBuilder
from pydrake.systems.planar_scenegraph_visualizer import (
Expand Down Expand Up @@ -105,9 +104,7 @@ def test_procedural_geometry(self):
box_shape = Box(1., 2., 3.)
# This rigid body will be added to the world model instance since
# the model instance is not specified.
box_body = mbp.AddRigidBody("box", SpatialInertia(
mass=1.0, p_PScm_E=np.array([0., 0., 0.]),
G_SP_E=UnitInertia(1.0, 1.0, 1.0)))
box_body = mbp.AddRigidBody("box")
mbp.WeldFrames(world_body.body_frame(), box_body.body_frame(),
RigidTransform())
mbp.RegisterVisualGeometry(
Expand Down Expand Up @@ -146,9 +143,7 @@ def scene_graph_with_mesh(filename, scale=1.0):
world_body = mbp.world_body()

mesh_shape = Mesh(filename, scale=scale)
mesh_body = mbp.AddRigidBody("mesh", SpatialInertia(
mass=1.0, p_PScm_E=np.array([0., 0., 0.]),
G_SP_E=UnitInertia(1.0, 1.0, 1.0)))
mesh_body = mbp.AddRigidBody("mesh")
mbp.WeldFrames(world_body.body_frame(), mesh_body.body_frame(),
RigidTransform())
mbp.RegisterVisualGeometry(
Expand Down
4 changes: 1 addition & 3 deletions bindings/pydrake/visualization/_model_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
from pydrake.multibody.meshcat import JointSliders
from pydrake.multibody.tree import (
FixedOffsetFrame,
SpatialInertia,
default_model_instance,
)
from pydrake.planning import RobotDiagramBuilder
Expand Down Expand Up @@ -293,8 +292,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
1 change: 0 additions & 1 deletion examples/hydroelastic/ball_plate/make_ball_plate_plant.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@ using multibody::CoulombFriction;
using multibody::MultibodyPlant;
using multibody::RigidBody;
using multibody::SpatialInertia;
using multibody::UnitInertia;
using math::RigidTransformd;
using math::RotationMatrixd;
using Eigen::Vector3d;
Expand Down
8 changes: 1 addition & 7 deletions geometry/optimization/test/c_iris_collision_geometry_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -512,17 +512,11 @@ GTEST_TEST(DistanceToHalfspace, Test) {
// properties.
AddContactMaterial(0.1, 250.0, multibody::CoulombFriction<double>{0.9, 0.5},
&proximity_properties);
// C-IRIS only considers robot kinematics, not dynamics. So we use an
// arbitrary inertia.
const multibody::SpatialInertia<double> spatial_inertia(
1, Eigen::Vector3d::Zero(),
multibody::UnitInertia<double>(0.01, 0.01, 0.01, 0, 0, 0));

std::vector<multibody::BodyIndex> body_indices;
for (int i = 0; i < 5; ++i) {
body_indices.push_back(
plant->AddRigidBody("body" + std::to_string(i), spatial_inertia)
.index());
plant->AddRigidBody("body" + std::to_string(i)).index());
}
const Eigen::Vector3d box_size(0.05, 0.02, 0.03);
const geometry::GeometryId body0_box = plant->RegisterCollisionGeometry(
Expand Down
Loading

0 comments on commit d1d0b09

Please sign in to comment.