Drake
Drake C++ Documentation
DeformableContactInfo< T > Class Template Reference

Detailed Description

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

A class containing information regarding contact and contact response between two geometries belonging to a pair of bodies with at least one of them being a deformable body.

This class provides:

  • The shared contact mesh between the two geometries.
  • The tractions acting at the contact points on the contact mesh.
  • The slip speeds at the contact points on the contact mesh.
  • The spatial force from the integrated tractions that is applied at the centroid of the contact surface.

The two geometries are denoted as A and B respectively with geometry A guaranteed to be belonging to a deformable body.

Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.
Template Parameters
TThe scalar type, which must be one of the default scalars.

#include <drake/multibody/plant/deformable_contact_info.h>

Public Member Functions

 DeformableContactInfo (geometry::GeometryId id_A, geometry::GeometryId id_B, geometry::PolygonSurfaceMesh< T > contact_mesh_W, SpatialForce< T > F_Ac_W, std::vector< DeformableContactPointData< T >> contact_point_data)
 Constructs a DeformableContactInfo. More...
 
geometry::GeometryId id_A () const
 The geometry id of geometry A, guaranteed to belong to a deformable body in contact. More...
 
geometry::GeometryId id_B () const
 The geometry id of geometry B. More...
 
const geometry::PolygonSurfaceMesh< T > & contact_mesh () const
 Returns a reference to the contact mesh expressed in the world frame. More...
 
const SpatialForce< T > & F_Ac_W () const
 Gets the spatial force applied on the deformable body associated with geometry A, at the centroid point C of the contact surface mesh, and expressed in the world frame W. More...
 
const std::vector< DeformableContactPointData< T > > & contact_point_data () const
 Gets the contact point data, including tractions and slip velocities, at each contact point located at the centroid of each element of the contact mesh. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 DeformableContactInfo (const DeformableContactInfo &)=default
 
DeformableContactInfooperator= (const DeformableContactInfo &)=default
 
 DeformableContactInfo (DeformableContactInfo &&)=default
 
DeformableContactInfooperator= (DeformableContactInfo &&)=default
 

Constructor & Destructor Documentation

◆ DeformableContactInfo() [1/3]

DeformableContactInfo ( const DeformableContactInfo< T > &  )
default

◆ DeformableContactInfo() [2/3]

◆ DeformableContactInfo() [3/3]

DeformableContactInfo ( geometry::GeometryId  id_A,
geometry::GeometryId  id_B,
geometry::PolygonSurfaceMesh< T >  contact_mesh_W,
SpatialForce< T >  F_Ac_W,
std::vector< DeformableContactPointData< T >>  contact_point_data 
)

Constructs a DeformableContactInfo.

Parameters
[in]id_AThe geometry id of the deformable geometry A.
[in]id_BThe geometry id of geometry B.
[in]contact_mesh_WThe contact mesh between geometries A and B in the world frame.
[in]F_Ac_WSpatial force acting on body A, at contact mesh centroid C, and expressed in the world frame.
[in]contact_point_dataThe vector of per-contact-point data where the contact points are sampled at the centroid of each face of the contact mesh. This vector is ordered the same way as the faces of contact_mesh_W.
Precondition
id_A corresponds to a deformable geometry.

Member Function Documentation

◆ contact_mesh()

const geometry::PolygonSurfaceMesh<T>& contact_mesh ( ) const

Returns a reference to the contact mesh expressed in the world frame.

◆ contact_point_data()

const std::vector<DeformableContactPointData<T> >& contact_point_data ( ) const

Gets the contact point data, including tractions and slip velocities, at each contact point located at the centroid of each element of the contact mesh.

Ordered the same way as the faces of contact_mesh()`.

◆ F_Ac_W()

const SpatialForce<T>& F_Ac_W ( ) const

Gets the spatial force applied on the deformable body associated with geometry A, at the centroid point C of the contact surface mesh, and expressed in the world frame W.

◆ id_A()

geometry::GeometryId id_A ( ) const

The geometry id of geometry A, guaranteed to belong to a deformable body in contact.

◆ id_B()

geometry::GeometryId id_B ( ) const

The geometry id of geometry B.

◆ operator=() [1/2]

DeformableContactInfo& operator= ( const DeformableContactInfo< T > &  )
default

◆ operator=() [2/2]

DeformableContactInfo& operator= ( DeformableContactInfo< T > &&  )
default

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