Skip to content

Commit 74bf5e7

Browse files
authored
Eliminate Body base class in favor of RigidBody (#20676)
Leaves Body as an alias for RigidBody but modifies all Drake code to use RigidBody only. Removes unused ability to have body types other than RigidBody. Moves now-non-templatized AddRigidBody function from inl.h to .cc. Also renames BodyFrame to RigidBodyFrame and deprecates BodyFrame alias.
1 parent 3eeff76 commit 74bf5e7

File tree

161 files changed

+1713
-1960
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

161 files changed

+1713
-1960
lines changed

bindings/pydrake/multibody/plant_py.cc

+16-15
Original file line numberDiff line numberDiff line change
@@ -393,7 +393,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
393393
.def("GetFreeBodyPose", &Class::GetFreeBodyPose, py::arg("context"),
394394
py::arg("body"), cls_doc.GetFreeBodyPose.doc)
395395
.def("SetFreeBodyPose",
396-
overload_cast_explicit<void, Context<T>*, const Body<T>&,
396+
overload_cast_explicit<void, Context<T>*, const RigidBody<T>&,
397397
const RigidTransform<T>&>(&Class::SetFreeBodyPose),
398398
py::arg("context"), py::arg("body"), py::arg("X_WB"),
399399
cls_doc.SetFreeBodyPose.doc_3args)
@@ -464,7 +464,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
464464
cls_doc.GetVelocities.doc_2args)
465465
.def(
466466
"SetFreeBodySpatialVelocity",
467-
[](const Class* self, const Body<T>& body,
467+
[](const Class* self, const RigidBody<T>& body,
468468
const SpatialVelocity<T>& V_WB, Context<T>* context) {
469469
self->SetFreeBodySpatialVelocity(context, body, V_WB);
470470
},
@@ -479,15 +479,15 @@ void DoScalarDependentDefinitions(py::module m, T) {
479479
.def(
480480
"EvalBodyPoseInWorld",
481481
[](const Class* self, const Context<T>& context,
482-
const Body<T>& body_B) {
482+
const RigidBody<T>& body_B) {
483483
return self->EvalBodyPoseInWorld(context, body_B);
484484
},
485485
py::arg("context"), py::arg("body"),
486486
cls_doc.EvalBodyPoseInWorld.doc)
487487
.def(
488488
"EvalBodySpatialVelocityInWorld",
489489
[](const Class* self, const Context<T>& context,
490-
const Body<T>& body_B) {
490+
const RigidBody<T>& body_B) {
491491
return self->EvalBodySpatialVelocityInWorld(context, body_B);
492492
},
493493
py::arg("context"), py::arg("body"),
@@ -783,12 +783,12 @@ void DoScalarDependentDefinitions(py::module m, T) {
783783
.def("GetFrameIndices", &Class::GetFrameIndices,
784784
py::arg("model_instance"), cls_doc.GetFrameIndices.doc)
785785
.def("GetBodyByName",
786-
overload_cast_explicit<const Body<T>&, string_view>(
786+
overload_cast_explicit<const RigidBody<T>&, string_view>(
787787
&Class::GetBodyByName),
788788
py::arg("name"), py_rvp::reference_internal,
789789
cls_doc.GetBodyByName.doc_1args)
790790
.def("GetBodyByName",
791-
overload_cast_explicit<const Body<T>&, string_view,
791+
overload_cast_explicit<const RigidBody<T>&, string_view,
792792
ModelInstanceIndex>(&Class::GetBodyByName),
793793
py::arg("name"), py::arg("model_instance"),
794794
py_rvp::reference_internal, cls_doc.GetBodyByName.doc_2args)
@@ -854,26 +854,27 @@ void DoScalarDependentDefinitions(py::module m, T) {
854854
&Class::RegisterAsSourceForSceneGraph, py::arg("scene_graph"),
855855
cls_doc.RegisterAsSourceForSceneGraph.doc)
856856
.def("RegisterVisualGeometry",
857-
py::overload_cast<const Body<T>&, const RigidTransform<double>&,
858-
const geometry::Shape&, const std::string&,
859-
const Vector4<double>&>(&Class::RegisterVisualGeometry),
857+
py::overload_cast<const RigidBody<T>&,
858+
const RigidTransform<double>&, const geometry::Shape&,
859+
const std::string&, const Vector4<double>&>(
860+
&Class::RegisterVisualGeometry),
860861
py::arg("body"), py::arg("X_BG"), py::arg("shape"), py::arg("name"),
861862
py::arg("diffuse_color"),
862863
cls_doc.RegisterVisualGeometry
863864
.doc_5args_body_X_BG_shape_name_diffuse_color)
864865
.def("RegisterCollisionGeometry",
865-
py::overload_cast<const Body<T>&, const RigidTransform<double>&,
866-
const geometry::Shape&, const std::string&,
867-
geometry::ProximityProperties>(
866+
py::overload_cast<const RigidBody<T>&,
867+
const RigidTransform<double>&, const geometry::Shape&,
868+
const std::string&, geometry::ProximityProperties>(
868869
&Class::RegisterCollisionGeometry),
869870
py::arg("body"), py::arg("X_BG"), py::arg("shape"), py::arg("name"),
870871
py::arg("properties"),
871872
cls_doc.RegisterCollisionGeometry
872873
.doc_5args_body_X_BG_shape_name_properties)
873874
.def("RegisterCollisionGeometry",
874-
py::overload_cast<const Body<T>&, const RigidTransform<double>&,
875-
const geometry::Shape&, const std::string&,
876-
const CoulombFriction<double>&>(
875+
py::overload_cast<const RigidBody<T>&,
876+
const RigidTransform<double>&, const geometry::Shape&,
877+
const std::string&, const CoulombFriction<double>&>(
877878
&Class::RegisterCollisionGeometry),
878879
py::arg("body"), py::arg("X_BG"), py::arg("shape"), py::arg("name"),
879880
py::arg("coulomb_friction"),

bindings/pydrake/multibody/test/plant_test.py

+17-9
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919
)
2020
from pydrake.multibody.tree import (
2121
BallRpyJoint_,
22-
Body_,
22+
Body_, # dispreferred alias for RigidBody_
2323
BodyIndex,
2424
CalcSpatialInertia,
2525
MultibodyConstraintId,
@@ -46,6 +46,7 @@
4646
QuaternionFloatingJoint_,
4747
RevoluteJoint_,
4848
RevoluteSpring_,
49+
RigidBody,
4950
RigidBody_,
5051
RotationalInertia_,
5152
ScopedName,
@@ -61,6 +62,11 @@
6162
world_index,
6263
world_model_instance,
6364
)
65+
# Deprecated, remove 2024-04-01. Just making sure these exist.
66+
from pydrake.multibody.tree import (
67+
BodyFrame,
68+
BodyFrame_,
69+
)
6470
from pydrake.multibody.math import (
6571
SpatialForce_,
6672
SpatialMomentum_,
@@ -140,7 +146,7 @@
140146
def get_index_class(cls, T):
141147
# Maps a class to its corresponding index class, accommdating inheritance.
142148
class_to_index_class_map = {
143-
Body_[T]: BodyIndex,
149+
RigidBody_[T]: BodyIndex,
144150
ForceElement_[T]: ForceElementIndex,
145151
Frame_[T]: FrameIndex,
146152
Joint_[T]: JointIndex,
@@ -320,7 +326,7 @@ def test_casting_and_get_weakref_and_last_body():
320326
def test_multibody_plant_api_via_parsing(self, T):
321327
MultibodyPlant = MultibodyPlant_[T]
322328
Joint = Joint_[T]
323-
Body = Body_[T]
329+
Body = Body_[T] # check that dispreferred alias works
324330
Frame = Frame_[T]
325331
JointActuator = JointActuator_[T]
326332
InputPort = InputPort_[T]
@@ -415,7 +421,7 @@ def check_repr(element, expected):
415421
link1_frame = plant.GetFrameByName(name="Link1")
416422
check_repr(
417423
link1_frame,
418-
"<BodyFrame name='Link1' index=1 model_instance=2>")
424+
"<RigidBodyFrame name='Link1' index=1 model_instance=2>")
419425
self.assertIs(
420426
link1_frame,
421427
plant.GetFrameByName(name="Link1", model_instance=model_instance))
@@ -500,7 +506,7 @@ def _test_frame_api(self, T, frame):
500506
self.assertIsInstance(frame, Frame)
501507
self._test_multibody_tree_element_mixin(T, frame)
502508

503-
self.assertIsInstance(frame.body(), Body_[T])
509+
self.assertIsInstance(frame.body(), RigidBody_[T])
504510
self.assertIsInstance(frame.is_world_frame(), bool)
505511
self.assertIsInstance(frame.is_body_frame(), bool)
506512
self.assertIsInstance(frame.name(), str)
@@ -514,7 +520,7 @@ def _test_frame_api(self, T, frame):
514520
RotationMatrix_[T])
515521

516522
def _test_body_api(self, T, body):
517-
Body = Body_[T]
523+
Body = RigidBody_[T]
518524

519525
self.assertIsInstance(body, Body)
520526
self._test_multibody_tree_element_mixin(T, body)
@@ -564,7 +570,7 @@ def test_body_context_methods(self, T):
564570

565571
def _test_joint_api(self, T, joint):
566572
Joint = Joint_[T]
567-
Body = Body_[T]
573+
Body = RigidBody_[T]
568574
Frame = Frame_[T]
569575

570576
self.assertIsInstance(joint, Joint)
@@ -882,11 +888,13 @@ def test_legacy_unpickle_plant_module(self):
882888

883889
@numpy_compare.check_all_types
884890
def test_rigid_body_api(self, T):
885-
RigidBody = RigidBody_[T]
891+
TemplatedRigidBody = RigidBody_[T]
886892
M = SpatialInertia_[float]()
887893
i = ModelInstanceIndex(0)
894+
TemplatedRigidBody(body_name="body_name", M_BBo_B=M)
895+
TemplatedRigidBody(body_name="body_name", model_instance=i, M_BBo_B=M)
896+
# Make sure the default (float) version also works.
888897
RigidBody(body_name="body_name", M_BBo_B=M)
889-
RigidBody(body_name="body_name", model_instance=i, M_BBo_B=M)
890898

891899
@numpy_compare.check_all_types
892900
def test_multibody_force_element(self, T):

bindings/pydrake/multibody/tree_py.cc

+37-37
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,6 @@
1212
#include "drake/bindings/pydrake/pydrake_pybind.h"
1313
#include "drake/multibody/plant/multibody_plant.h"
1414
#include "drake/multibody/tree/ball_rpy_joint.h"
15-
#include "drake/multibody/tree/body.h"
1615
#include "drake/multibody/tree/door_hinge.h"
1716
#include "drake/multibody/tree/force_element.h"
1817
#include "drake/multibody/tree/frame.h"
@@ -288,11 +287,15 @@ void DoScalarDependentDefinitions(py::module m, T) {
288287
}
289288

290289
{
291-
using Class = BodyFrame<T>;
292-
constexpr auto& cls_doc = doc.BodyFrame;
290+
using Class = RigidBodyFrame<T>;
291+
constexpr auto& cls_doc = doc.RigidBodyFrame;
293292
auto cls = DefineTemplateClassWithDefault<Class, Frame<T>>(
294-
m, "BodyFrame", param, cls_doc.doc);
293+
m, "RigidBodyFrame", param, cls_doc.doc);
295294
// No need to re-bind element mixins from `Frame`.
295+
296+
// TODO(sherm1) This is deprecated; remove 2024-04-01.
297+
m.attr("BodyFrame") = m.attr("RigidBodyFrame");
298+
m.attr("BodyFrame_") = m.attr("RigidBodyFrame_");
296299
}
297300

298301
{
@@ -306,7 +309,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
306309
std::optional<ModelInstanceIndex>>(),
307310
py::arg("name"), py::arg("P"), py::arg("X_PF"),
308311
py::arg("model_instance") = std::nullopt, cls_doc.ctor.doc_4args)
309-
.def(py::init<const std::string&, const Body<T>&,
312+
.def(py::init<const std::string&, const RigidBody<T>&,
310313
const math::RigidTransform<double>&>(),
311314
py::arg("name"), py::arg("bodyB"), py::arg("X_BF"),
312315
cls_doc.ctor.doc_3args)
@@ -317,14 +320,20 @@ void DoScalarDependentDefinitions(py::module m, T) {
317320
py::arg("context"), cls_doc.GetPoseInParentFrame.doc);
318321
}
319322

320-
// Bodies.
323+
// Rigid bodies.
321324
{
322-
using Class = Body<T>;
323-
constexpr auto& cls_doc = doc.Body;
324-
auto cls =
325-
DefineTemplateClassWithDefault<Class>(m, "Body", param, cls_doc.doc);
325+
using Class = RigidBody<T>;
326+
constexpr auto& cls_doc = doc.RigidBody;
327+
auto cls = DefineTemplateClassWithDefault<Class>(
328+
m, "RigidBody", param, cls_doc.doc);
326329
BindMultibodyElementMixin<T>(&cls);
327330
cls // BR
331+
.def(py::init<const std::string&, const SpatialInertia<double>&>(),
332+
py::arg("body_name"), py::arg("M_BBo_B"), cls_doc.ctor.doc_2args)
333+
.def(py::init<const std::string&, ModelInstanceIndex,
334+
const SpatialInertia<double>&>(),
335+
py::arg("body_name"), py::arg("model_instance"), py::arg("M_BBo_B"),
336+
cls_doc.ctor.doc_3args)
328337
.def("name", &Class::name, cls_doc.name.doc)
329338
.def("scoped_name", &Class::scoped_name, cls_doc.scoped_name.doc)
330339
.def("body_frame", &Class::body_frame, py_rvp::reference_internal,
@@ -366,31 +375,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
366375
.def("Lock", &Class::Lock, py::arg("context"), cls_doc.Lock.doc)
367376
.def("Unlock", &Class::Unlock, py::arg("context"), cls_doc.Unlock.doc)
368377
.def("is_locked", &Class::is_locked, py::arg("context"),
369-
cls_doc.is_locked.doc);
370-
371-
// TODO(sherm1) Remove as of 2024-02-01.
372-
#pragma GCC diagnostic push
373-
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
374-
cls // BR
375-
.def("floating_velocities_start",
376-
WrapDeprecated(cls_doc.floating_velocities_start.doc_deprecated,
377-
&Class::floating_velocities_start),
378-
cls_doc.floating_velocities_start.doc_deprecated);
379-
#pragma GCC diagnostic pop
380-
}
381-
382-
{
383-
using Class = RigidBody<T>;
384-
constexpr auto& cls_doc = doc.RigidBody;
385-
auto cls = DefineTemplateClassWithDefault<Class, Body<T>>(
386-
m, "RigidBody", param, cls_doc.doc);
387-
cls // BR
388-
.def(py::init<const std::string&, const SpatialInertia<double>&>(),
389-
py::arg("body_name"), py::arg("M_BBo_B"), cls_doc.ctor.doc_2args)
390-
.def(py::init<const std::string&, ModelInstanceIndex,
391-
const SpatialInertia<double>&>(),
392-
py::arg("body_name"), py::arg("model_instance"), py::arg("M_BBo_B"),
393-
cls_doc.ctor.doc_3args)
378+
cls_doc.is_locked.doc)
394379
.def("default_mass", &Class::default_mass, cls_doc.default_mass.doc)
395380
.def("default_com", &Class::default_com, py_rvp::reference_internal,
396381
cls_doc.default_com.doc)
@@ -408,6 +393,20 @@ void DoScalarDependentDefinitions(py::module m, T) {
408393
.def("SetSpatialInertiaInBodyFrame",
409394
&Class::SetSpatialInertiaInBodyFrame, py::arg("context"),
410395
py::arg("M_Bo_B"), cls_doc.SetSpatialInertiaInBodyFrame.doc);
396+
397+
// TODO(sherm1) Remove as of 2024-02-01.
398+
#pragma GCC diagnostic push
399+
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
400+
cls // BR
401+
.def("floating_velocities_start",
402+
WrapDeprecated(cls_doc.floating_velocities_start.doc_deprecated,
403+
&Class::floating_velocities_start),
404+
cls_doc.floating_velocities_start.doc_deprecated);
405+
#pragma GCC diagnostic pop
406+
407+
// Aliases for backwards compatibility (dispreferred).
408+
m.attr("Body") = m.attr("RigidBody");
409+
m.attr("Body_") = m.attr("RigidBody_");
411410
}
412411

413412
// Joints.
@@ -888,8 +887,9 @@ void DoScalarDependentDefinitions(py::module m, T) {
888887
auto cls = DefineTemplateClassWithDefault<Class, ForceElement<T>>(
889888
m, "LinearSpringDamper", param, cls_doc.doc);
890889
cls // BR
891-
.def(py::init<const Body<T>&, const Vector3<double>&, const Body<T>&,
892-
const Vector3<double>&, double, double, double>(),
890+
.def(py::init<const RigidBody<T>&, const Vector3<double>&,
891+
const RigidBody<T>&, const Vector3<double>&, double, double,
892+
double>(),
893893
py::arg("bodyA"), py::arg("p_AP"), py::arg("bodyB"),
894894
py::arg("p_BQ"), py::arg("free_length"), py::arg("stiffness"),
895895
py::arg("damping"), cls_doc.ctor.doc)

bindings/pydrake/planning/planning_py_collision_checker.cc

+11-10
Original file line numberDiff line numberDiff line change
@@ -11,9 +11,9 @@ namespace drake {
1111
namespace pydrake {
1212
namespace internal {
1313

14-
using multibody::Body;
1514
using multibody::BodyIndex;
1615
using multibody::Frame;
16+
using multibody::RigidBody;
1717

1818
void DefinePlanningCollisionChecker(py::module m) {
1919
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
@@ -34,7 +34,7 @@ void DefinePlanningCollisionChecker(py::module m) {
3434
.def("robot_model_instances", &Class::robot_model_instances,
3535
cls_doc.robot_model_instances.doc)
3636
.def("IsPartOfRobot",
37-
overload_cast_explicit<bool, const Body<double>&>(
37+
overload_cast_explicit<bool, const RigidBody<double>&>(
3838
&Class::IsPartOfRobot),
3939
py::arg("body"), cls_doc.IsPartOfRobot.doc)
4040
.def("IsPartOfRobot",
@@ -107,8 +107,8 @@ void DefinePlanningCollisionChecker(py::module m) {
107107
py::arg("bodyA_index"), py::arg("bodyB_index"),
108108
cls_doc.GetPaddingBetween.doc_2args_bodyA_index_bodyB_index)
109109
.def("GetPaddingBetween",
110-
overload_cast_explicit<double, const Body<double>&,
111-
const Body<double>&>(&Class::GetPaddingBetween),
110+
overload_cast_explicit<double, const RigidBody<double>&,
111+
const RigidBody<double>&>(&Class::GetPaddingBetween),
112112
py::arg("bodyA"), py::arg("bodyB"),
113113
cls_doc.GetPaddingBetween.doc_2args_bodyA_bodyB)
114114
.def("SetPaddingBetween",
@@ -117,8 +117,8 @@ void DefinePlanningCollisionChecker(py::module m) {
117117
py::arg("bodyA_index"), py::arg("bodyB_index"), py::arg("padding"),
118118
cls_doc.SetPaddingBetween.doc_3args_bodyA_index_bodyB_index_padding)
119119
.def("SetPaddingBetween",
120-
py::overload_cast<const Body<double>&, const Body<double>&, double>(
121-
&Class::SetPaddingBetween),
120+
py::overload_cast<const RigidBody<double>&,
121+
const RigidBody<double>&, double>(&Class::SetPaddingBetween),
122122
py::arg("bodyA"), py::arg("bodyB"), py::arg("padding"),
123123
cls_doc.SetPaddingBetween.doc_3args_bodyA_bodyB_padding)
124124
.def("GetPaddingMatrix", &Class::GetPaddingMatrix,
@@ -152,8 +152,8 @@ void DefinePlanningCollisionChecker(py::module m) {
152152
cls_doc.IsCollisionFilteredBetween
153153
.doc_2args_bodyA_index_bodyB_index)
154154
.def("IsCollisionFilteredBetween",
155-
overload_cast_explicit<bool, const Body<double>&,
156-
const Body<double>&>(&Class::IsCollisionFilteredBetween),
155+
overload_cast_explicit<bool, const RigidBody<double>&,
156+
const RigidBody<double>&>(&Class::IsCollisionFilteredBetween),
157157
py::arg("bodyA"), py::arg("bodyB"),
158158
cls_doc.IsCollisionFilteredBetween.doc_2args_bodyA_bodyB)
159159
.def("SetCollisionFilteredBetween",
@@ -164,7 +164,8 @@ void DefinePlanningCollisionChecker(py::module m) {
164164
cls_doc.SetCollisionFilteredBetween
165165
.doc_3args_bodyA_index_bodyB_index_filter_collision)
166166
.def("SetCollisionFilteredBetween",
167-
py::overload_cast<const Body<double>&, const Body<double>&, bool>(
167+
py::overload_cast<const RigidBody<double>&,
168+
const RigidBody<double>&, bool>(
168169
&Class::SetCollisionFilteredBetween),
169170
py::arg("bodyA"), py::arg("bodyB"), py::arg("filter_collision"),
170171
cls_doc.SetCollisionFilteredBetween
@@ -175,7 +176,7 @@ void DefinePlanningCollisionChecker(py::module m) {
175176
py::arg("body_index"),
176177
cls_doc.SetCollisionFilteredWithAllBodies.doc_1args_body_index)
177178
.def("SetCollisionFilteredWithAllBodies",
178-
py::overload_cast<const Body<double>&>(
179+
py::overload_cast<const RigidBody<double>&>(
179180
&Class::SetCollisionFilteredWithAllBodies),
180181
py::arg("body"),
181182
cls_doc.SetCollisionFilteredWithAllBodies.doc_1args_body)

0 commit comments

Comments
 (0)