template<typename T>
class drake::multibody::RigidBodyFrame< T >
A RigidBodyFrame is a material Frame that serves as the unique reference frame for a RigidBody.
Each RigidBody B has a unique body frame for which we use the same symbol B (with meaning clear from context). We represent a body frame by a RigidBodyFrame object that is created whenever a RigidBody is constructed and is owned by the RigidBody. All properties of a RigidBody are defined with respect to its RigidBodyFrame, including its mass properties and attachment locations for joints, constraints, actuators, geometry and so on. Run time motion of the body is defined with respect to the motion of its body frame.
Note that the body frame associated with a rigid body does not necessarily need to be located at its center of mass nor does it need to be aligned with the body's principal axes, although, in practice, it frequently is.
A RigidBodyFrame and RigidBody are tightly coupled concepts; neither makes sense without the other. Therefore, a RigidBodyFrame instance is constructed in conjunction with its RigidBody and cannot be constructed anywhere else. However, you can still access the frame associated with a body, see RigidBody::body_frame(). This access is more than a convenience; you can use the RigidBodyFrame to define other frames on the body and to attach other multibody elements to it.
- Template Parameters
-
|
| ~RigidBodyFrame () override |
|
math::RigidTransform< T > | GetFixedPoseInBodyFrame () const override |
| Variant of CalcPoseInBodyFrame() that returns the fixed pose X_BF of this frame F in the body frame B associated with this frame. More...
|
|
math::RotationMatrix< T > | GetFixedRotationMatrixInBodyFrame () const override |
| Returns the rotation matrix R_BF that relates body frame B to this frame F (B is the body frame to which this frame F is attached). More...
|
|
math::RigidTransform< T > | GetFixedOffsetPoseInBody (const math::RigidTransform< T > &X_FQ) const override |
| Variant of CalcOffsetPoseInBody() that given the offset pose X_FQ of a frame Q in this frame F, returns the pose X_BQ of frame Q in the body frame B to which this frame is attached. More...
|
|
math::RotationMatrix< T > | GetFixedRotationMatrixInBody (const math::RotationMatrix< T > &R_FQ) const override |
| Calculates and returns the rotation matrix R_BQ that relates body frame B to frame Q via this intermediate frame F, i.e., R_BQ = R_BF * R_FQ (B is the body frame to which this frame F is attached). More...
|
|
|
| RigidBodyFrame (const RigidBodyFrame &)=delete |
|
RigidBodyFrame & | operator= (const RigidBodyFrame &)=delete |
|
| RigidBodyFrame (RigidBodyFrame &&)=delete |
|
RigidBodyFrame & | operator= (RigidBodyFrame &&)=delete |
|
Public Member Functions inherited from Frame< T > |
| ~Frame () override |
|
const RigidBody< T > & | body () const |
| Returns a const reference to the body associated to this Frame. More...
|
|
bool | is_world_frame () const |
| Returns true if this is the world frame. More...
|
|
bool | is_body_frame () const |
| Returns true if this is the body frame. More...
|
|
const std::string & | name () const |
| Returns the name of this frame. The name will never be empty. More...
|
|
ScopedName | scoped_name () const |
| Returns scoped name of this frame. More...
|
|
const math::RigidTransform< T > & | EvalPoseInBodyFrame (const systems::Context< T > &context) const |
| Returns a reference to the body-relative pose X_BF giving the pose of this Frame with respect to its body's RigidBodyFrame. More...
|
|
math::RigidTransform< T > | CalcPoseInBodyFrame (const systems::Context< T > &context) const |
| Returns the pose X_BF of this frame F in the body frame B associated with this frame. More...
|
|
math::RotationMatrix< T > | CalcRotationMatrixInBodyFrame (const systems::Context< T > &context) const |
| Returns the rotation matrix R_BF that relates body frame B to this frame F (B is the body frame to which this frame F is attached). More...
|
|
math::RigidTransform< T > | CalcOffsetPoseInBody (const systems::Context< T > &context, const math::RigidTransform< T > &X_FQ) const |
| Given the offset pose X_FQ of a frame Q in this frame F, this method computes the pose X_BQ of frame Q in the body frame B to which this frame is attached. More...
|
|
math::RotationMatrix< T > | CalcOffsetRotationMatrixInBody (const systems::Context< T > &context, const math::RotationMatrix< T > &R_FQ) const |
| Calculates and returns the rotation matrix R_BQ that relates body frame B to frame Q via this intermediate frame F, i.e., R_BQ = R_BF * R_FQ (B is the body frame to which this frame F is attached). More...
|
|
math::RigidTransform< T > | CalcPoseInWorld (const systems::Context< T > &context) const |
| Computes and returns the pose X_WF of this frame F in the world frame W as a function of the state of the model stored in context . More...
|
|
math::RigidTransform< T > | CalcPose (const systems::Context< T > &context, const Frame< T > &frame_M) const |
| Computes and returns the pose X_MF of this frame F in measured in frame_M as a function of the state of the model stored in context . More...
|
|
math::RotationMatrix< T > | CalcRotationMatrix (const systems::Context< T > &context, const Frame< T > &frame_M) const |
| Calculates and returns the rotation matrix R_MF that relates frame_M and this frame F as a function of the state stored in context . More...
|
|
math::RotationMatrix< T > | CalcRotationMatrixInWorld (const systems::Context< T > &context) const |
| Calculates and returns the rotation matrix R_WF that relates the world frame W and this frame F as a function of the state stored in context . More...
|
|
const Vector3< T > & | EvalAngularVelocityInWorld (const systems::Context< T > &context) const |
| Evaluates this frame F's angular velocity measured and expressed in the world frame W. More...
|
|
Vector3< T > | CalcAngularVelocity (const systems::Context< T > &context, const Frame< T > &measured_in_frame, const Frame< T > &expressed_in_frame) const |
| Calculates this frame F's angular velocity measured in a frame M, expressed in a frame E. More...
|
|
SpatialVelocity< T > | CalcSpatialVelocityInWorld (const systems::Context< T > &context) const |
| Calculates this frame F's spatial velocity measured and expressed in the world frame W. More...
|
|
SpatialVelocity< T > | CalcSpatialVelocity (const systems::Context< T > &context, const Frame< T > &frame_M, const Frame< T > &frame_E) const |
| Calculates this frame F's spatial velocity measured in a frame M, expressed in a frame E. More...
|
|
SpatialVelocity< T > | CalcRelativeSpatialVelocityInWorld (const systems::Context< T > &context, const Frame< T > &other_frame) const |
| Calculates this frame C's spatial velocity relative to another frame B, measured and expressed in the world frame W. More...
|
|
SpatialVelocity< T > | CalcRelativeSpatialVelocity (const systems::Context< T > &context, const Frame< T > &other_frame, const Frame< T > &measured_in_frame, const Frame< T > &expressed_in_frame) const |
| Calculates this frame C's spatial velocity relative to another frame B, measured in a frame M, expressed in a frame E. More...
|
|
SpatialAcceleration< T > | CalcSpatialAccelerationInWorld (const systems::Context< T > &context) const |
| Calculates this frame F's spatial acceleration measured and expressed in the world frame W. More...
|
|
SpatialAcceleration< T > | CalcSpatialAcceleration (const systems::Context< T > &context, const Frame< T > &measured_in_frame, const Frame< T > &expressed_in_frame) const |
| Calculates this frame F's spatial acceleration measured in a frame M, expressed in a frame E. More...
|
|
SpatialAcceleration< T > | CalcRelativeSpatialAccelerationInWorld (const systems::Context< T > &context, const Frame< T > &other_frame) const |
| Calculates this frame C's spatial acceleration relative to another frame B, measured and expressed in the world frame W. More...
|
|
SpatialAcceleration< T > | CalcRelativeSpatialAcceleration (const systems::Context< T > &context, const Frame< T > &other_frame, const Frame< T > &measured_in_frame, const Frame< T > &expressed_in_frame) const |
| Calculates this frame C's spatial acceleration relative to another frame B, measured in a frame M, expressed in a frame E. More...
|
|
template<typename ToScalar > |
std::unique_ptr< Frame< ToScalar > > | CloneToScalar (const internal::MultibodyTree< ToScalar > &tree_clone) const |
| (Advanced) NVI to DoCloneToScalar() templated on the scalar type of the new clone to be created. More...
|
|
| Frame (const Frame &)=delete |
|
Frame & | operator= (const Frame &)=delete |
|
| Frame (Frame &&)=delete |
|
Frame & | operator= (Frame &&)=delete |
|
void | set_body_pose_index_in_cache (int body_pose_index) |
| (Internal use only) A Frame's pose-in-parent X_PF can be parameterized, the parent's pose may also be parameterized, and so on. More...
|
|
int | get_body_pose_index_in_cache () const |
| (Internal use only) Retrieve this Frame's body pose index in the cache. More...
|
|
const math::RigidTransform< T > & | get_X_BF (const internal::FrameBodyPoseCache< T > &frame_body_poses) const |
| (Internal use only) Given an already up-to-date frame body pose cache, extract X_BF for this Frame from it. More...
|
|
const math::RigidTransform< T > & | get_X_FB (const internal::FrameBodyPoseCache< T > &frame_body_poses) const |
| (Internal use only) Given an already up-to-date frame body pose cache, extract X_FB (=X_BF⁻¹) for this Frame from it. More...
|
|
Public Member Functions inherited from FrameBase< T > |
FrameIndex | index () const |
| Returns this element's unique index. More...
|
|
| ~FrameBase () override |
|
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 |
|