Drake
Drake C++ Documentation
Loading...
Searching...
No Matches
MultibodyElement< T > Class Template Referenceabstract

Detailed Description

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

A class representing an element (subcomponent) of a MultibodyPlant or (internally) a MultibodyTree.

Examples of multibody elements are bodies, joints, force elements, and actuators. After a Finalize() call, multibody elements get assigned a type-specific index that uniquely identifies them. By convention, every subclass of MultibodyElement provides an index() member function that returns the assigned index, e.g.,

/** Returns this element's unique index. */
BodyIndex index() const { return this->template index_impl<BodyIndex>(); }
ElementIndexType index_impl() const
Returns this element's unique index.
Definition multibody_element.h:116
TypeSafeIndex< class RigidBodyTag > BodyIndex
Type used to identify RigidBodies (a.k.a.
Definition multibody_tree_indexes.h:36

Some multibody elements are added during Finalize() and are not part of the user-specified model. These are called "ephemeral" elements and can be identified using the is_ephemeral() function here. Examples include

  • free joints added to connect lone bodies or free-floating trees to World
  • fixed offset frames added when joints are modeled by mobilizers
  • all mobilizers.
Template Parameters
TThe scalar type, which must be one of the default scalars.

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

Public Member Functions

virtual ~MultibodyElement ()
ModelInstanceIndex model_instance () const
 Returns the ModelInstanceIndex of the model instance to which this element belongs.
template<typename = void>
const MultibodyPlant< T > & GetParentPlant () const
 Returns the MultibodyPlant that owns this MultibodyElement.
void DeclareParameters (internal::MultibodyTreeSystem< T > *tree_system)
 Declares MultibodyTreeSystem Parameters at MultibodyTreeSystem::Finalize() time.
void SetDefaultParameters (systems::Parameters< T > *parameters) const
 Sets default values of parameters belonging to each MultibodyElement in parameters at a call to MultibodyTreeSystem::SetDefaultParameters().
void DeclareDiscreteState (internal::MultibodyTreeSystem< T > *tree_system)
 Declares MultibodyTreeSystem discrete states.
void DeclareCacheEntries (internal::MultibodyTreeSystem< T > *tree_system)
 (Advanced) Declares all cache entries needed by this element.
bool is_ephemeral () const
 Returns true if this MultibodyElement was added during Finalize() rather than something a user added.
void set_is_ephemeral (bool is_ephemeral)
 (Internal use only) Sets the is_ephemeral flag to the indicated value.
Does not allow copy, move, or assignment
 MultibodyElement (const MultibodyElement &)=delete
MultibodyElementoperator= (const MultibodyElement &)=delete
 MultibodyElement (MultibodyElement &&)=delete
MultibodyElementoperator= (MultibodyElement &&)=delete

Protected Member Functions

 MultibodyElement ()
 Default constructor made protected so that sub-classes can still declare their default constructors if they need to.
 MultibodyElement (ModelInstanceIndex model_instance)
 Constructor which allows specifying a model instance.
 MultibodyElement (ModelInstanceIndex model_instance, int64_t index)
 Both the model instance and element index are specified.
template<typename ElementIndexType>
ElementIndexType index_impl () const
 Returns this element's unique index.
template<typename ElementOrdinalType = int64_t>
ElementOrdinalType ordinal_impl () const
 Returns this element's unique ordinal.
const internal::MultibodyTree< T > & get_parent_tree () const
 Returns a constant reference to the parent MultibodyTree that owns this element.
const internal::MultibodyTreeSystem< T > & GetParentTreeSystem () const
 Returns a constant reference to the parent MultibodyTreeSystem that owns the parent MultibodyTree that owns this element.
void SetTopology ()
 (Internal use only) Gives MultibodyElement-derived objects the opportunity to set data members that depend on topology and coordinate assignments having been finalized.
virtual void DoSetTopology ()=0
 Implementation of the NVI SetTopology().
virtual void DoDeclareParameters (internal::MultibodyTreeSystem< T > *)
 Implementation of the NVI DeclareParameters().
virtual void DoSetDefaultParameters (systems::Parameters< T > *) const
 Implementation of the NVI SetDefaultParameters().
virtual void DoDeclareDiscreteState (internal::MultibodyTreeSystem< T > *)
 Implementation of the NVI DeclareDiscreteState().
virtual void DoDeclareCacheEntries (internal::MultibodyTreeSystem< T > *)
 Derived classes must override this method to declare cache entries needed by this element.
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().
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().
systems::DiscreteStateIndex DeclareDiscreteState (internal::MultibodyTreeSystem< T > *tree_system, const VectorX< T > &model_value)
 To be used by MultibodyElement-derived objects when declaring discrete states in their implementation of DoDeclareDiscreteStates().
systems::CacheEntryDeclareCacheEntry (internal::MultibodyTreeSystem< T > *tree_system, std::string description, systems::ValueProducer value_producer, std::set< systems::DependencyTicket > prerequisites_of_calc)
 To be used by MultibodyElement-derived objects when declaring cache entries in their implementation of DoDeclareCacheEntries().
bool has_parent_tree () const
 Returns true if this multibody element has a parent tree, otherwise false.

Friends

class internal::MultibodyTree< T >
class DeformableModel< T >
class MultibodyElementTester

Constructor & Destructor Documentation

◆ MultibodyElement() [1/5]

template<typename T>
MultibodyElement ( const MultibodyElement< T > & )
delete

◆ MultibodyElement() [2/5]

template<typename T>
MultibodyElement ( MultibodyElement< T > && )
delete

◆ ~MultibodyElement()

template<typename T>
virtual ~MultibodyElement ( )
virtual

◆ MultibodyElement() [3/5]

template<typename T>
MultibodyElement ( )
protected

Default constructor made protected so that sub-classes can still declare their default constructors if they need to.

◆ MultibodyElement() [4/5]

template<typename T>
MultibodyElement ( ModelInstanceIndex model_instance)
explicitprotected

Constructor which allows specifying a model instance.

◆ MultibodyElement() [5/5]

template<typename T>
MultibodyElement ( ModelInstanceIndex model_instance,
int64_t index )
explicitprotected

Both the model instance and element index are specified.

Member Function Documentation

◆ DeclareAbstractParameter()

template<typename T>
systems::AbstractParameterIndex DeclareAbstractParameter ( internal::MultibodyTreeSystem< T > * tree_system,
const AbstractValue & model_value )
protected

To be used by MultibodyElement-derived objects when declaring parameters in their implementation of DoDeclareParameters().

For an example, see Joint::DoDeclareParameters().

◆ DeclareCacheEntries()

template<typename T>
void DeclareCacheEntries ( internal::MultibodyTreeSystem< T > * tree_system)

(Advanced) Declares all cache entries needed by this element.

This method is called by MultibodyTree on this element during MultibodyTree::Finalize(). It subsequently calls DoDeclareCacheEntries(). Custom elements that need to declare cache entries must override DoDeclareCacheEntries().

◆ DeclareCacheEntry()

template<typename T>
systems::CacheEntry & DeclareCacheEntry ( internal::MultibodyTreeSystem< T > * tree_system,
std::string description,
systems::ValueProducer value_producer,
std::set< systems::DependencyTicket > prerequisites_of_calc )
protected

To be used by MultibodyElement-derived objects when declaring cache entries in their implementation of DoDeclareCacheEntries().

For an example, see DeformableBody::DoDeclareCacheEntries().

◆ DeclareDiscreteState() [1/2]

template<typename T>
void DeclareDiscreteState ( internal::MultibodyTreeSystem< T > * tree_system)

Declares MultibodyTreeSystem discrete states.

NVI to the virtual method DoDeclareDiscreteState().

Parameters
[in]tree_systemA mutable copy of the parent MultibodyTreeSystem.
Precondition
'tree_system' must be the same as the parent tree system (what's returned from GetParentTreeSystem()).

◆ DeclareDiscreteState() [2/2]

template<typename T>
systems::DiscreteStateIndex DeclareDiscreteState ( internal::MultibodyTreeSystem< T > * tree_system,
const VectorX< T > & model_value )
protected

To be used by MultibodyElement-derived objects when declaring discrete states in their implementation of DoDeclareDiscreteStates().

For an example, see DeformableBody::DoDeclareDiscreteStates().

◆ DeclareNumericParameter()

template<typename T>
systems::NumericParameterIndex DeclareNumericParameter ( internal::MultibodyTreeSystem< T > * tree_system,
const systems::BasicVector< T > & model_vector )
protected

To be used by MultibodyElement-derived objects when declaring parameters in their implementation of DoDeclareParameters().

For an example, see RigidBody::DoDeclareParameters().

◆ DeclareParameters()

template<typename T>
void DeclareParameters ( internal::MultibodyTreeSystem< T > * tree_system)

Declares MultibodyTreeSystem Parameters at MultibodyTreeSystem::Finalize() time.

NVI to the virtual method DoDeclareParameters().

Parameters
[in]tree_systemA mutable copy of the parent MultibodyTreeSystem.
Precondition
'tree_system' must be the same as the parent tree system (what's returned from GetParentTreeSystem()).

◆ DoDeclareCacheEntries()

template<typename T>
virtual void DoDeclareCacheEntries ( internal::MultibodyTreeSystem< T > * )
protectedvirtual

Derived classes must override this method to declare cache entries needed by this element.

The default implementation is a no-op.

◆ DoDeclareDiscreteState()

template<typename T>
virtual void DoDeclareDiscreteState ( internal::MultibodyTreeSystem< T > * )
protectedvirtual

Implementation of the NVI DeclareDiscreteState().

MultibodyElement-derived objects may override to declare their specific state variables.

◆ DoDeclareParameters()

template<typename T>
virtual void DoDeclareParameters ( internal::MultibodyTreeSystem< T > * )
protectedvirtual

Implementation of the NVI DeclareParameters().

MultibodyElement-derived objects may override to declare their specific parameters.

◆ DoSetDefaultParameters()

template<typename T>
virtual void DoSetDefaultParameters ( systems::Parameters< T > * ) const
protectedvirtual

Implementation of the NVI SetDefaultParameters().

MultibodyElement-derived objects may override to set default values of their specific parameters.

◆ DoSetTopology()

template<typename T>
virtual void DoSetTopology ( )
protectedpure virtual

Implementation of the NVI SetTopology().

For advanced use only for developers implementing new MultibodyTree components.

Implemented in Joint< T >.

◆ get_parent_tree()

template<typename T>
const internal::MultibodyTree< T > & get_parent_tree ( ) const
protected

Returns a constant reference to the parent MultibodyTree that owns this element.

Precondition
has_parent_tree is true.

◆ GetParentPlant()

template<typename T>
template<typename = void>
const MultibodyPlant< T > & GetParentPlant ( ) const

Returns the MultibodyPlant that owns this MultibodyElement.

Note
You can only invoke this method if you have a definition of MultibodyPlant available. That is, you must include drake/multibody/plant/multibody_plant.h in the translation unit that invokes this method; multibody_element.h cannot do that for you.
Exceptions
std::exceptionif there is no MultibodyPlant owner.

◆ GetParentTreeSystem()

template<typename T>
const internal::MultibodyTreeSystem< T > & GetParentTreeSystem ( ) const
protected

Returns a constant reference to the parent MultibodyTreeSystem that owns the parent MultibodyTree that owns this element.

Exceptions
std::exceptionif has_parent_tree() is false.

◆ has_parent_tree()

template<typename T>
bool has_parent_tree ( ) const
protected

Returns true if this multibody element has a parent tree, otherwise false.

◆ index_impl()

template<typename T>
template<typename ElementIndexType>
ElementIndexType index_impl ( ) const
protected

Returns this element's unique index.

◆ is_ephemeral()

template<typename T>
bool is_ephemeral ( ) const

Returns true if this MultibodyElement was added during Finalize() rather than something a user added.

(See class comments.)

◆ model_instance()

template<typename T>
ModelInstanceIndex model_instance ( ) const

Returns the ModelInstanceIndex of the model instance to which this element belongs.

◆ operator=() [1/2]

template<typename T>
MultibodyElement & operator= ( const MultibodyElement< T > & )
delete

◆ operator=() [2/2]

template<typename T>
MultibodyElement & operator= ( MultibodyElement< T > && )
delete

◆ ordinal_impl()

template<typename T>
template<typename ElementOrdinalType = int64_t>
ElementOrdinalType ordinal_impl ( ) const
protected

Returns this element's unique ordinal.

Note
The int64_t default is present for backwards compatibility but you should not use it. Instead, define a ThingOrdinal specialization of TypeSafeIndex for any element Thing that has a meaningful ordinal. Then use that type explicitly in Thing's public ordinal() method.

◆ set_is_ephemeral()

template<typename T>
void set_is_ephemeral ( bool is_ephemeral)

(Internal use only) Sets the is_ephemeral flag to the indicated value.

The default if this is never called is false. Any element that is added during Finalize() should set this flag to true.

◆ SetDefaultParameters()

template<typename T>
void SetDefaultParameters ( systems::Parameters< T > * parameters) const

Sets default values of parameters belonging to each MultibodyElement in parameters at a call to MultibodyTreeSystem::SetDefaultParameters().

Parameters
[out]parametersA mutable collections of parameters in a context.
Precondition
parameters != nullptr

◆ SetTopology()

template<typename T>
void SetTopology ( )
protected

(Internal use only) Gives MultibodyElement-derived objects the opportunity to set data members that depend on topology and coordinate assignments having been finalized.

This is invoked at the end of MultibodyTree::Finalize(). NVI to pure virtual method DoSetTopology().

◆ DeformableModel< T >

template<typename T>
friend class DeformableModel< T >
friend

◆ internal::MultibodyTree< T >

template<typename T>
friend class internal::MultibodyTree< T >
friend

◆ MultibodyElementTester

template<typename T>
friend class MultibodyElementTester
friend

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