Skip to content

Commit c7c1984

Browse files
committed
Eliminate Body base class in favor of RigidBody
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 6be045b commit c7c1984

File tree

161 files changed

+1702
-1958
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

+1702
-1958
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

+7-7
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,
@@ -140,7 +140,7 @@
140140
def get_index_class(cls, T):
141141
# Maps a class to its corresponding index class, accommdating inheritance.
142142
class_to_index_class_map = {
143-
Body_[T]: BodyIndex,
143+
RigidBody_[T]: BodyIndex,
144144
ForceElement_[T]: ForceElementIndex,
145145
Frame_[T]: FrameIndex,
146146
Joint_[T]: JointIndex,
@@ -320,7 +320,7 @@ def test_casting_and_get_weakref_and_last_body():
320320
def test_multibody_plant_api_via_parsing(self, T):
321321
MultibodyPlant = MultibodyPlant_[T]
322322
Joint = Joint_[T]
323-
Body = Body_[T]
323+
Body = Body_[T] # check that dispreferred alias works
324324
Frame = Frame_[T]
325325
JointActuator = JointActuator_[T]
326326
InputPort = InputPort_[T]
@@ -415,7 +415,7 @@ def check_repr(element, expected):
415415
link1_frame = plant.GetFrameByName(name="Link1")
416416
check_repr(
417417
link1_frame,
418-
"<BodyFrame name='Link1' index=1 model_instance=2>")
418+
"<RigidBodyFrame name='Link1' index=1 model_instance=2>")
419419
self.assertIs(
420420
link1_frame,
421421
plant.GetFrameByName(name="Link1", model_instance=model_instance))
@@ -500,7 +500,7 @@ def _test_frame_api(self, T, frame):
500500
self.assertIsInstance(frame, Frame)
501501
self._test_multibody_tree_element_mixin(T, frame)
502502

503-
self.assertIsInstance(frame.body(), Body_[T])
503+
self.assertIsInstance(frame.body(), RigidBody_[T])
504504
self.assertIsInstance(frame.is_world_frame(), bool)
505505
self.assertIsInstance(frame.is_body_frame(), bool)
506506
self.assertIsInstance(frame.name(), str)
@@ -514,7 +514,7 @@ def _test_frame_api(self, T, frame):
514514
RotationMatrix_[T])
515515

516516
def _test_body_api(self, T, body):
517-
Body = Body_[T]
517+
Body = RigidBody_[T]
518518

519519
self.assertIsInstance(body, Body)
520520
self._test_multibody_tree_element_mixin(T, body)
@@ -564,7 +564,7 @@ def test_body_context_methods(self, T):
564564

565565
def _test_joint_api(self, T, joint):
566566
Joint = Joint_[T]
567-
Body = Body_[T]
567+
Body = RigidBody_[T]
568568
Frame = Frame_[T]
569569

570570
self.assertIsInstance(joint, Joint)

bindings/pydrake/multibody/tree_py.cc

+36-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,14 @@ 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");
296298
}
297299

298300
{
@@ -306,7 +308,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
306308
std::optional<ModelInstanceIndex>>(),
307309
py::arg("name"), py::arg("P"), py::arg("X_PF"),
308310
py::arg("model_instance") = std::nullopt, cls_doc.ctor.doc_4args)
309-
.def(py::init<const std::string&, const Body<T>&,
311+
.def(py::init<const std::string&, const RigidBody<T>&,
310312
const math::RigidTransform<double>&>(),
311313
py::arg("name"), py::arg("bodyB"), py::arg("X_BF"),
312314
cls_doc.ctor.doc_3args)
@@ -317,14 +319,20 @@ void DoScalarDependentDefinitions(py::module m, T) {
317319
py::arg("context"), cls_doc.GetPoseInParentFrame.doc);
318320
}
319321

