The term rigid body implies that the deformations of the body under consideration are so small that they have no significant effect on the overall motions of the body and therefore deformations can be neglected.
If deformations are neglected, the distance between any two points on the rigid body remains constant at all times. This invariance of the distance between two arbitrary points is often taken as the definition of a rigid body in classical treatments of multibody mechanics [Goldstein 2001]. It can be demonstrated that the unconstrained three-dimensional motions of a rigid body can be described by six coordinates and thus it is often said that a free body in space has six degrees of freedom. These degrees of freedom obey the Newton-Euler equations of motion. However, within a MultibodyTree, a RigidBody is not free in space; instead, it is assigned a limited number of degrees of freedom (0-6) with respect to its parent body in the multibody tree by its Mobilizer (also called a "tree joint" or "inboard joint"). Additional constraints on permissible motion can be added using Constraint objects to remove more degrees of freedom.
T | The scalar type, which must be one of the default scalars. |
#include <drake/multibody/tree/rigid_body.h>
Public Member Functions | |
RigidBody (const std::string &body_name, const SpatialInertia< double > &M_BBo_B=SpatialInertia< double >::Zero()) | |
Constructs a RigidBody named body_name with the given default SpatialInertia. More... | |
RigidBody (const std::string &body_name, ModelInstanceIndex model_instance, const SpatialInertia< double > &M_BBo_B=SpatialInertia< double >::Zero()) | |
Constructs a RigidBody named body_name with the given default SpatialInertia. More... | |
~RigidBody () override | |
BodyIndex | index () const |
Returns this element's unique index. More... | |
const std::string & | name () const |
Gets the name associated with this rigid body. More... | |
ScopedName | scoped_name () const |
Returns scoped name of this frame. More... | |
const RigidBodyFrame< T > & | body_frame () const |
Returns a const reference to the associated BodyFrame. More... | |
void | Lock (systems::Context< T > *context) const |
For a floating base RigidBody, lock its inboard joint. More... | |
void | Unlock (systems::Context< T > *context) const |
For a floating base RigidBody, unlock its inboard joint. More... | |
bool | is_locked (const systems::Context< T > &context) const |
Determines whether this RigidBody is currently locked to its inboard (parent) RigidBody. More... | |
internal::MobodIndex | mobod_index () const |
(Advanced) Returns the index of the mobilized body ("mobod") in the computational directed forest structure of the owning MultibodyTree to which this RigidBody belongs. More... | |
bool | is_floating () const |
(Advanced) Returns true if this body is granted 6-dofs by a Mobilizer and the parent body of this body's associated 6-dof joint is world . More... | |
bool | has_quaternion_dofs () const |
(Advanced) If true , this body's generalized position coordinates q include a quaternion, which occupies the first four elements of q. More... | |
int | floating_positions_start () const |
(Advanced) For floating base bodies (see is_floating()) this method returns the index of this RigidBody's first generalized position in the vector q of generalized position coordinates for a MultibodyPlant model. More... | |
int | floating_velocities_start_in_v () const |
(Advanced) For floating base bodies (see is_floating()) this method returns the index of this RigidBody's first generalized velocity in the vector v of generalized velocities for a MultibodyPlant model. More... | |
std::string | floating_position_suffix (int position_index_in_body) const |
Returns a string suffix (e.g. More... | |
std::string | floating_velocity_suffix (int velocity_index_in_body) const |
Returns a string suffix (e.g. More... | |
double | default_mass () const |
Returns this RigidBody's default mass, which is initially supplied at construction when specifying this body's SpatialInertia. More... | |
const Vector3< double > & | default_com () const |
Returns the default value of this RigidBody's center of mass as measured and expressed in its body frame. More... | |
const UnitInertia< double > & | default_unit_inertia () const |
Returns the default value of this body B's unit inertia about Bo (body B's origin), expressed in B (this body's body frame). More... | |
RotationalInertia< double > | default_rotational_inertia () const |
Gets the default value of this body B's rotational inertia about Bo (B's origin), expressed in B (this body's body frame). More... | |
const SpatialInertia< double > & | default_spatial_inertia () const |
Gets the default value of this body B's SpatialInertia about Bo (B's origin) and expressed in B (this body's frame). More... | |
const T & | get_mass (const systems::Context< T > &context) const |
Gets this body's mass from the given context. More... | |
const math::RigidTransform< T > & | EvalPoseInWorld (const systems::Context< T > &context) const |
Returns the pose X_WB of this RigidBody B in the world frame W as a function of the state of the model stored in context . More... | |
const SpatialVelocity< T > & | EvalSpatialVelocityInWorld (const systems::Context< T > &context) const |
Evaluates V_WB, this body B's SpatialVelocity in the world frame W. More... | |
const SpatialAcceleration< T > & | EvalSpatialAccelerationInWorld (const systems::Context< T > &context) const |
Evaluates A_WB, this body B's SpatialAcceleration in the world frame W. More... | |
const SpatialForce< T > & | GetForceInWorld (const systems::Context< T > &, const MultibodyForces< T > &forces) const |
Gets the SpatialForce on this RigidBody B from forces as F_BBo_W: applied at body B's origin Bo and expressed in world frame W. More... | |
void | AddInForceInWorld (const systems::Context< T > &, const SpatialForce< T > &F_Bo_W, MultibodyForces< T > *forces) const |
Adds the SpatialForce on this RigidBody B, applied at body B's origin Bo and expressed in the world frame W into forces . More... | |
void | AddInForce (const systems::Context< T > &context, const Vector3< T > &p_BP_E, const SpatialForce< T > &F_Bp_E, const Frame< T > &frame_E, MultibodyForces< T > *forces) const |
Adds the SpatialForce on this RigidBody B, applied at point P and expressed in a frame E into forces . More... | |
Vector3< T > | CalcCenterOfMassInBodyFrame (const systems::Context< T > &context) const |
Gets this body's center of mass position from the given context. More... | |
Vector3< T > | CalcCenterOfMassTranslationalVelocityInWorld (const systems::Context< T > &context) const |
Calculates Bcm's translational velocity in the world frame W. More... | |
Vector3< T > | CalcCenterOfMassTranslationalAccelerationInWorld (const systems::Context< T > &context) const |
Calculates Bcm's translational acceleration in the world frame W. More... | |
SpatialInertia< T > | CalcSpatialInertiaInBodyFrame (const systems::Context< T > &context) const |
Gets this body's spatial inertia about its origin from the given context. More... | |
void | SetMass (systems::Context< T > *context, const T &mass) const |
For this RigidBody B, sets its mass stored in context to mass . More... | |
void | SetCenterOfMassInBodyFrame (systems::Context< T > *context, const Vector3< T > &com) const |
(Advanced) Sets this body's center of mass position while preserving its inertia about its body origin. More... | |
void | SetCenterOfMassInBodyFrameAndPreserveCentralInertia (systems::Context< T > *context, const Vector3< T > ¢er_of_mass_position) const |
Sets this body's center of mass position while preserving its inertia about its center of mass. More... | |
void | SetSpatialInertiaInBodyFrame (systems::Context< T > *context, const SpatialInertia< T > &M_Bo_B) const |
For this RigidBody B, sets its SpatialInertia that is stored in context to M_Bo_B . More... | |
template<typename ToScalar > | |
std::unique_ptr< RigidBody< ToScalar > > | CloneToScalar (const internal::MultibodyTree< ToScalar > &tree_clone) const |
(Advanced) This method is mostly intended to be called by MultibodyTree::CloneToScalar(). More... | |
Does not allow copy, move, or assignment | |
RigidBody (const RigidBody &)=delete | |
RigidBody & | operator= (const RigidBody &)=delete |
RigidBody (RigidBody &&)=delete | |
RigidBody & | operator= (RigidBody &&)=delete |
Methods to access position kinematics quantities. | |
The input PositionKinematicsCache to these methods must be in sync with context. These method's APIs will be deprecated when caching arrives. | |
const math::RigidTransform< T > & | get_pose_in_world (const internal::PositionKinematicsCache< T > &pc) const |
(Advanced) Extract this body's pose in world (from the position kinematics). More... | |
const math::RotationMatrix< T > | get_rotation_matrix_in_world (const internal::PositionKinematicsCache< T > &pc) const |
(Advanced) Extract the RotationMatrix relating the world frame to this body's frame. More... | |
const Vector3< T > | get_origin_position_in_world (const internal::PositionKinematicsCache< T > &pc) const |
(Advanced) Extract the position vector from world origin to this body's origin, expressed in world. More... | |
Methods to access velocity kinematics quantities. | |
The input VelocityKinematicsCache to these methods must be in sync with context. These method's APIs will be deprecated when caching arrives. | |
const SpatialVelocity< T > & | get_spatial_velocity_in_world (const internal::VelocityKinematicsCache< T > &vc) const |
(Advanced) Returns V_WB, this RigidBody B's SpatialVelocity in the world frame W. More... | |
const Vector3< T > & | get_angular_velocity_in_world (const internal::VelocityKinematicsCache< T > &vc) const |
(Advanced) Extract this body's angular velocity in world, expressed in world. More... | |
const Vector3< T > & | get_origin_velocity_in_world (const internal::VelocityKinematicsCache< T > &vc) const |
(Advanced) Extract the velocity of this body's origin in world, expressed in world. More... | |
Methods to access acceleration kinematics quantities. | |
The input AccelerationKinematicsCache to these methods must be in sync with context. These method APIs will be deprecated when caching arrives. | |
const SpatialAcceleration< T > & | get_spatial_acceleration_in_world (const internal::AccelerationKinematicsCache< T > &ac) const |
(Advanced) Returns A_WB, this RigidBody B's SpatialAcceleration in the world frame W. More... | |
const Vector3< T > & | get_angular_acceleration_in_world (const internal::AccelerationKinematicsCache< T > &ac) const |
(Advanced) Extract this body's angular acceleration in world, expressed in world. More... | |
const Vector3< T > & | get_origin_acceleration_in_world (const internal::AccelerationKinematicsCache< T > &ac) const |
(Advanced) Extract acceleration of this body's origin in world, expressed in world. More... | |
Public Member Functions inherited from MultibodyElement< T > | |
virtual | ~MultibodyElement () |
ModelInstanceIndex | model_instance () const |
Returns the ModelInstanceIndex of the model instance to which this element belongs. More... | |
template<typename MultibodyPlantDeferred = MultibodyPlant<T>> | |
const MultibodyPlantDeferred & | GetParentPlant () const |
Returns the MultibodyPlant that owns this MultibodyElement. More... | |
void | DeclareParameters (internal::MultibodyTreeSystem< T > *tree_system) |
Declares MultibodyTreeSystem Parameters at MultibodyTreeSystem::Finalize() time. More... | |
void | SetDefaultParameters (systems::Parameters< T > *parameters) const |
Sets default values of parameters belonging to each MultibodyElement in parameters at a call to MultibodyTreeSystem::SetDefaultParameters(). More... | |
MultibodyElement (const MultibodyElement &)=delete | |
MultibodyElement & | operator= (const MultibodyElement &)=delete |
MultibodyElement (MultibodyElement &&)=delete | |
MultibodyElement & | operator= (MultibodyElement &&)=delete |
Friends | |
class | internal::RigidBodyAttorney< T > |
Additional Inherited Members | |
Protected Member Functions inherited from MultibodyElement< T > | |
MultibodyElement () | |
Default constructor made protected so that sub-classes can still declare their default constructors if they need to. More... | |
MultibodyElement (ModelInstanceIndex model_instance) | |
Constructor which allows specifying a model instance. More... | |
MultibodyElement (ModelInstanceIndex model_instance, int64_t index) | |
Both the model instance and element index are specified. More... | |
template<typename ElementIndexType > | |
ElementIndexType | index_impl () const |
Returns this element's unique index. More... | |
int | ordinal_impl () const |
Returns this element's unique ordinal. More... | |
const internal::MultibodyTree< T > & | get_parent_tree () const |
Returns a constant reference to the parent MultibodyTree that owns this element. More... | |
const internal::MultibodyTreeSystem< T > & | GetParentTreeSystem () const |
Returns a constant reference to the parent MultibodyTreeSystem that owns the parent MultibodyTree that owns this element. More... | |
void | SetTopology (const internal::MultibodyTreeTopology &tree) |
Gives MultibodyElement-derived objects the opportunity to retrieve their topology after MultibodyTree::Finalize() is invoked. More... | |
systems::NumericParameterIndex | DeclareNumericParameter (internal::MultibodyTreeSystem< T > *tree_system, const systems::BasicVector< T > &model_vector) |
To be used by MultibodyElement-derived objects when declaring parameters in their implementation of DoDeclareParameters(). More... | |
systems::AbstractParameterIndex | DeclareAbstractParameter (internal::MultibodyTreeSystem< T > *tree_system, const AbstractValue &model_value) |
To be used by MultibodyElement-derived objects when declaring parameters in their implementation of DoDeclareParameters(). More... | |
|
explicit |
Constructs a RigidBody named body_name
with the given default SpatialInertia.
[in] | body_name | A name associated with this body. |
[in] | M_BBo_B | Spatial inertia of this body B about the frame's origin Bo and expressed in the body frame B. When not provided, defaults to zero. |
RigidBody | ( | const std::string & | body_name, |
ModelInstanceIndex | model_instance, | ||
const SpatialInertia< double > & | M_BBo_B = SpatialInertia< double >::Zero() |
||
) |
Constructs a RigidBody named body_name
with the given default SpatialInertia.
[in] | body_name | A name associated with this body. |
[in] | model_instance | The model instance associated with this body. |
[in] | M_BBo_B | Spatial inertia of this body B about the frame's origin Bo and expressed in the body frame B. When not provided, defaults to zero. |
|
override |
void AddInForce | ( | const systems::Context< T > & | context, |
const Vector3< T > & | p_BP_E, | ||
const SpatialForce< T > & | F_Bp_E, | ||
const Frame< T > & | frame_E, | ||
MultibodyForces< T > * | forces | ||
) | const |
Adds the SpatialForce on this RigidBody B, applied at point P and expressed in a frame E into forces
.
[in] | context | The context containing the current state of the model. |
[in] | p_BP_E | The position of point P in B, expressed in a frame E. |
[in] | F_Bp_E | The spatial force to be applied on body B at point P, expressed in frame E. |
[in] | frame_E | The expressed-in frame E. |
[out] | forces | A multibody forces objects that on output will have F_Bp_E added. |
std::exception | if forces is nullptr or if it is not consistent with the model to which this body belongs. |
void AddInForceInWorld | ( | const systems::Context< T > & | , |
const SpatialForce< T > & | F_Bo_W, | ||
MultibodyForces< T > * | forces | ||
) | const |
Adds the SpatialForce on this RigidBody B, applied at body B's origin Bo and expressed in the world frame W into forces
.
const RigidBodyFrame<T>& body_frame | ( | ) | const |
Returns a const reference to the associated BodyFrame.
Vector3<T> CalcCenterOfMassInBodyFrame | ( | const systems::Context< T > & | context | ) | const |
Gets this body's center of mass position from the given context.
[in] | context | contains the state of the multibody system. |
Vector3<T> CalcCenterOfMassTranslationalAccelerationInWorld | ( | const systems::Context< T > & | context | ) | const |
Calculates Bcm's translational acceleration in the world frame W.
[in] | context | The context contains the state of the model. |
a_WBcm_W | The translational acceleration of Bcm (this rigid body's center of mass) in the world frame W, expressed in W. |
Vector3<T> CalcCenterOfMassTranslationalVelocityInWorld | ( | const systems::Context< T > & | context | ) | const |
Calculates Bcm's translational velocity in the world frame W.
[in] | context | The context contains the state of the model. |
v_WBcm_W | The translational velocity of Bcm (this rigid body's center of mass) in the world frame W, expressed in W. |
SpatialInertia<T> CalcSpatialInertiaInBodyFrame | ( | const systems::Context< T > & | context | ) | const |
Gets this body's spatial inertia about its origin from the given context.
[in] | context | contains the state of the multibody system. |
std::unique_ptr<RigidBody<ToScalar> > CloneToScalar | ( | const internal::MultibodyTree< ToScalar > & | tree_clone | ) | const |
(Advanced) This method is mostly intended to be called by MultibodyTree::CloneToScalar().
Most users should not call this clone method directly but rather clone the entire parent MultibodyTree if needed.
Returns the default value of this RigidBody's center of mass as measured and expressed in its body frame.
This value is initially supplied at construction when specifying this body's SpatialInertia.
p_BoBcm_B | The position of this rigid body B's center of mass Bcm measured from Bo (B's frame origin) and expressed in B (body B's frame). |
double default_mass | ( | ) | const |
Returns this RigidBody's default mass, which is initially supplied at construction when specifying this body's SpatialInertia.
RotationalInertia<double> default_rotational_inertia | ( | ) | const |
Gets the default value of this body B's rotational inertia about Bo (B's origin), expressed in B (this body's body frame).
This value is calculated from the SpatialInertia supplied at construction of this body.
I_BBo_B | body B's rotational inertia about Bo, expressed in B. |
const SpatialInertia<double>& default_spatial_inertia | ( | ) | const |
Gets the default value of this body B's SpatialInertia about Bo (B's origin) and expressed in B (this body's frame).
M_BBo_B | body B's spatial inertia about Bo, expressed in B. |
const UnitInertia<double>& default_unit_inertia | ( | ) | const |
Returns the default value of this body B's unit inertia about Bo (body B's origin), expressed in B (this body's body frame).
This value is initially supplied at construction when specifying this body's SpatialInertia.
G_BBo_B | rigid body B's unit inertia about Bo, expressed in B. |
const math::RigidTransform<T>& EvalPoseInWorld | ( | const systems::Context< T > & | context | ) | const |
Returns the pose X_WB
of this RigidBody B in the world frame W as a function of the state of the model stored in context
.
const SpatialAcceleration<T>& EvalSpatialAccelerationInWorld | ( | const systems::Context< T > & | context | ) | const |
Evaluates A_WB, this body B's SpatialAcceleration in the world frame W.
[in] | context | Contains the state of the model. |
A_WB_W | this body B's spatial acceleration in the world frame W, expressed in W (for point Bo, the body's origin). |
const SpatialVelocity<T>& EvalSpatialVelocityInWorld | ( | const systems::Context< T > & | context | ) | const |
Evaluates V_WB, this body B's SpatialVelocity in the world frame W.
[in] | context | Contains the state of the model. |
V_WB_W | this body B's spatial velocity in the world frame W, expressed in W (for point Bo, the body frame's origin). |
std::string floating_position_suffix | ( | int | position_index_in_body | ) | const |
Returns a string suffix (e.g.
to be appended to the name()) to identify the k
th position in the floating base. position_index_in_body
must be in [0, 7) if has_quaternion_dofs()
is true, otherwise in [0, 6).
std::exception | if called pre-finalize |
int floating_positions_start | ( | ) | const |
(Advanced) For floating base bodies (see is_floating()) this method returns the index of this RigidBody's first generalized position in the vector q of generalized position coordinates for a MultibodyPlant model.
Positions q for this RigidBody are then contiguous starting at this index. When a floating RigidBody is modeled with quaternion coordinates (see has_quaternion_dofs()), the four consecutive entries in the state starting at this index correspond to the quaternion that parametrizes this RigidBody's orientation.
std::exception | if called pre-finalize |
int floating_velocities_start_in_v | ( | ) | const |
(Advanced) For floating base bodies (see is_floating()) this method returns the index of this RigidBody's first generalized velocity in the vector v of generalized velocities for a MultibodyPlant model.
Velocities v for this RigidBody are then contiguous starting at this index.
std::exception | if called pre-finalize |
std::string floating_velocity_suffix | ( | int | velocity_index_in_body | ) | const |
Returns a string suffix (e.g.
to be appended to the name()) to identify the k
th velocity in the floating base. velocity_index_in_body
must be in [0,6).
std::exception | if called pre-finalize |
const Vector3<T>& get_angular_acceleration_in_world | ( | const internal::AccelerationKinematicsCache< T > & | ac | ) | const |
(Advanced) Extract this body's angular acceleration in world, expressed in world.
[in] | ac | velocity kinematics cache. |
alpha_WB_W | B's angular acceleration in world W, expressed in W. |
const Vector3<T>& get_angular_velocity_in_world | ( | const internal::VelocityKinematicsCache< T > & | vc | ) | const |
(Advanced) Extract this body's angular velocity in world, expressed in world.
[in] | vc | velocity kinematics cache. |
w_WB_W | rigid body B's angular velocity in world W, expressed in W. |
const T& get_mass | ( | const systems::Context< T > & | context | ) | const |
Gets this body's mass from the given context.
[in] | context | contains the state of the multibody system. |
const Vector3<T>& get_origin_acceleration_in_world | ( | const internal::AccelerationKinematicsCache< T > & | ac | ) | const |
(Advanced) Extract acceleration of this body's origin in world, expressed in world.
[in] | vc | velocity kinematics cache. |
a_WBo_W | acceleration of body origin Bo in world W, expressed in W. |
const Vector3<T> get_origin_position_in_world | ( | const internal::PositionKinematicsCache< T > & | pc | ) | const |
(Advanced) Extract the position vector from world origin to this body's origin, expressed in world.
[in] | pc | position kinematics cache. |
p_WoBo_W | position vector from Wo (world origin) to Bo (this body's origin) expressed in W (world). |
const Vector3<T>& get_origin_velocity_in_world | ( | const internal::VelocityKinematicsCache< T > & | vc | ) | const |
(Advanced) Extract the velocity of this body's origin in world, expressed in world.
[in] | vc | velocity kinematics cache. |
v_WBo_W | velocity of Bo (body origin) in world W, expressed in W. |
const math::RigidTransform<T>& get_pose_in_world | ( | const internal::PositionKinematicsCache< T > & | pc | ) | const |
(Advanced) Extract this body's pose in world (from the position kinematics).
[in] | pc | position kinematics cache. |
X_WB | pose of rigid body B in world frame W. |
const math::RotationMatrix<T> get_rotation_matrix_in_world | ( | const internal::PositionKinematicsCache< T > & | pc | ) | const |
(Advanced) Extract the RotationMatrix relating the world frame to this body's frame.
[in] | pc | position kinematics cache. |
R_WB | rotation matrix relating rigid body B in world frame W. |
const SpatialAcceleration<T>& get_spatial_acceleration_in_world | ( | const internal::AccelerationKinematicsCache< T > & | ac | ) | const |
(Advanced) Returns A_WB, this RigidBody B's SpatialAcceleration in the world frame W.
[in] | ac | acceleration kinematics cache. |
A_WB_W | this rigid body B's spatial acceleration in the world frame W, expressed in W (for point Bo, the body frame's origin). |
const SpatialVelocity<T>& get_spatial_velocity_in_world | ( | const internal::VelocityKinematicsCache< T > & | vc | ) | const |
(Advanced) Returns V_WB, this RigidBody B's SpatialVelocity in the world frame W.
[in] | vc | velocity kinematics cache. |
V_WB_W | this rigid body B's spatial velocity in the world frame W, expressed in W (for point Bo, the body frame's origin). |
const SpatialForce<T>& GetForceInWorld | ( | const systems::Context< T > & | , |
const MultibodyForces< T > & | forces | ||
) | const |
Gets the SpatialForce on this RigidBody B from forces
as F_BBo_W: applied at body B's origin Bo and expressed in world frame W.
bool has_quaternion_dofs | ( | ) | const |
(Advanced) If true
, this body's generalized position coordinates q include a quaternion, which occupies the first four elements of q.
Note that this does not imply that the body is floating base body since it may have fewer than 6 dofs or its inboard body could be something other than World.
std::exception | if called pre-finalize |
BodyIndex index | ( | ) | const |
Returns this element's unique index.
bool is_floating | ( | ) | const |
(Advanced) Returns true
if this body is granted 6-dofs by a Mobilizer and the parent body of this body's associated 6-dof joint is world
.
std::exception | if called pre-finalize, |
bool is_locked | ( | const systems::Context< T > & | context | ) | const |
Determines whether this RigidBody is currently locked to its inboard (parent) RigidBody.
This is not limited to floating base bodies but generally Joint::is_locked() is preferable otherwise.
void Lock | ( | systems::Context< T > * | context | ) | const |
For a floating base RigidBody, lock its inboard joint.
Its generalized velocities will be 0 until it is unlocked.
std::exception | if this body is not a floating base body. |
internal::MobodIndex mobod_index | ( | ) | const |
(Advanced) Returns the index of the mobilized body ("mobod") in the computational directed forest structure of the owning MultibodyTree to which this RigidBody belongs.
This serves as the BodyNode index and the index into all associated quantities.
const std::string& name | ( | ) | const |
Gets the name
associated with this rigid body.
The name will never be empty.
ScopedName scoped_name | ( | ) | const |
Returns scoped name of this frame.
Neither of the two pieces of the name will be empty (the scope name and the element name).
void SetCenterOfMassInBodyFrame | ( | systems::Context< T > * | context, |
const Vector3< T > & | com | ||
) | const |
(Advanced) Sets this body's center of mass position while preserving its inertia about its body origin.
[in,out] | context | contains the state of the multibody system. It is modified to store the updated com (center of mass position). |
[in] | com | position vector from Bo (this body B's origin) to Bcm (B's center of mass), expressed in B. |
std::exception | if context is null. |
void SetCenterOfMassInBodyFrameAndPreserveCentralInertia | ( | systems::Context< T > * | context, |
const Vector3< T > & | center_of_mass_position | ||
) | const |
Sets this body's center of mass position while preserving its inertia about its center of mass.
[in,out] | context | contains the state of the multibody system. It is modified to store the updated center_of_mass_position and the updated G_BBo_B (this body B's unit inertia about B's origin Bo, expressed in B). |
[in] | center_of_mass_position | position vector from Bo to Bcm (B's center of mass), expressed in B. |
std::exception | if context is null. |
void SetMass | ( | systems::Context< T > * | context, |
const T & | mass | ||
) | const |
For this RigidBody B, sets its mass stored in context
to mass
.
[out] | context | contains the state of the multibody system. |
[in] | mass | mass of this rigid body B. |
std::exception | if context is null. |
void SetSpatialInertiaInBodyFrame | ( | systems::Context< T > * | context, |
const SpatialInertia< T > & | M_Bo_B | ||
) | const |
For this RigidBody B, sets its SpatialInertia that is stored in context
to M_Bo_B
.
[out] | context | contains the state of the multibody system. |
[in] | M_Bo_B | spatial inertia of this rigid body B about Bo (B's origin), expressed in B. M_Bo_B contains properties related to B's mass, the position vector from Bo to Bcm (B's center of mass), and G_Bo_B (B's unit inertia about Bo expressed in B). |
std::exception | if context is null. |
void Unlock | ( | systems::Context< T > * | context | ) | const |
For a floating base RigidBody, unlock its inboard joint.
std::exception | if this body is not a floating base body. |
|
friend |