(Internal) PhysicalModel provides the functionalities to extend the type of physical model of MultibodyPlant.
Developers can derive from this PhysicalModel to incorporate additional model elements coupled with the rigid body dynamics. For instance, simulation of deformable objects requires additional state and ports to interact with externals systems such as visualization.
Similar to the routine of adding multiple model elements in MultibodyPlant, users should add all the model elements they wish to add to a PhysicalModel before the owning MultibodyPlant calls Finalize()
. When Finalize()
is invoked, MultibodyPlant will allocate the system level context resources for each PhysicalModel it owns. After the system resources are allocated, model mutation in the PhysicalModels owned by MultibodyPlant is not allowed.
This class is for internal use only. Use derived concrete models (e.g. DeformableModel) instead.
T | The scalar type, which must be one of the default scalars. |
#include <drake/multibody/plant/physical_model.h>
Public Member Functions | |
PhysicalModel (MultibodyPlant< T > *owning_plant) | |
Constructs a PhysicalModel owned by the given owning_plant . More... | |
~PhysicalModel () override | |
template<typename ScalarType > | |
std::unique_ptr< PhysicalModel< ScalarType > > | CloneToScalar (MultibodyPlant< ScalarType > *plant) const |
(Internal only) Creates a clone of this concrete PhysicalModel object with the scalar type ScalarType to be owned by the given plant . More... | |
bool | is_cloneable_to_double () const override |
Defaults to false. More... | |
bool | is_cloneable_to_autodiff () const override |
Defaults to false. More... | |
bool | is_cloneable_to_symbolic () const override |
Defaults to false. More... | |
void | DeclareSystemResources () |
(Internal only) MultibodyPlant calls this from within Finalize() to declare additional system resources. More... | |
void | DeclareSceneGraphPorts () |
(Internal only) Declares zero or more output ports in the owning MultibodyPlant to communicate with a SceneGraph. More... | |
PhysicalModelPointerVariant< T > | ToPhysicalModelPointerVariant () const |
Returns (a const pointer to) the specific model variant of this PhysicalModel. More... | |
const MultibodyPlant< T > * | plant () const |
Does not allow copy, move, or assignment | |
PhysicalModel (const PhysicalModel &)=delete | |
PhysicalModel & | operator= (const PhysicalModel &)=delete |
PhysicalModel (PhysicalModel &&)=delete | |
PhysicalModel & | operator= (PhysicalModel &&)=delete |
|
delete |
|
delete |
|
explicit |
Constructs a PhysicalModel owned by the given owning_plant
.
The lifespan of the owning_plant
must outlast this
PhysicalModel. This PhysicalModel declares System resources from the owning_plant
in the call to DeclareSystemResources()
through the call to MultibodyPlant::Finalize()
.
|
override |
|
protectedvirtual |
|
protectedvirtual |
std::unique_ptr<PhysicalModel<ScalarType> > CloneToScalar | ( | MultibodyPlant< ScalarType > * | plant | ) | const |
(Internal only) Creates a clone of this
concrete PhysicalModel object with the scalar type ScalarType
to be owned by the given plant
.
The clone should be a deep copy of the original PhysicalModel with the exception of members overwritten in DeclareSystemResources()
. This method is meant to be called by the scalar-converting copy constructor of MultibodyPlant only and thus is only called from a finalized MultibodyPlant.
T | The scalar type, which must be one of the default scalars. |
std::exception | if plant is nullptr. |
std::exception | if the owning plant of this PhysicalModel is not finalized. |
[in] | plant | pointer to the MultibodyPlant owning the clone. This needs to be a mutable pointer because the constructor of the clone requires a mutable pointer to the owning plant. |
DeclareSystemResources()
is not called on the clone and needs to be called from the plant owning the clone.
|
protectedvirtual |
|
protected |
|
protected |
void DeclareSceneGraphPorts | ( | ) |
(Internal only) Declares zero or more output ports in the owning MultibodyPlant to communicate with a SceneGraph.
std::exception | if called after call to DeclareSystemResources(). |
std::exception | if called more than once when at least one output port is created. |
void DeclareSystemResources | ( | ) |
(Internal only) MultibodyPlant calls this from within Finalize() to declare additional system resources.
This method is only meant to be called by MultibodyPlant. The pointer to the owning plant is nulled after call to this function.
|
protected |
|
protectedvirtual |
|
protectedpure virtual |
|
protectedpure virtual |
|
override |
Defaults to false.
Derived classes that support making a clone that uses AutoDiffXd as a scalar type must override this to return true.
|
override |
Defaults to false.
Derived classes that support making a clone that uses double as a scalar type must override this to return true.
|
override |
Defaults to false.
Derived classes that support making a clone that uses symbolic::Expression as a scalar type must override this to return true.
|
protected |
|
protected |
|
delete |
|
delete |
const MultibodyPlant<T>* plant | ( | ) | const |
|
protected |
|
protected |
PhysicalModelPointerVariant<T> ToPhysicalModelPointerVariant | ( | ) | const |
Returns (a const pointer to) the specific model variant of this
PhysicalModel.
Note that the variant contains a pointer to the concrete model and therefore should not persist longer than the lifespan of this model.