Skip to content

Commit 8a9436a

Browse files
committed
Removed references to deprecated Body class
1 parent 92f235f commit 8a9436a

19 files changed

+96
-134
lines changed

examples/simple_gripper/simple_gripper.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -121,7 +121,7 @@ const double kPadMinorRadius = 6e-3; // 6 mm.
121121
// @param[in] pad_offset the ring offset along the x-axis in the finger
122122
// coordinate frame, i.e., how far the ring protrudes from the center of the
123123
// finger.
124-
// @param[in] finger the Body representing the finger
124+
// @param[in] finger the RigidBody representing the finger
125125
void AddGripperPads(MultibodyPlant<double>* plant, const double pad_offset,
126126
const RigidBody<double>& finger) {
127127
const int sample_count = FLAGS_ring_samples;

manipulation/util/make_arm_controller_model.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -106,7 +106,7 @@ std::unique_ptr<MultibodyPlant<double>> MakeArmControllerModel(
106106
for (const RigidBody<double>* welded_body : sim_gripper_welded_bodies) {
107107
if ((welded_body->model_instance() != gripper_info->model_instance) &&
108108
(welded_body->model_instance() != arm_info.model_instance)) {
109-
log()->debug("Adding BodyIndex of Body {}", welded_body->name());
109+
log()->debug("Adding BodyIndex of RigidBody {}", welded_body->name());
110110
sim_gripper_body_indices.push_back(welded_body->index());
111111
}
112112
}

multibody/multibody_doxygen.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -214,7 +214,7 @@ combination of `w_AB` and `v_AB`.
214214
See @ref multibody_quantities for more information about notation.
215215
216216
Each _body_ contains a _body frame_ and we use the same symbol `B` for both a
217-
body `B` and its body frame. Body B's location is defined via `Bo` (the
217+
body `B` and its body frame. Body B's location is defined via `Bo` (the
218218
origin of the body frame) and body B's pose is defined via the pose of B's
219219
body frame. Body properties (e.g., inertia and geometry) are measured with
220220
respect to the body frame. Body B's center of mass is denoted `Bcm`

multibody/plant/multibody_plant.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -3408,8 +3408,8 @@ void MultibodyPlant<T>::CalcFramePoseOutput(const Context<T>& context,
34083408
// NOTE: The body index to frame id map *always* includes the world body but
34093409
// the world body does *not* get reported in the frame poses; only dynamic
34103410
// frames do.
3411-
// TODO(amcastro-tri): Make use of Body::EvalPoseInWorld(context) once caching
3412-
// lands.
3411+
// TODO(amcastro-tri): Make use of RigidBody::EvalPoseInWorld(context) once
3412+
// caching lands.
34133413
poses->clear();
34143414
for (const auto& it : body_index_to_frame_id_) {
34153415
const BodyIndex body_index = it.first;

multibody/plant/multibody_plant.h

+25-25
Original file line numberDiff line numberDiff line change
@@ -1153,7 +1153,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
11531153
/// @param[in] name
11541154
/// A string that identifies the new body to be added to `this` model. A
11551155
/// std::runtime_error is thrown if a body named `name` already is part of
1156-
/// @p model_instance. See HasBodyNamed(), Body::name().
1156+
/// @p model_instance. See HasBodyNamed(), RigidBody::name().
11571157
/// @param[in] model_instance
11581158
/// A model instance index which this body is part of.
11591159
/// @param[in] M_BBo_B
@@ -1200,7 +1200,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
12001200
/// A string that identifies the new body to be added to `this` model. A
12011201
/// std::runtime_error is thrown if a body named `name` already is part of
12021202
/// the model in the default model instance. See HasBodyNamed(),
1203-
/// Body::name().
1203+
/// RigidBody::name().
12041204
/// @param[in] M_BBo_B
12051205
/// The SpatialInertia of the new rigid body to be added to `this`
12061206
/// %MultibodyPlant, computed about the body frame origin `Bo` and expressed
@@ -1305,7 +1305,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
13051305
/// plant.AddRigidBody("Body1", SpatialInertia<double>(...));
13061306
/// const RigidBody<double>& body_2 =
13071307
/// plant.AddRigidBody("Body2", SpatialInertia<double>(...));
1308-
/// // Body 1 serves as parent, Body 2 serves as child.
1308+
/// // RigidBody 1 serves as parent, RigidBody 2 serves as child.
13091309
/// // Define the pose X_BM of a frame M rigidly attached to child body B.
13101310
/// const RevoluteJoint<double>& elbow =
13111311
/// plant.AddJoint<RevoluteJoint>(
@@ -1632,9 +1632,9 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
16321632
///
16331633
/// f = −stiffness ⋅ d − damping ⋅ ḋ
16341634
///
1635-
/// @param[in] body_A Body to which point P is rigidly attached.
1635+
/// @param[in] body_A RigidBody to which point P is rigidly attached.
16361636
/// @param[in] p_AP Position of point P in body A's frame.
1637-
/// @param[in] body_B Body to which point Q is rigidly attached.
1637+
/// @param[in] body_B RigidBody to which point Q is rigidly attached.
16381638
/// @param[in] p_BQ Position of point Q in body B's frame.
16391639
/// @param[in] distance Fixed length of the distance constraint, in meters. It
16401640
/// must be strictly positive.
@@ -1677,9 +1677,9 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
16771677
/// all times with point Q affixed to body B, effectively modeling a
16781678
/// ball-and-socket joint.
16791679
///
1680-
/// @param[in] body_A Body to which point P is rigidly attached.
1680+
/// @param[in] body_A RigidBody to which point P is rigidly attached.
16811681
/// @param[in] p_AP Position of point P in body A's frame.
1682-
/// @param[in] body_B Body to which point Q is rigidly attached.
1682+
/// @param[in] body_B RigidBody to which point Q is rigidly attached.
16831683
/// @param[in] p_BQ Position of point Q in body B's frame.
16841684
/// @returns the id of the newly added constraint.
16851685
///
@@ -1699,9 +1699,9 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
16991699
/// all times with frame Q affixed to body B, effectively modeling a weld
17001700
/// joint.
17011701
///
1702-
/// @param[in] body_A Body to which frame P is rigidly attached.
1702+
/// @param[in] body_A RigidBody to which frame P is rigidly attached.
17031703
/// @param[in] X_AP Pose of frame P in body A's frame.
1704-
/// @param[in] body_B Body to which frame Q is rigidly attached.
1704+
/// @param[in] body_B RigidBody to which frame Q is rigidly attached.
17051705
/// @param[in] X_BQ Pose of frame Q in body B's frame.
17061706
/// @returns the id of the newly added constraint.
17071707
///
@@ -1780,8 +1780,8 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
17801780
/// when %MultibodyPlant registers the corresponding SceneGraph frame, it is
17811781
/// named with a "scoped name". This is a concatenation of
17821782
/// `[model instance name]::[body name]`. Searching for a frame with just the
1783-
/// name `body name` will fail. (See Body::name() and GetModelInstanceName()
1784-
/// for those values.)
1783+
/// name `body name` will fail. (See RigidBody::name() and
1784+
/// GetModelInstanceName() for those values.)
17851785
/// @{
17861786

17871787
/// Registers `this` plant to serve as a source for an instance of
@@ -3093,8 +3093,8 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
30933093
/// @anchor mbp_working_with_free_bodies
30943094
/// @name Working with free bodies
30953095
///
3096-
/// A %MultibodyPlant user adds sets of Body and Joint objects to `this` plant
3097-
/// to build a physical representation of a mechanical model.
3096+
/// A %MultibodyPlant user adds sets of RigidBody and Joint objects to `this`
3097+
/// plant to build a physical representation of a mechanical model.
30983098
/// At Finalize(), %MultibodyPlant builds a mathematical representation of
30993099
/// such system, consisting of a tree representation. In this
31003100
/// representation each body is assigned a Mobilizer, which grants a certain
@@ -3104,12 +3104,12 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
31043104
/// tree. If the root body has six degrees of freedom with respect to the
31053105
/// world, it is called a "free body" (sometimes called a "floating body").
31063106
/// A user can request the set of all free bodies with a call to
3107-
/// GetFloatingBaseBodies(). Alternatively, a user can query whether a Body is
3108-
/// free (floating) or not with Body::is_floating().
3107+
/// GetFloatingBaseBodies(). Alternatively, a user can query whether a
3108+
/// RigidBody is free (floating) or not with RigidBody::is_floating().
31093109
/// For many applications, a user might need to work with indexes in the
31103110
/// multibody state vector. For such applications,
3111-
/// Body::floating_positions_start() and
3112-
/// Body::floating_velocities_start_in_v() offer the additional level of
3111+
/// RigidBody::floating_positions_start() and
3112+
/// RigidBody::floating_velocities_start_in_v() offer the additional level of
31133113
/// introspection needed.
31143114
///
31153115
/// It is sometimes convenient for users to perform operations on Bodies
@@ -3118,7 +3118,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
31183118
/// bodies at the time of Finalize(). Using Joint APIs to affect a free body
31193119
/// (setting state, changing parameters, etc.) has the same effect as using
31203120
/// the free body APIs below. Each implicitly created joint is named the same
3121-
/// as the free body, as reported by `Body::name()`. In the rare case that
3121+
/// as the free body, as reported by `RigidBody::name()`. In the rare case that
31223122
/// there is already some (unrelated) joint with that name, we'll prepend
31233123
/// underscores to the name until it is unique.
31243124
/// @{
@@ -3174,7 +3174,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
31743174
/// effect of the call is that the value will be echoed back in
31753175
/// GetDefaultFreeBodyPose().
31763176
/// @param[in] body
3177-
/// Body whose default pose will be set.
3177+
/// RigidBody whose default pose will be set.
31783178
/// @param[in] X_WB
31793179
/// Default pose of the body.
31803180
void SetDefaultFreeBodyPose(const RigidBody<T>& body,
@@ -3185,7 +3185,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
31853185
/// Gets the default pose of `body` as set by SetDefaultFreeBodyPose(). If no
31863186
/// pose is specified for the body, returns the identity pose.
31873187
/// @param[in] body
3188-
/// Body whose default pose will be retrieved.
3188+
/// RigidBody whose default pose will be retrieved.
31893189
math::RigidTransform<double> GetDefaultFreeBodyPose(
31903190
const RigidBody<T>& body) const {
31913191
return internal_tree().GetDefaultFreeBodyPose(body);
@@ -3331,7 +3331,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
33313331
/// Evaluates V_WB, body B's spatial velocity in the world frame W.
33323332
/// @param[in] context The context storing the state of the model.
33333333
/// @param[in] body_B The body B for which the spatial velocity is requested.
3334-
/// @retval V_WB_W Body B's spatial velocity in the world frame W,
3334+
/// @retval V_WB_W RigidBody B's spatial velocity in the world frame W,
33353335
/// expressed in W (for point Bo, the body's origin).
33363336
/// @throws std::exception if Finalize() was not called on `this` model or
33373337
/// if `body_B` does not belong to this model.
@@ -3344,7 +3344,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
33443344
/// Evaluates A_WB, body B's spatial acceleration in the world frame W.
33453345
/// @param[in] context The context storing the state of the model.
33463346
/// @param[in] body_B The body for which spatial acceleration is requested.
3347-
/// @retval A_WB_W Body B's spatial acceleration in the world frame W,
3347+
/// @retval A_WB_W RigidBody B's spatial acceleration in the world frame W,
33483348
/// expressed in W (for point Bo, the body's origin).
33493349
/// @throws std::exception if Finalize() was not called on `this` model or
33503350
/// if `body_B` does not belong to this model.
@@ -3787,7 +3787,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
37873787
/// spatial forces F on each body, refer to documentation in MultibodyForces
37883788
/// for details. Users of MultibodyForces will use
37893789
/// MultibodyForces::mutable_generalized_forces() to mutate the stored
3790-
/// generalized forces directly and will use Body::AddInForceInWorld() to
3790+
/// generalized forces directly and will use RigidBody::AddInForceInWorld() to
37913791
/// append spatial forces.
37923792
///
37933793
/// For a given set of forces stored as MultibodyForces, this method will
@@ -4589,7 +4589,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
45894589
/// @see HasBodyNamed() to query if there exists a body in `this`
45904590
/// %MultibodyPlant with a given specified name.
45914591
const RigidBody<T>& GetBodyByName(std::string_view name) const {
4592-
return internal_tree().GetBodyByName(name);
4592+
return internal_tree().GetRigidBodyByName(name);
45934593
}
45944594

45954595
/// Returns a constant reference to the body that is uniquely identified
@@ -4599,7 +4599,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
45994599
/// %MultibodyPlant with a given specified name.
46004600
const RigidBody<T>& GetBodyByName(std::string_view name,
46014601
ModelInstanceIndex model_instance) const {
4602-
return internal_tree().GetBodyByName(name, model_instance);
4602+
return internal_tree().GetRigidBodyByName(name, model_instance);
46034603
}
46044604

46054605
/// Returns a list of body indices associated with `model_instance`.

multibody/plant/propeller.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -25,8 +25,8 @@ struct PropellerInfo {
2525
thrust_ratio(thrust_ratio_),
2626
moment_ratio(moment_ratio_) {}
2727

28-
/** The BodyIndex of a Body in the MultibodyPlant to which the propeller is
29-
attached. The spatial forces will be applied to this body. */
28+
/** The BodyIndex of a RigidBody in the MultibodyPlant to which the propeller
29+
is attached. The spatial forces will be applied to this body. */
3030
BodyIndex body_index;
3131

3232
/** Pose of the propeller frame P measured in the body frame B. @default is

multibody/plant/test/frame_kinematics_test.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -341,7 +341,7 @@ TEST_F(KukaIiwaModelTests, CalcSpatialAcceleration) {
341341
*end_effector_link_);
342342
EXPECT_EQ(A_WE_W.get_coeffs(), A_WE_W_expected1.get_coeffs());
343343

344-
// Also verify A_WE_W against Body::EvalSpatialAccelerationInWorld().
344+
// Also verify A_WE_W against RigidBody::EvalSpatialAccelerationInWorld().
345345
const SpatialAcceleration<double> A_WE_W_expected2 =
346346
end_effector_link_->EvalSpatialAccelerationInWorld(*context_);
347347
EXPECT_EQ(A_WE_W.get_coeffs(), A_WE_W_expected2.get_coeffs());

multibody/plant/test/multibody_plant_jacobians_test.cc

+2-2
Original file line numberDiff line numberDiff line change
@@ -508,8 +508,8 @@ TEST_F(TwoDOFPlanarPendulumTest,
508508
const RigidBody<double>& body_A = rigid_bodyA();
509509
const RigidBody<double>& body_B = rigid_bodyB();
510510

511-
// Verify Body::CalcCenterOfMassTranslationalVelocityInWorld() with by-hand
512-
// results for translational velocities measured in the world frame W:
511+
// Verify RigidBody::CalcCenterOfMassTranslationalVelocityInWorld() with
512+
// by-hand results for translational velocities measured in the world frame W:
513513
// Acm's translational velocity: v_WAcm_W = 0.5 L wAz_ Wy.
514514
// Bcm's translational velocity: v_WBcm_W = (0.5 L wBz_ + 1.5 L wAz_) Wy.
515515
const Vector3d v_WAcm_W_expected(0, 0.5 * link_length_ * wAz_, 0);

multibody/plant/test/multibody_plant_test.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -763,7 +763,7 @@ class AcrobotPlantTests : public ::testing::Test {
763763
const SpatialForce<double>& F_Bo_W =
764764
body.GetForceInWorld(*plant_context_, forces);
765765
const double mass = body.default_mass();
766-
// TODO(amcastro-tri): provide Body::EvalCOMInWorld().
766+
// TODO(amcastro-tri): provide RigidBody::EvalCOMInWorld().
767767
const Vector3<double> p_BoBcm_B =
768768
body.CalcCenterOfMassInBodyFrame(*plant_context_);
769769
const RigidTransform<double> X_WB =

multibody/tree/frame.h

+7-6
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ template<typename T> class RigidBody;
3131
/// to a %Frame are applied to the %Frame's underlying Body. Force-producing
3232
/// elements like joints, actuators, and constraints usually employ two %Frames,
3333
/// with one %Frame connected to one body and the other connected to a different
34-
/// Body. Every %Frame object can report the Body to which it is attached.
34+
/// Body. Every %Frame object can report the RigidBody to which it is attached.
3535
/// Despite its name, %Frame is not the most general frame in Drake
3636
/// (see FrameBase for more information).
3737
///
@@ -172,7 +172,7 @@ class Frame : public FrameBase<T> {
172172

173173
/// Computes and returns the pose `X_WF` of `this` frame F in the world
174174
/// frame W as a function of the state of the model stored in `context`.
175-
/// @note Body::EvalPoseInWorld() provides a more efficient way to obtain
175+
/// @note RigidBody::EvalPoseInWorld() provides a more efficient way to obtain
176176
/// the pose for a body frame.
177177
math::RigidTransform<T> CalcPoseInWorld(
178178
const systems::Context<T>& context) const {
@@ -262,8 +262,8 @@ class Frame : public FrameBase<T> {
262262
/// ω_WF_W (frame F's angular velocity ω measured and expressed in the world
263263
/// frame W). The translational part is v_WFo_W (translational velocity v of
264264
/// frame F's origin point Fo, measured and expressed in the world frame W).
265-
/// @note Body::EvalSpatialVelocityInWorld() provides a more efficient way to
266-
/// obtain a body frame's spatial velocity measured in the world frame.
265+
/// @note RigidBody::EvalSpatialVelocityInWorld() provides a more efficient
266+
/// way to obtain a body frame's spatial velocity measured in the world frame.
267267
/// @see CalcSpatialVelocity(), CalcRelativeSpatialVelocityInWorld(), and
268268
/// CalcSpatialAccelerationInWorld().
269269
SpatialVelocity<T> CalcSpatialVelocityInWorld(
@@ -396,8 +396,9 @@ class Frame : public FrameBase<T> {
396396
/// expressed in the world frame W). The translational part is a_WFo_W
397397
/// (translational acceleration of frame F's origin point Fo, measured and
398398
/// expressed in the world frame W).
399-
/// @note Body::EvalSpatialAccelerationInWorld() provides a more efficient way
400-
/// to obtain a body frame's spatial acceleration measured in the world frame.
399+
/// @note RigidBody::EvalSpatialAccelerationInWorld() provides a more
400+
/// efficient way to obtain a body frame's spatial acceleration measured in
401+
/// the world frame.
401402
/// @note When cached values are out of sync with the state stored in context,
402403
/// this method performs an expensive forward dynamics computation, whereas
403404
/// once evaluated, successive calls to this method are inexpensive.

0 commit comments

Comments
 (0)