Drake
BodyFrame< T > Class Template Referencefinal

Detailed Description

template<typename T>
class drake::multibody::BodyFrame< T >

A BodyFrame is a material Frame that serves as the unique reference frame for a Body.

Each Body B, regardless of whether it represents a rigid body or a flexible body, has a unique body frame for which we use the same symbol B (with meaning clear from context). The body frame is also referred to as a reference frame in the literature for flexible body mechanics modeling using the Finite Element Method. All properties of a body are defined with respect to its body frame, 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. We represent a body frame by a BodyFrame object that is created whenever a Body is constructed and is owned by the Body.

Note that the BodyFrame associated with a 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. For flexible bodies, BodyFrame provides a representation for the body's reference frame. The flexible degrees of freedom associated with a flexible body describe the body's deformation in this frame. Therefore, the motion of a flexible body is defined by the motion of its BodyFrame, or reference frame, plus the motion of the material points on the body with respect to its BodyFrame.

A BodyFrame and Body are tightly coupled concepts; neither makes sense without the other. Therefore, a BodyFrame instance is constructed in conjunction with its Body and cannot be constructed anywhere else. However, you can still access the frame associated with a body, see Body::body_frame(). This access is more than a convenience; you can use the BodyFrame to define other frames on the body and to attach other multibody elements to it.

Template Parameters
TThe scalar type, which must be one of the default scalars.

#include <drake/multibody/tree/multibody_tree.h>

Public Member Functions

math::RigidTransform< T > CalcPoseInBodyFrame (const systems::Context< T > &) const override
 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 > &) 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 > CalcOffsetPoseInBody (const systems::Context< T > &, const math::RigidTransform< T > &X_FQ) const override
 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 > &, 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...
 
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...
 
Does not allow copy, move, or assignment
 BodyFrame (const BodyFrame &)=delete
 
BodyFrameoperator= (const BodyFrame &)=delete
 
 BodyFrame (BodyFrame &&)=delete
 
BodyFrameoperator= (BodyFrame &&)=delete
 
- Public Member Functions inherited from Frame< T >
const Body< 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. It may be empty if unnamed. 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...
 
SpatialVelocity< T > CalcSpatialVelocityInWorld (const systems::Context< T > &context) const
 Computes and returns the spatial velocity V_WF of this frame F in the world frame W as a function of the state of the model stored in context. More...
 
SpatialVelocity< T > CalcSpatialVelocity (const systems::Context< T > &context, const Frame< T > &frame_M, const Frame< T > &frame_E) const
 Computes and returns the spatial velocity V_MF_E of this frame F measured in frame_M and expressed in frame_E as a function of the state of the model stored in context. More...
 
SpatialAcceleration< T > CalcSpatialAccelerationInWorld (const systems::Context< T > &context) const
 Computes and returns the spatial acceleration A_WF_W of this frame F in world frame W expressed in W as a function of the state stored in context. 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
 
Frameoperator= (const Frame &)=delete
 
 Frame (Frame &&)=delete
 
Frameoperator= (Frame &&)=delete
 
- Public Member Functions inherited from MultibodyElement< FrameBase, T, FrameIndex >
virtual ~MultibodyElement ()
 
FrameIndex index () const
 Returns this element's unique index. More...
 
ModelInstanceIndex model_instance () const
 Returns the ModelInstanceIndex of the model instance to which this element belongs. More...
 
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...
 
 MultibodyElement (const MultibodyElement &)=delete
 
 MultibodyElement (MultibodyElement &&)=delete
 
MultibodyElementoperator= (const MultibodyElement &)=delete
 
MultibodyElementoperator= (MultibodyElement &&)=delete
 

Protected Member Functions

std::unique_ptr< Frame< double > > DoCloneToScalar (const internal::MultibodyTree< double > &tree_clone) const override
 Clones this Frame (templated on T) to a frame templated on double. More...
 
std::unique_ptr< Frame< AutoDiffXd > > DoCloneToScalar (const internal::MultibodyTree< AutoDiffXd > &tree_clone) const override
 Clones this Frame (templated on T) to a frame templated on AutoDiffXd. More...
 
std::unique_ptr< Frame< symbolic::Expression > > DoCloneToScalar (const internal::MultibodyTree< symbolic::Expression > &) const override
 
- Protected Member Functions inherited from Frame< T >
 Frame (const std::string &name, const Body< T > &body, std::optional< ModelInstanceIndex > model_instance={})
 Only derived classes can use this constructor. More...
 
 Frame (const Body< T > &body)
 Overload to permit constructing an unnamed frame. More...
 
- Protected Member Functions inherited from FrameBase< T >
 FrameBase (ModelInstanceIndex model_instance)
 
- Protected Member Functions inherited from MultibodyElement< FrameBase, T, FrameIndex >
 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...
 
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...
 
virtual void DoDeclareParameters (internal::MultibodyTreeSystem< T > *)
 Implementation of the NVI DeclareParameters(). 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...
 

