Drake
Drake C++ Documentation
PhysicalModel< T > Class Template Referenceabstract

Detailed Description

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

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

Template Parameters
TThe 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
 
PhysicalModeloperator= (const PhysicalModel &)=delete
 
 PhysicalModel (PhysicalModel &&)=delete
 
PhysicalModeloperator= (PhysicalModel &&)=delete
 

Protected Member Functions

MultibodyPlant< T > * mutable_plant ()
 
virtual PhysicalModelPointerVariant< T > DoToPhysicalModelPointerVariant () const =0
 
virtual std::unique_ptr< PhysicalModel< double > > CloneToDouble (MultibodyPlant< double > *plant) const
 
virtual std::unique_ptr< PhysicalModel< AutoDiffXd > > CloneToAutoDiffXd (MultibodyPlant< AutoDiffXd > *plant) const
 
virtual std::unique_ptr< PhysicalModel< symbolic::Expression > > CloneToSymbolic (MultibodyPlant< symbolic::Expression > *plant) const
 
virtual void DoDeclareSystemResources ()=0
 
virtual void DoDeclareSceneGraphPorts ()
 
void ThrowIfSystemResourcesDeclared (const char *function_name) const
 
void ThrowIfSystemResourcesNotDeclared (const char *function_name) const
 
geometry::SceneGraph< T > & mutable_scene_graph ()
 
systems::DiscreteStateIndex DeclareDiscreteState (const VectorX< T > &model_value)
 
systems::LeafOutputPort< T > & DeclareAbstractOutputPort (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()})
 
systems::LeafOutputPort< T > & DeclareVectorOutputPort (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()})
 

Constructor & Destructor Documentation

◆ PhysicalModel() [1/3]

PhysicalModel ( const PhysicalModel< T > &  )
delete

◆ PhysicalModel() [2/3]

PhysicalModel ( PhysicalModel< T > &&  )
delete

◆ PhysicalModel() [3/3]

PhysicalModel ( MultibodyPlant< T > *  owning_plant)
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().

Precondition
owning_plant != nullptr.

◆ ~PhysicalModel()

~PhysicalModel ( )
override

Member Function Documentation

◆ CloneToAutoDiffXd()

virtual std::unique_ptr<PhysicalModel<AutoDiffXd> > CloneToAutoDiffXd ( MultibodyPlant< AutoDiffXd > *  plant) const
protectedvirtual

◆ CloneToDouble()

virtual std::unique_ptr<PhysicalModel<double> > CloneToDouble ( MultibodyPlant< double > *  plant) const
protectedvirtual

◆ CloneToScalar()

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.

Template Parameters
TThe scalar type, which must be one of the default scalars.
Exceptions
std::exceptionif plant is nullptr.
std::exceptionif the owning plant of this PhysicalModel is not finalized.
Parameters
[in]plantpointer 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.
Note
DeclareSystemResources() is not called on the clone and needs to be called from the plant owning the clone.

◆ CloneToSymbolic()

virtual std::unique_ptr<PhysicalModel<symbolic::Expression> > CloneToSymbolic ( MultibodyPlant< symbolic::Expression > *  plant) const
protectedvirtual

◆ DeclareAbstractOutputPort()

systems::LeafOutputPort<T>& DeclareAbstractOutputPort ( 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()} 
)
protected

◆ DeclareDiscreteState()

systems::DiscreteStateIndex DeclareDiscreteState ( const VectorX< T > &  model_value)
protected

◆ DeclareSceneGraphPorts()

void DeclareSceneGraphPorts ( )

(Internal only) Declares zero or more output ports in the owning MultibodyPlant to communicate with a SceneGraph.

Exceptions
std::exceptionif called after call to DeclareSystemResources().
std::exceptionif called more than once when at least one output port is created.

◆ DeclareSystemResources()

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.

◆ DeclareVectorOutputPort()

systems::LeafOutputPort<T>& DeclareVectorOutputPort ( 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()} 
)
protected

◆ DoDeclareSceneGraphPorts()

virtual void DoDeclareSceneGraphPorts ( )
protectedvirtual

◆ DoDeclareSystemResources()

virtual void DoDeclareSystemResources ( )
protectedpure virtual

◆ DoToPhysicalModelPointerVariant()

virtual PhysicalModelPointerVariant<T> DoToPhysicalModelPointerVariant ( ) const
protectedpure virtual

◆ is_cloneable_to_autodiff()

bool is_cloneable_to_autodiff ( ) const
override

Defaults to false.

Derived classes that support making a clone that uses AutoDiffXd as a scalar type must override this to return true.

◆ is_cloneable_to_double()

bool is_cloneable_to_double ( ) const
override

Defaults to false.

Derived classes that support making a clone that uses double as a scalar type must override this to return true.

◆ is_cloneable_to_symbolic()

bool is_cloneable_to_symbolic ( ) const
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.

◆ mutable_plant()

MultibodyPlant<T>* mutable_plant ( )
protected

◆ mutable_scene_graph()

geometry::SceneGraph<T>& mutable_scene_graph ( )
protected

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ plant()

const MultibodyPlant<T>* plant ( ) const

◆ ThrowIfSystemResourcesDeclared()

void ThrowIfSystemResourcesDeclared ( const char *  function_name) const
protected

◆ ThrowIfSystemResourcesNotDeclared()

void ThrowIfSystemResourcesNotDeclared ( const char *  function_name) const
protected

◆ ToPhysicalModelPointerVariant()

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.


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