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.,
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
T | The 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 = void> | |
const MultibodyPlant< T > & | 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... | |
bool | is_ephemeral () const |
Returns true if this MultibodyElement was added during Finalize() rather than something a user added. More... | |
void | set_is_ephemeral (bool is_ephemeral) |
(Internal use only) Sets the is_ephemeral flag to the indicated value. More... | |
Does not allow copy, move, or assignment | |
MultibodyElement (const MultibodyElement &)=delete | |
MultibodyElement & | operator= (const MultibodyElement &)=delete |
MultibodyElement (MultibodyElement &&)=delete | |
MultibodyElement & | operator= (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 |
|
delete |
|
delete |
|
virtual |
|
protected |
Default constructor made protected so that sub-classes can still declare their default constructors if they need to.
|
explicitprotected |
Constructor which allows specifying a model instance.
|
explicitprotected |
Both the model instance and element index are specified.
|
protected |
To be used by MultibodyElement-derived objects when declaring parameters in their implementation of DoDeclareParameters().
For an example, see Joint::DoDeclareParameters().
|
protected |
To be used by MultibodyElement-derived objects when declaring parameters in their implementation of DoDeclareParameters().
For an example, see RigidBody::DoDeclareParameters().
void DeclareParameters | ( | internal::MultibodyTreeSystem< T > * | tree_system | ) |
Declares MultibodyTreeSystem Parameters at MultibodyTreeSystem::Finalize() time.
NVI to the virtual method DoDeclareParameters().
[in] | tree_system | A mutable copy of the parent MultibodyTreeSystem. |
|
protectedvirtual |
Implementation of the NVI DeclareParameters().
MultibodyElement-derived objects may override to declare their specific parameters.
|
protectedvirtual |
Implementation of the NVI SetDefaultParameters().
MultibodyElement-derived objects may override to set default values of their specific parameters.
|
protectedpure virtual |
Implementation of the NVI SetTopology().
For advanced use only for developers implementing new MultibodyTree components.
Implemented in Joint< T >.
|
protected |
Returns a constant reference to the parent MultibodyTree that owns this element.
const MultibodyPlant<T>& GetParentPlant | ( | ) | const |
Returns the MultibodyPlant that owns this MultibodyElement.
drake/multibody/plant/multibody_plant.h
in the translation unit that invokes this method; multibody_element.h cannot do that for you.std::exception | if there is no MultibodyPlant owner. |
|
protected |
Returns a constant reference to the parent MultibodyTreeSystem that owns the parent MultibodyTree that owns this element.
|
protected |
Returns this element's unique index.
bool is_ephemeral | ( | ) | const |
Returns true
if this MultibodyElement was added during Finalize() rather than something a user added.
(See class comments.)
ModelInstanceIndex model_instance | ( | ) | const |
Returns the ModelInstanceIndex of the model instance to which this element belongs.
|
delete |
|
delete |
|
protected |
Returns this element's unique ordinal.
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
.
void SetDefaultParameters | ( | systems::Parameters< T > * | parameters | ) | const |
Sets default values of parameters belonging to each MultibodyElement in parameters
at a call to MultibodyTreeSystem::SetDefaultParameters().
[out] | parameters | A mutable collections of parameters in a context. |
|
protected |
Gives MultibodyElement-derived objects the opportunity to retrieve their topology after MultibodyTree::Finalize() is invoked.
NVI to pure virtual method DoSetTopology().
|
friend |
|
friend |