Friends

class Body< T >
 
template<typename >
class BodyFrame
 

Constructor & Destructor Documentation

◆ BodyFrame() [1/2]

BodyFrame ( const BodyFrame< T > &  )
delete

◆ BodyFrame() [2/2]

BodyFrame ( BodyFrame< T > &&  )
delete

Member Function Documentation

◆ CalcOffsetPoseInBody()

math::RigidTransform<T> CalcOffsetPoseInBody ( const systems::Context< T > &  context,
const math::RigidTransform< T > &  X_FQ 
) const
overridevirtual

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.

In other words, if the pose of this frame F in the body frame B is X_BF, this method computes the pose X_BQ of frame Q in the body frame B as X_BQ = X_BF * X_FQ. In particular, if this isthe body frame B, i.e.X_BFis the identity transformation, this method directly returnsX_FQ`. Specific frame subclasses can override this method to provide faster implementations if needed.

Reimplemented from Frame< T >.

◆ CalcOffsetRotationMatrixInBody()

math::RotationMatrix<T> CalcOffsetRotationMatrixInBody ( const systems::Context< T > &  context,
const math::RotationMatrix< T > &  R_FQ 
) const
overridevirtual

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).

Parameters
[in]R_FQrotation matrix that relates frame F to frame Q.

Reimplemented from Frame< T >.

◆ CalcPoseInBodyFrame()

math::RigidTransform<T> CalcPoseInBodyFrame ( const systems::Context< T > &  context) const
overridevirtual

Returns the pose X_BF of this frame F in the body frame B associated with this frame.

In particular, if this is the body frame B, this method directly returns the identity transformation.

Implements Frame< T >.

◆ CalcRotationMatrixInBodyFrame()

math::RotationMatrix<T> CalcRotationMatrixInBodyFrame ( const systems::Context< T > &  context) const
overridevirtual

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).

Note
If this is B, this method returns the identity RotationMatrix.

Implements Frame< T >.

◆ DoCloneToScalar() [1/3]

std::unique_ptr<Frame<double> > DoCloneToScalar ( const internal::MultibodyTree< double > &  tree_clone) const
overrideprotectedvirtual

Clones this Frame (templated on T) to a frame templated on double.

Implements Frame< T >.

◆ DoCloneToScalar() [2/3]

std::unique_ptr<Frame<AutoDiffXd> > DoCloneToScalar ( const internal::MultibodyTree< AutoDiffXd > &  tree_clone) const
overrideprotectedvirtual

Clones this Frame (templated on T) to a frame templated on AutoDiffXd.

Implements Frame< T >.

◆ DoCloneToScalar() [3/3]

std::unique_ptr<Frame<symbolic::Expression> > DoCloneToScalar ( const internal::MultibodyTree< symbolic::Expression > &  ) const
overrideprotectedvirtual

Implements Frame< T >.

◆ GetFixedOffsetPoseInBody()

math::RigidTransform<T> GetFixedOffsetPoseInBody ( const math::RigidTransform< T > &  X_FQ) const
overridevirtual

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.

Exceptions
std::exceptionif called on a Frame that does not have a fixed offset in the body frame.

Reimplemented from Frame< T >.

◆ GetFixedPoseInBodyFrame()

math::RigidTransform<T> GetFixedPoseInBodyFrame ( ) const
overridevirtual

Variant of CalcPoseInBodyFrame() that returns the fixed pose X_BF of this frame F in the body frame B associated with this frame.

Exceptions
std::exceptionif called on a Frame that does not have a fixed offset in the body frame.

Reimplemented from Frame< T >.

◆ GetFixedRotationMatrixInBody()

math::RotationMatrix<T> GetFixedRotationMatrixInBody ( const math::RotationMatrix< T > &  R_FQ) const
overridevirtual

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).

Parameters
[in]R_FQrotation matrix that relates frame F to frame Q.
Exceptions
std::exceptionif this frame F is a Frame that does not have a fixed offset in the body frame B (i.e., R_BF is not constant).

Reimplemented from Frame< T >.

◆ GetFixedRotationMatrixInBodyFrame()

math::RotationMatrix<T> GetFixedRotationMatrixInBodyFrame ( ) const
overridevirtual

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).

Exceptions
std::exceptionif this frame F is a Frame that does not have a fixed offset in the body frame B (i.e., R_BF is not constant). Frame sub-classes that have a constant R_BF must override this method. An example of a frame sub-class not implementing this method would be that of a frame on a soft body, for which its pose in the body frame depends on the state of deformation of the body.

Reimplemented from Frame< T >.

◆ operator=() [1/2]

BodyFrame& operator= ( const BodyFrame< T > &  )
delete

◆ operator=() [2/2]

BodyFrame& operator= ( BodyFrame< T > &&  )
delete

Friends And Related Function Documentation

◆ Body< T >

friend class Body< T >
friend

◆ BodyFrame

friend class BodyFrame
friend

The documentation for this class was generated from the following file: