Drake
Drake C++ Documentation
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>(); }
Template Parameters
TThe scalar type, which must be one of the default scalars.

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

Public Member Functions

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...
 
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. 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...
 
int ordinal_impl () const
 Returns this element's unique ordinal. 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...
 

Friends

class internal::MultibodyTree< T >
 
class MultibodyElementTester
 

Constructor & Destructor Documentation

◆ MultibodyElement() [1/5]

MultibodyElement ( const MultibodyElement< T > &  )
delete

◆ MultibodyElement() [2/5]

MultibodyElement ( MultibodyElement< T > &&  )
delete

◆ ~MultibodyElement()

virtual ~MultibodyElement ( )
virtual

◆ MultibodyElement() [3/5]

MultibodyElement ( )
protected

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

◆ MultibodyElement() [4/5]

MultibodyElement ( ModelInstanceIndex  model_instance)
explicitprotected

Constructor which allows specifying a model instance.

◆ MultibodyElement() [5/5]

MultibodyElement ( ModelInstanceIndex  model_instance,
int64_t  index 
)
explicitprotected

Both the model instance and element index are specified.

Member Function Documentation

◆ DeclareAbstractParameter()

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

◆ DeclareNumericParameter()

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

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

◆ DoDeclareParameters()

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

Implementation of the NVI DeclareParameters().

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

◆ DoSetDefaultParameters()

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

virtual void DoSetTopology ( const internal::MultibodyTreeTopology &  tree)
protectedpure virtual

Implementation of the NVI SetTopology().

For advanced use only for developers implementing new MultibodyTree components.

Implemented in Joint< T >.

◆ get_parent_tree()

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

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

◆ GetParentPlant()

const MultibodyPlantDeferred& 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()

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

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

◆ index_impl()

ElementIndexType index_impl ( ) const
protected

Returns this element's unique index.

◆ model_instance()

ModelInstanceIndex model_instance ( ) const

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

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ ordinal_impl()

int ordinal_impl ( ) const
protected

Returns this element's unique ordinal.

◆ SetDefaultParameters()

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

void SetTopology ( const internal::MultibodyTreeTopology &  tree)
protected

Gives MultibodyElement-derived objects the opportunity to retrieve their topology after MultibodyTree::Finalize() is invoked.

NVI to pure virtual method DoSetTopology().

Friends And Related Function Documentation

◆ internal::MultibodyTree< T >

friend class internal::MultibodyTree< T >
friend

◆ MultibodyElementTester

friend class MultibodyElementTester
friend

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