(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 ()=default | |
~PhysicalModel () override=default | |
template<typename ScalarType > | |
std::unique_ptr< PhysicalModel< ScalarType > > | CloneToScalar () const |
Creates a clone of the concrete PhysicalModel object with the scalar type ScalarType . 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 (MultibodyPlant< T > *plant) |
MultibodyPlant calls this from within Finalize() to declare additional system resources. More... | |
PhysicalModelPointerVariant< T > | ToPhysicalModelPointerVariant () const |
Returns (a const pointer to) the specific model variant of this PhysicalModel. More... | |
Does not allow copy, move, or assignment | |
PhysicalModel (const PhysicalModel &)=delete | |
PhysicalModel & | operator= (const PhysicalModel &)=delete |
PhysicalModel (PhysicalModel &&)=delete | |
PhysicalModel & | operator= (PhysicalModel &&)=delete |
Protected Member Functions | |
virtual PhysicalModelPointerVariant< T > | DoToPhysicalModelPointerVariant () const =0 |
virtual std::unique_ptr< PhysicalModel< double > > | CloneToDouble () const |
virtual std::unique_ptr< PhysicalModel< AutoDiffXd > > | CloneToAutoDiffXd () const |
virtual std::unique_ptr< PhysicalModel< symbolic::Expression > > | CloneToSymbolic () const |
virtual void | DoDeclareSystemResources (MultibodyPlant< T > *plant)=0 |
void | ThrowIfSystemResourcesDeclared (const char *source_method) const |
void | ThrowIfSystemResourcesNotDeclared (const char *source_method) const |
geometry::SceneGraph< T > & | mutable_scene_graph (MultibodyPlant< T > *plant) |
Static Protected Member Functions | |
static systems::DiscreteStateIndex | DeclareDiscreteState (MultibodyPlant< T > *plant, const VectorX< T > &model_value) |
static systems::LeafOutputPort< T > & | DeclareAbstractOutputPort (MultibodyPlant< T > *plant, std::string name, typename systems::LeafOutputPort< T >::AllocCallback alloc_function, typename systems::LeafOutputPort< T >::CalcCallback calc_function, std::set< systems::DependencyTicket > prerequisites_of_calc={ systems::System< T >::all_sources_ticket()}) |
static systems::LeafOutputPort< T > & | DeclareVectorOutputPort (MultibodyPlant< T > *plant, std::string name, const systems::BasicVector< T > &model_vector, typename systems::LeafOutputPort< T >::CalcVectorCallback vector_calc_function, std::set< systems::DependencyTicket > prerequisites_of_calc={ systems::System< T >::all_sources_ticket()}) |
|
delete |
|
delete |
|
default |
|
overridedefault |
|
protectedvirtual |
|
protectedvirtual |
std::unique_ptr<PhysicalModel<ScalarType> > CloneToScalar | ( | ) | const |
Creates a clone of the concrete PhysicalModel object with the scalar type ScalarType
.
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.
T | The scalar type, which must be one of the default scalars. |
|
protectedvirtual |
|
staticprotected |
|
staticprotected |
void DeclareSystemResources | ( | MultibodyPlant< T > * | plant | ) |
MultibodyPlant calls this from within Finalize() to declare additional system resources.
This method is only meant to be called by MultibodyPlant. We pass in a MultibodyPlant pointer so that derived PhysicalModels can use specific MultibodyPlant cache tickets.
|
staticprotected |
|
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 |
|
delete |
|
delete |
|
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.