@@ -1153,7 +1153,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
1153
1153
// / @param[in] name
1154
1154
// / A string that identifies the new body to be added to `this` model. A
1155
1155
// / 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().
1157
1157
// / @param[in] model_instance
1158
1158
// / A model instance index which this body is part of.
1159
1159
// / @param[in] M_BBo_B
@@ -1200,7 +1200,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
1200
1200
// / A string that identifies the new body to be added to `this` model. A
1201
1201
// / std::runtime_error is thrown if a body named `name` already is part of
1202
1202
// / the model in the default model instance. See HasBodyNamed(),
1203
- // / Body ::name().
1203
+ // / RigidBody ::name().
1204
1204
// / @param[in] M_BBo_B
1205
1205
// / The SpatialInertia of the new rigid body to be added to `this`
1206
1206
// / %MultibodyPlant, computed about the body frame origin `Bo` and expressed
@@ -1305,7 +1305,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
1305
1305
// / plant.AddRigidBody("Body1", SpatialInertia<double>(...));
1306
1306
// / const RigidBody<double>& body_2 =
1307
1307
// / 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.
1309
1309
// / // Define the pose X_BM of a frame M rigidly attached to child body B.
1310
1310
// / const RevoluteJoint<double>& elbow =
1311
1311
// / plant.AddJoint<RevoluteJoint>(
@@ -1632,9 +1632,9 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
1632
1632
// /
1633
1633
// / f = −stiffness ⋅ d − damping ⋅ ḋ
1634
1634
// /
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.
1636
1636
// / @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.
1638
1638
// / @param[in] p_BQ Position of point Q in body B's frame.
1639
1639
// / @param[in] distance Fixed length of the distance constraint, in meters. It
1640
1640
// / must be strictly positive.
@@ -1677,9 +1677,9 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
1677
1677
// / all times with point Q affixed to body B, effectively modeling a
1678
1678
// / ball-and-socket joint.
1679
1679
// /
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.
1681
1681
// / @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.
1683
1683
// / @param[in] p_BQ Position of point Q in body B's frame.
1684
1684
// / @returns the id of the newly added constraint.
1685
1685
// /
@@ -1699,9 +1699,9 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
1699
1699
// / all times with frame Q affixed to body B, effectively modeling a weld
1700
1700
// / joint.
1701
1701
// /
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.
1703
1703
// / @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.
1705
1705
// / @param[in] X_BQ Pose of frame Q in body B's frame.
1706
1706
// / @returns the id of the newly added constraint.
1707
1707
// /
@@ -1780,8 +1780,8 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
1780
1780
// / when %MultibodyPlant registers the corresponding SceneGraph frame, it is
1781
1781
// / named with a "scoped name". This is a concatenation of
1782
1782
// / `[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.)
1785
1785
// / @{
1786
1786
1787
1787
// / Registers `this` plant to serve as a source for an instance of
@@ -3093,8 +3093,8 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
3093
3093
// / @anchor mbp_working_with_free_bodies
3094
3094
// / @name Working with free bodies
3095
3095
// /
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.
3098
3098
// / At Finalize(), %MultibodyPlant builds a mathematical representation of
3099
3099
// / such system, consisting of a tree representation. In this
3100
3100
// / representation each body is assigned a Mobilizer, which grants a certain
@@ -3104,12 +3104,12 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
3104
3104
// / tree. If the root body has six degrees of freedom with respect to the
3105
3105
// / world, it is called a "free body" (sometimes called a "floating body").
3106
3106
// / 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().
3109
3109
// / For many applications, a user might need to work with indexes in the
3110
3110
// / 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
3113
3113
// / introspection needed.
3114
3114
// /
3115
3115
// / It is sometimes convenient for users to perform operations on Bodies
@@ -3118,7 +3118,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
3118
3118
// / bodies at the time of Finalize(). Using Joint APIs to affect a free body
3119
3119
// / (setting state, changing parameters, etc.) has the same effect as using
3120
3120
// / 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
3122
3122
// / there is already some (unrelated) joint with that name, we'll prepend
3123
3123
// / underscores to the name until it is unique.
3124
3124
// / @{
@@ -3174,7 +3174,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
3174
3174
// / effect of the call is that the value will be echoed back in
3175
3175
// / GetDefaultFreeBodyPose().
3176
3176
// / @param[in] body
3177
- // / Body whose default pose will be set.
3177
+ // / RigidBody whose default pose will be set.
3178
3178
// / @param[in] X_WB
3179
3179
// / Default pose of the body.
3180
3180
void SetDefaultFreeBodyPose (const RigidBody<T>& body,
@@ -3185,7 +3185,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
3185
3185
// / Gets the default pose of `body` as set by SetDefaultFreeBodyPose(). If no
3186
3186
// / pose is specified for the body, returns the identity pose.
3187
3187
// / @param[in] body
3188
- // / Body whose default pose will be retrieved.
3188
+ // / RigidBody whose default pose will be retrieved.
3189
3189
math::RigidTransform<double > GetDefaultFreeBodyPose (
3190
3190
const RigidBody<T>& body) const {
3191
3191
return internal_tree ().GetDefaultFreeBodyPose (body);
@@ -3331,7 +3331,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
3331
3331
// / Evaluates V_WB, body B's spatial velocity in the world frame W.
3332
3332
// / @param[in] context The context storing the state of the model.
3333
3333
// / @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,
3335
3335
// / expressed in W (for point Bo, the body's origin).
3336
3336
// / @throws std::exception if Finalize() was not called on `this` model or
3337
3337
// / if `body_B` does not belong to this model.
@@ -3344,7 +3344,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
3344
3344
// / Evaluates A_WB, body B's spatial acceleration in the world frame W.
3345
3345
// / @param[in] context The context storing the state of the model.
3346
3346
// / @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,
3348
3348
// / expressed in W (for point Bo, the body's origin).
3349
3349
// / @throws std::exception if Finalize() was not called on `this` model or
3350
3350
// / if `body_B` does not belong to this model.
@@ -3787,7 +3787,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
3787
3787
// / spatial forces F on each body, refer to documentation in MultibodyForces
3788
3788
// / for details. Users of MultibodyForces will use
3789
3789
// / 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
3791
3791
// / append spatial forces.
3792
3792
// /
3793
3793
// / For a given set of forces stored as MultibodyForces, this method will
@@ -4589,7 +4589,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
4589
4589
// / @see HasBodyNamed() to query if there exists a body in `this`
4590
4590
// / %MultibodyPlant with a given specified name.
4591
4591
const RigidBody<T>& GetBodyByName (std::string_view name) const {
4592
- return internal_tree ().GetBodyByName (name);
4592
+ return internal_tree ().GetRigidBodyByName (name);
4593
4593
}
4594
4594
4595
4595
// / Returns a constant reference to the body that is uniquely identified
@@ -4599,7 +4599,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
4599
4599
// / %MultibodyPlant with a given specified name.
4600
4600
const RigidBody<T>& GetBodyByName (std::string_view name,
4601
4601
ModelInstanceIndex model_instance) const {
4602
- return internal_tree ().GetBodyByName (name, model_instance);
4602
+ return internal_tree ().GetRigidBodyByName (name, model_instance);
4603
4603
}
4604
4604
4605
4605
// / Returns a list of body indices associated with `model_instance`.
0 commit comments