320-
// Bodies.
322+
// Rigid bodies.
321323
{
322-
using Class = Body<T>;
323-
constexpr auto& cls_doc = doc.Body;
324-
auto cls =
325-
DefineTemplateClassWithDefault<Class>(m, "Body", param, cls_doc.doc);
324+
using Class = RigidBody<T>;
325+
constexpr auto& cls_doc = doc.RigidBody;
326+
auto cls = DefineTemplateClassWithDefault<Class>(
327+
m, "RigidBody", param, cls_doc.doc);
326328
BindMultibodyElementMixin<T>(&cls);
327329
cls // BR
330+
.def(py::init<const std::string&, const SpatialInertia<double>&>(),
331+
py::arg("body_name"), py::arg("M_BBo_B"), cls_doc.ctor.doc_2args)
332+
.def(py::init<const std::string&, ModelInstanceIndex,
333+
const SpatialInertia<double>&>(),
334+
py::arg("body_name"), py::arg("model_instance"), py::arg("M_BBo_B"),
335+
cls_doc.ctor.doc_3args)
328336
.def("name", &Class::name, cls_doc.name.doc)
329337
.def("scoped_name", &Class::scoped_name, cls_doc.scoped_name.doc)
330338
.def("body_frame", &Class::body_frame, py_rvp::reference_internal,
@@ -366,31 +374,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
366374
.def("Lock", &Class::Lock, py::arg("context"), cls_doc.Lock.doc)
367375
.def("Unlock", &Class::Unlock, py::arg("context"), cls_doc.Unlock.doc)
368376
.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)
377+
cls_doc.is_locked.doc)
394378
.def("default_mass", &Class::default_mass, cls_doc.default_mass.doc)
395379
.def("default_com", &Class::default_com, py_rvp::reference_internal,
396380
cls_doc.default_com.doc)
@@ -408,6 +392,20 @@ void DoScalarDependentDefinitions(py::module m, T) {
408392
.def("SetSpatialInertiaInBodyFrame",
409393
&Class::SetSpatialInertiaInBodyFrame, py::arg("context"),
410394
py::arg("M_Bo_B"), cls_doc.SetSpatialInertiaInBodyFrame.doc);
395+
396+
// TODO(sherm1) Remove as of 2024-02-01.
397+
#pragma GCC diagnostic push
398+
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
399+
cls // BR
400+
.def("floating_velocities_start",
401+
WrapDeprecated(cls_doc.floating_velocities_start.doc_deprecated,
402+
&Class::floating_velocities_start),
403+
cls_doc.floating_velocities_start.doc_deprecated);
404+
#pragma GCC diagnostic pop
405+
406+
// Aliases for backwards compatibility (dispreferred).
407+
m.attr("Body") = m.attr("RigidBody");
408+
m.attr("Body_") = m.attr("RigidBody_");
411409
}
412410

413411
// Joints.
@@ -888,8 +886,9 @@ void DoScalarDependentDefinitions(py::module m, T) {
888886
auto cls = DefineTemplateClassWithDefault<Class, ForceElement<T>>(
889887
m, "LinearSpringDamper", param, cls_doc.doc);
890888
cls // BR
891-
.def(py::init<const Body<T>&, const Vector3<double>&, const Body<T>&,
892-
const Vector3<double>&, double, double, double>(),
889+
.def(py::init<const RigidBody<T>&, const Vector3<double>&,
890+
const RigidBody<T>&, const Vector3<double>&, double, double,
891+
double>(),
893892
py::arg("bodyA"), py::arg("p_AP"), py::arg("bodyB"),
894893
py::arg("p_BQ"), py::arg("free_length"), py::arg("stiffness"),
895894
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)

bindings/pydrake/visualization/_triad.py

+3-3
Original file line numberDiff line numberDiff line change
@@ -10,13 +10,13 @@
1010
)
1111
from pydrake.math import RigidTransform
1212
from pydrake.multibody.plant import MultibodyPlant
13-
from pydrake.multibody.tree import Body
13+
from pydrake.multibody.tree import RigidBody
1414

1515

1616
def AddFrameTriadIllustration(
1717
*,
1818
scene_graph: SceneGraph,
19-
body: Body = None,
19+
body: RigidBody = None,
2020
frame_id: FrameId = None,
2121
plant: MultibodyPlant = None,
2222
name: str = "frame",
@@ -28,7 +28,7 @@ def AddFrameTriadIllustration(
2828
"""
2929
Adds illustration geometry representing the given frame using an RGB triad,
3030
with the x-axis drawn in red, the y-axis in green and the z-axis in blue.
31-
The given frame can be either a geometry FrameId or a multibody Body.
31+
The given frame can be either a geometry FrameId or a multibody RigidBody.
3232
3333
Args:
3434
scene_graph: the SceneGraph where geometry will be added.

examples/allegro_hand/joint_control/allegro_single_object_simulation.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -257,12 +257,12 @@ void DoMain() {
257257
diagram->SetDefaultContext(diagram_context.get());
258258

259259
// Set the position of object
260-
const multibody::Body<double>& hand = plant.GetBodyByName("hand_root");
260+
const multibody::RigidBody<double>& hand = plant.GetBodyByName("hand_root");
261261
systems::Context<double>& plant_context =
262262
diagram->GetMutableSubsystemContext(plant, diagram_context.get());
263263

264264
// Initialize the mug pose to be right in the middle between the fingers.
265-
const multibody::Body<double>& mug = plant.GetBodyByName("simple_mug");
265+
const multibody::RigidBody<double>& mug = plant.GetBodyByName("simple_mug");
266266
const Eigen::Vector3d& p_WHand =
267267
plant.EvalBodyPoseInWorld(plant_context, hand).translation();
268268
RigidTransformd X_WM(

examples/atlas/atlas_run_dynamics.cc

+2-1
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,8 @@ int do_main() {
8282

8383
// Verify the "pelvis" body is free and modeled with quaternions dofs before
8484
// moving on with that assumption.
85-
const drake::multibody::Body<double>& pelvis = plant.GetBodyByName("pelvis");
85+
const drake::multibody::RigidBody<double>& pelvis =
86+
plant.GetBodyByName("pelvis");
8687
DRAKE_DEMAND(pelvis.is_floating());
8788
DRAKE_DEMAND(pelvis.has_quaternion_dofs());
8889
// Since there is a single floating body, we know that the positions for it

0 commit comments

Comments
 (0)