12
12
#include " drake/bindings/pydrake/pydrake_pybind.h"
13
13
#include " drake/multibody/plant/multibody_plant.h"
14
14
#include " drake/multibody/tree/ball_rpy_joint.h"
15
- #include " drake/multibody/tree/body.h"
16
15
#include " drake/multibody/tree/door_hinge.h"
17
16
#include " drake/multibody/tree/force_element.h"
18
17
#include " drake/multibody/tree/frame.h"
@@ -288,11 +287,14 @@ void DoScalarDependentDefinitions(py::module m, T) {
288
287
}
289
288
290
289
{
291
- using Class = BodyFrame <T>;
292
- constexpr auto & cls_doc = doc.BodyFrame ;
290
+ using Class = RigidBodyFrame <T>;
291
+ constexpr auto & cls_doc = doc.RigidBodyFrame ;
293
292
auto cls = DefineTemplateClassWithDefault<Class, Frame<T>>(
294
- m, " BodyFrame " , param, cls_doc.doc );
293
+ m, " RigidBodyFrame " , param, cls_doc.doc );
295
294
// No need to re-bind element mixins from `Frame`.
295
+
296
+ // TODO(sherm1) Deprecate this alias. But how?
297
+ m.attr (" BodyFrame" ) = m.attr (" RigidBodyFrame" );
296
298
}
297
299
298
300
{
@@ -306,7 +308,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
306
308
std::optional<ModelInstanceIndex>>(),
307
309
py::arg (" name" ), py::arg (" P" ), py::arg (" X_PF" ),
308
310
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>&,
310
312
const math::RigidTransform<double >&>(),
311
313
py::arg (" name" ), py::arg (" bodyB" ), py::arg (" X_BF" ),
312
314
cls_doc.ctor .doc_3args )
@@ -317,14 +319,20 @@ void DoScalarDependentDefinitions(py::module m, T) {
317
319
py::arg (" context" ), cls_doc.GetPoseInParentFrame .doc );
318
320
}
319
321
320
- // Bodies .
322
+ // Rigid bodies .
321
323
{
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 );
326
328
BindMultibodyElementMixin<T>(&cls);
327
329
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 )
328
336
.def (" name" , &Class::name, cls_doc.name .doc )
329
337
.def (" scoped_name" , &Class::scoped_name, cls_doc.scoped_name .doc )
330
338
.def (" body_frame" , &Class::body_frame, py_rvp::reference_internal,
@@ -366,31 +374,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
366
374
.def (" Lock" , &Class::Lock, py::arg (" context" ), cls_doc.Lock .doc )
367
375
.def (" Unlock" , &Class::Unlock, py::arg (" context" ), cls_doc.Unlock .doc )
368
376
.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 )
394
378
.def (" default_mass" , &Class::default_mass, cls_doc.default_mass .doc )
395
379
.def (" default_com" , &Class::default_com, py_rvp::reference_internal,
396
380
cls_doc.default_com .doc )
@@ -408,6 +392,20 @@ void DoScalarDependentDefinitions(py::module m, T) {
408
392
.def (" SetSpatialInertiaInBodyFrame" ,
409
393
&Class::SetSpatialInertiaInBodyFrame, py::arg (" context" ),
410
394
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_" );
411
409
}
412
410
413
411
// Joints.
@@ -888,8 +886,9 @@ void DoScalarDependentDefinitions(py::module m, T) {
888
886
auto cls = DefineTemplateClassWithDefault<Class, ForceElement<T>>(
889
887
m, " LinearSpringDamper" , param, cls_doc.doc );
890
888
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 >(),
893
892
py::arg (" bodyA" ), py::arg (" p_AP" ), py::arg (" bodyB" ),
894
893
py::arg (" p_BQ" ), py::arg (" free_length" ), py::arg (" stiffness" ),
895
894
py::arg (" damping" ), cls_doc.ctor .doc )
0 commit comments