Drake
Frame< T > Class Template Referenceabstract

Detailed Description

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

Frame is an abstract class representing a material frame (also called a physical frame), meaning that it is associated with a material point of a Body.

A material frame can be used to apply forces and torques to a multibody system, and can be used as an attachment point for force-producing elements like joints, actuators, and constraints. Despite its name, Frame is not the most general frame representation in Drake; see FrameBase for a more-general discussion.

The pose and motion of a Frame object is always calculated relative to the BodyFrame of the body with which it is associated, and every Frame object can report which Body object that is. Concrete classes derived from Frame differ only in how those kinematic properties are calculated. For soft bodies that calculation may depend on the body's deformation state variables. A Frame on a rigid body will usually have a fixed offset from its BodyFrame, but that is not required – a frame that moves with respect to its BodyFrame can still be a material frame on that rigid body.

As always in Drake, runtime numerical quantities are stored in a Context. A Frame object does not store runtime values, but provides methods for extracting frame-associated values (such as the Frame object's kinematics) from a given Context.

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

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

Public Member Functions

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...
 
virtual math::RigidTransform< T > CalcPoseInBodyFrame (const systems::Context< T > &context) const =0
 Returns the pose X_BF of this frame F in the body frame B associated with this frame. More...
 
virtual math::RotationMatrix< T > CalcRotationMatrixInBodyFrame (const systems::Context< T > &context) const =0
 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...
 
virtual math::RigidTransform< T > GetFixedPoseInBodyFrame () const
 Variant of CalcPoseInBodyFrame() that returns the fixed pose X_BF of this frame F in the body frame B associated with this frame. More...
 
virtual math::RotationMatrix< T > GetFixedRotationMatrixInBodyFrame () 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...
 
virtual 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...
 
virtual 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...
 
virtual math::RigidTransform< T > GetFixedOffsetPoseInBody (const math::RigidTransform< T > &X_FQ) const
 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...
 
virtual math::RotationMatrix< T > GetFixedRotationMatrixInBody (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...
 
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...
 
Does not allow copy, move, or assignment
 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

 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...
 
Methods to make a clone templated on different scalar types.

These methods are meant to be called by MultibodyTree::CloneToScalar() when making a clone of the entire tree or a new instance templated on a different scalar type.

The only const argument to these methods is the new MultibodyTree clone under construction. Specific Frame subclasses might specify a number of prerequisites on the cloned tree and therefore require it to be at a given state of cloning. See MultibodyTree::CloneToScalar() for a list of prerequisites that are guaranteed to be satisfied during the cloning process.

virtual std::unique_ptr< Frame< double > > DoCloneToScalar (const internal::MultibodyTree< double > &tree_clone) const =0
 Clones this Frame (templated on T) to a frame templated on double. More...
 
virtual std::unique_ptr< Frame< AutoDiffXd > > DoCloneToScalar (const internal::MultibodyTree< AutoDiffXd > &tree_clone) const =0
 Clones this Frame (templated on T) to a frame templated on AutoDiffXd. More...
 
virtual std::unique_ptr< Frame< symbolic::Expression > > DoCloneToScalar (const internal::MultibodyTree< symbolic::Expression > &) const =0
 
- 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...
 

Constructor & Destructor Documentation

◆ Frame() [1/4]

Frame ( const Frame< T > &  )
delete

◆ Frame() [2/4]

Frame ( Frame< T > &&  )
delete

◆ Frame() [3/4]

Frame ( const std::string &  name,
const Body< T > &  body,
std::optional< ModelInstanceIndex model_instance = {} 
)
explicitprotected

Only derived classes can use this constructor.

It creates a Frame object attached to body and puts the frame in the body's model instance.

◆ Frame() [4/4]

Frame ( const Body< T > &  body)
explicitprotected

Overload to permit constructing an unnamed frame.

Member Function Documentation

◆ body()

const Body<T>& body ( ) const

Returns a const reference to the body associated to this Frame.

◆ CalcOffsetPoseInBody()

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

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 in BodyFrame< T >, and BodyFrame< double >.

◆ CalcOffsetRotationMatrixInBody()

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

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 in BodyFrame< T >, and BodyFrame< double >.

◆ CalcPose()

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.

See also
CalcPoseInWorld().

◆ CalcPoseInBodyFrame()

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

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.

Implemented in FixedOffsetFrame< T >, BodyFrame< T >, and BodyFrame< double >.

◆ CalcPoseInWorld()

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.

Note
Body::EvalPoseInWorld() provides a more efficient way to obtain the pose for a body frame.

◆ CalcRotationMatrix()

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.

◆ CalcRotationMatrixInBodyFrame()

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

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.

Implemented in FixedOffsetFrame< T >, BodyFrame< T >, and BodyFrame< double >.

◆ CalcRotationMatrixInWorld()

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.

◆ CalcSpatialAccelerationInWorld()

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.

Note
Body::EvalSpatialAccelerationInWorld() provides a more efficient way to obtain the spatial acceleration for a body frame.
When cached values are out of sync with the state stored in context, this method performs an expensive forward dynamics computation, whereas once evaluated, successive calls to this method are inexpensive.

◆ CalcSpatialVelocity()

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.

See also
CalcSpatialVelocityInWorld().

◆ CalcSpatialVelocityInWorld()

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.

Note
Body::EvalSpatialVelocityInWorld() provides a more efficient way to obtain the spatial velocity for a body frame.

◆ CloneToScalar()

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.

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.

See also
MultibodyTree::CloneToScalar()

◆ DoCloneToScalar() [1/3]

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

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

Implemented in FixedOffsetFrame< T >, BodyFrame< T >, and BodyFrame< double >.

◆ DoCloneToScalar() [2/3]

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

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

Implemented in FixedOffsetFrame< T >, BodyFrame< T >, and BodyFrame< double >.

◆ DoCloneToScalar() [3/3]

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

◆ GetFixedOffsetPoseInBody()

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

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 in BodyFrame< T >, and BodyFrame< double >.

◆ GetFixedPoseInBodyFrame()

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

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 in FixedOffsetFrame< T >, BodyFrame< T >, and BodyFrame< double >.

◆ GetFixedRotationMatrixInBody()

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

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 in BodyFrame< T >, and BodyFrame< double >.

◆ GetFixedRotationMatrixInBodyFrame()

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

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 in FixedOffsetFrame< T >, BodyFrame< T >, and BodyFrame< double >.

◆ is_body_frame()

bool is_body_frame ( ) const

Returns true if this is the body frame.

◆ is_world_frame()

bool is_world_frame ( ) const

Returns true if this is the world frame.

◆ name()

const std::string& name ( ) const

Returns the name of this frame. It may be empty if unnamed.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

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