Drake
Drake C++ Documentation
FixedOffsetFrame< T > Class Template Referencefinal

Detailed Description

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

FixedOffsetFrame represents a material frame F whose pose is fixed with respect to a parent material frame P.

The pose offset is given by a spatial transform X_PF, which is constant after construction. For instance, we could rigidly attach a frame F to move with a rigid body B at a fixed pose X_BF, where B is the RigidBodyFrame associated with body B. Thus, the World frame pose X_WF of a FixedOffsetFrame F depends only on the World frame pose X_WP of its parent P, and the constant pose X_PF, with X_WF=X_WP*X_PF.

For more information about spatial transforms, see Spatial Pose and Transform.

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

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

Public Member Functions

 FixedOffsetFrame (const std::string &name, const Frame< T > &P, const math::RigidTransform< double > &X_PF, std::optional< ModelInstanceIndex > model_instance={})
 Creates a material Frame F whose pose is fixed with respect to its parent material Frame P. More...
 
 FixedOffsetFrame (const std::string &name, const RigidBody< T > &bodyB, const math::RigidTransform< double > &X_BF)
 Creates a material Frame F whose pose is fixed with respect to the RigidBodyFrame B of the given RigidBody, which serves as F's parent frame. More...
 
math::RigidTransform< T > CalcPoseInBodyFrame (const systems::Context< T > &context) 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 > &context) 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...
 
void SetPoseInParentFrame (systems::Context< T > *context, const math::RigidTransform< T > &X_PF) const
 Sets the pose of this frame F in its parent frame P. More...
 
math::RigidTransform< T > GetPoseInParentFrame (const systems::Context< T > &context) const
 Returns the rigid transform X_PF that characterizes this frame F's pose in its parent frame P. More...
 
math::RigidTransform< T > GetFixedPoseInBodyFrame () const override
 
math::RotationMatrix< T > GetFixedRotationMatrixInBodyFrame () const override
 
Does not allow copy, move, or assignment
 FixedOffsetFrame (const FixedOffsetFrame &)=delete
 
FixedOffsetFrameoperator= (const FixedOffsetFrame &)=delete
 
 FixedOffsetFrame (FixedOffsetFrame &&)=delete
 
FixedOffsetFrameoperator= (FixedOffsetFrame &&)=delete
 
- Public Member Functions inherited from Frame< T >
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...
 
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...
 
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
 
Frameoperator= (const Frame &)=delete
 
 Frame (Frame &&)=delete
 
Frameoperator= (Frame &&)=delete
 
- Public Member Functions inherited from FrameBase< T >
FrameIndex index () const
 Returns this element's unique index. 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
 
MultibodyElementoperator= (const MultibodyElement &)=delete
 
 MultibodyElement (MultibodyElement &&)=delete
 
MultibodyElementoperator= (MultibodyElement &&)=delete
 

Protected Member Functions

Methods to make a clone templated on different scalar types.

These methods provide implementations to the different overrides of Frame::DoCloneToScalar().

The only const argument to these methods is the new MultibodyTree clone under construction, which is required to already own the clone to the parent frame of the frame being cloned.

std::unique_ptr< Frame< double > > DoCloneToScalar (const internal::MultibodyTree< double > &tree_clone) const override
 
std::unique_ptr< Frame< AutoDiffXd > > DoCloneToScalar (const internal::MultibodyTree< AutoDiffXd > &tree_clone) const override
 
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 RigidBody< T > &body, std::optional< ModelInstanceIndex > model_instance={})
 Only derived classes can use this constructor. More...
 
- Protected Member Functions inherited from FrameBase< T >
 FrameBase (ModelInstanceIndex model_instance)
 
- 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...
 
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...
 

Constructor & Destructor Documentation

◆ FixedOffsetFrame() [1/4]

FixedOffsetFrame ( const FixedOffsetFrame< T > &  )
delete

◆ FixedOffsetFrame() [2/4]

FixedOffsetFrame ( FixedOffsetFrame< T > &&  )
delete

◆ FixedOffsetFrame() [3/4]

FixedOffsetFrame ( const std::string &  name,
const Frame< T > &  P,
const math::RigidTransform< double > &  X_PF,
std::optional< ModelInstanceIndex model_instance = {} 
)

Creates a material Frame F whose pose is fixed with respect to its parent material Frame P.

The pose is given by a spatial transform X_PF; see class documentation for more information.

Parameters
[in]nameThe name of this frame. Cannot be empty.
[in]PThe frame to which this frame is attached with a fixed pose.
[in]X_PFThe default transform giving the pose of F in P, therefore only the value (as a RigidTransform<double>) is provided.
[in]model_instanceThe model instance to which this frame belongs to. If unspecified, will use P.body().model_instance().

◆ FixedOffsetFrame() [4/4]

FixedOffsetFrame ( const std::string &  name,
const RigidBody< T > &  bodyB,
const math::RigidTransform< double > &  X_BF 
)

Creates a material Frame F whose pose is fixed with respect to the RigidBodyFrame B of the given RigidBody, which serves as F's parent frame.

The pose is given by a RigidTransform X_BF; see class documentation for more information.

Parameters
[in]nameThe name of this frame. Cannot be empty.
[in]bodyBThe body whose RigidBodyFrame B is to be F's parent frame.
[in]X_BFThe transform giving the pose of F in B.

Member Function Documentation

◆ 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
Precondition
The parent frame to this frame already has a clone in tree_clone.

Implements Frame< T >.

◆ DoCloneToScalar() [2/3]

std::unique_ptr<Frame<AutoDiffXd> > DoCloneToScalar ( const internal::MultibodyTree< AutoDiffXd > &  tree_clone) const
overrideprotectedvirtual
Precondition
The parent frame to this frame already has a clone in tree_clone.

Implements Frame< T >.

◆ DoCloneToScalar() [3/3]

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

Implements Frame< T >.

◆ GetFixedPoseInBodyFrame()

math::RigidTransform<T> GetFixedPoseInBodyFrame ( ) const
overridevirtual
Returns
The default fixed pose in the body frame.

Reimplemented from Frame< T >.

◆ GetFixedRotationMatrixInBodyFrame()

math::RotationMatrix<T> GetFixedRotationMatrixInBodyFrame ( ) const
overridevirtual
Returns
The default rotation matrix of this fixed pose in the body frame.

Reimplemented from Frame< T >.

◆ GetPoseInParentFrame()

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

Returns the rigid transform X_PF that characterizes this frame F's pose in its parent frame P.

Parameters
[in]contextcontains the state of the multibody plant.
Precondition
this frame has been registered in the given context.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ SetPoseInParentFrame()

void SetPoseInParentFrame ( systems::Context< T > *  context,
const math::RigidTransform< T > &  X_PF 
) const

Sets the pose of this frame F in its parent frame P.

Parameters
[in]contextcontains the state of the multibody plant.
[in]X_PFRigid transform that characterizes this frame F's pose (orientation and position) in its parent frame P.
Precondition
this frame has been registered in the given context.

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