Drake
Drake C++ Documentation
FrameBase< T > Class Template Reference

Detailed Description

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

FrameBase is an abstract representation of the concept of a frame in multibody dynamics.

A frame F is a mathematical object consisting of a set of three orthogonal unit vector axes Fx,Fy,Fz forming a right-handed orthogonal basis located at a point Fo called the frame's origin. If the frame origin Fo is a material point of a body, then F is a material frame (also called a physical frame) and can be used to apply forces and torques to its body. A material frame can serve as an attachment point for force-producing elements such as joints and constraints. Otherwise, we call the frame a free-floating or computed frame and it is still suited for observation, visualization, and measurement but cannot be used to apply forces. Because material frames are by far the most common and useful frames encountered in multibody systems, the derived class with the simple name Frame is used to represent them.

Given numerical values in a Context for the associated multibody system, every frame has a location and orientation (collectively, pose) in space that can be obtained through this base class. Most frames will also move based on the multibody system's configuration, or on general runtime computations, so may have meaningful spatial velocity and acceleration – that will always be the case for material frames during a dynamic simulation. Such kinematic quantities must always be measured with respect to some other specified frame. The only frame we can be sure exists is the World frame W, so pose and motion with respect to W are always available. Utilities are provided for calculating frame motion with respect to other frames. Derived frame objects will have additional properties. For example, material frames have an associated Body.

Summarizing, FrameBase serves as an abstraction for a general frame object; it doesn't store any values itself. As always in Drake, runtime values are obtained from a Context object. FrameBase provides an interface through which the pose of a frame may be obtained from a given Context. Classes derived from FrameBase are used to represent more specific types of frames, most importantly whether a frame is associated with a material point of a body.

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

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

Public Member Functions

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

 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...
 
virtual void DoSetTopology (const internal::MultibodyTreeTopology &tree)=0
 Implementation of the NVI SetTopology(). More...
 
virtual void DoDeclareParameters (internal::MultibodyTreeSystem< T > *)
 Implementation of the NVI DeclareParameters(). More...
 
virtual void DoSetDefaultParameters (systems::Parameters< T > *) const
 Implementation of the NVI SetDefaultParameters(). 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

◆ FrameBase()

FrameBase ( ModelInstanceIndex  model_instance)
explicitprotected

Member Function Documentation

◆ index()

FrameIndex index ( ) const

Returns this element's unique index.


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