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

Detailed Description

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

A class containing information regarding contact and contact response between two geometries attached to a pair of bodies.

This class provides the output from the Hydroelastic contact model and includes:

  • The shared contact surface between the two geometries, which includes the virtual pressures acting at every point on the contact surface.
  • The tractions acting at the quadrature points on the contact surface.
  • The slip speeds at the quadrature points on the contact surface.
  • The spatial force from the integrated tractions that is applied at the centroid of the contact surface.

The two geometries, denoted M and N (and obtainable via contact_surface().id_M() and contact_surface().id_N()) are attached to bodies A and B, respectively.

Template Parameters
TThe scalar type, which must be one of the default scalars.

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

Public Member Functions

const geometry::ContactSurface< T > & contact_surface () const
 Returns a reference to the ContactSurface data structure. More...
 
const std::vector< HydroelasticQuadraturePointData< T > > & quadrature_point_data () const
 Gets the intermediate data, including tractions, computed by the quadrature process. More...
 
const SpatialForce< T > & F_Ac_W () const
 Gets the spatial force applied on body A, at the centroid point C of the surface mesh M, and expressed in the world frame W. More...
 
Construction

The constructors below adhere to a number of invariants.

The geometry::ContactSurface defines contact between two geometries M and N (via contact_surface().id_M() and contact_surface().id_N(), respectively). HydroelasticContactInfo further associates geometries M and N with the bodies to which they are rigidly fixed, A and B, respectively. It is the responsibility of the caller of these constructors to ensure that the parameters satisfy the documented invariants, see below. Similarly, the spatial force F_Ac_W must be provided as indicated by the monogram notation in use, that is, it is the spatial force on body A, at the contact surface's centroid C, and expressed in the world frame. Quadrature points data must be provided in accordance to the conventions and monogram notation documented in HydroelasticQuadraturePointData.

 HydroelasticContactInfo (const geometry::ContactSurface< T > *contact_surface, const SpatialForce< T > &F_Ac_W, std::vector< HydroelasticQuadraturePointData< T >> &&quadrature_point_data)
 
 HydroelasticContactInfo (std::unique_ptr< geometry::ContactSurface< T >> contact_surface, const SpatialForce< T > &F_Ac_W, std::vector< HydroelasticQuadraturePointData< T >> &&quadrature_point_data)
 This constructor takes ownership of contact_surface via a std::unique_ptr, instead of aliasing a pre-existing contact surface. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible,

MoveAssignable.

 HydroelasticContactInfo (const HydroelasticContactInfo &info)
 Clones this data structure, making deep copies of all underlying data. More...
 
HydroelasticContactInfooperator= (const HydroelasticContactInfo &info)
 Clones this object in the same manner as the copy constructor. More...
 
 HydroelasticContactInfo (HydroelasticContactInfo &&)=default
 
HydroelasticContactInfooperator= (HydroelasticContactInfo &&)=default
 

Constructor & Destructor Documentation

◆ HydroelasticContactInfo() [1/4]

HydroelasticContactInfo ( const geometry::ContactSurface< T > *  contact_surface,
const SpatialForce< T > &  F_Ac_W,
std::vector< HydroelasticQuadraturePointData< T >> &&  quadrature_point_data 
)

Constructs this structure using the given contact surface, traction field, and slip field. This constructor does not own the ContactSurface; it points to a ContactSurface that another owns, see contact_surface().

Parameters
[in]contact_surfaceContact surface between two geometries M and N, see geometry::ContactSurface::id_M() and geometry::ContactSurface::id_N().
[in]F_Ac_WSpatial force applied on body A, at contact surface centroid C, and expressed in the world frame W. The position p_WC of C in the world frame W can be obtained with ContactSurface::centroid().
[in]quadrature_point_dataHydroelastic field data at each quadrature point. Data must be provided in accordance to the convention that geometry M and N are attached to bodies A and B, respectively. Refer to HydroelasticQuadraturePointData for further details.

◆ HydroelasticContactInfo() [2/4]

HydroelasticContactInfo ( std::unique_ptr< geometry::ContactSurface< T >>  contact_surface,
const SpatialForce< T > &  F_Ac_W,
std::vector< HydroelasticQuadraturePointData< T >> &&  quadrature_point_data 
)

This constructor takes ownership of contact_surface via a std::unique_ptr, instead of aliasing a pre-existing contact surface.

In all other respects, it is identical to the other overload that takes contact_surface by raw pointer.

◆ HydroelasticContactInfo() [3/4]

Clones this data structure, making deep copies of all underlying data.

Note
The new object will contain a cloned ContactSurface even if the original was constructed using a raw pointer referencing an existing ContactSurface.

◆ HydroelasticContactInfo() [4/4]

Member Function Documentation

◆ contact_surface()

const geometry::ContactSurface<T>& contact_surface ( ) const

Returns a reference to the ContactSurface data structure.

Note that the mesh and gradient vector fields are expressed in the world frame.

◆ F_Ac_W()

const SpatialForce<T>& F_Ac_W ( ) const

Gets the spatial force applied on body A, at the centroid point C of the surface mesh M, and expressed in the world frame W.

The position p_WC of the centroid point C in the world frame W can be obtained with contact_surface().centroid().

◆ operator=() [1/2]

HydroelasticContactInfo& operator= ( const HydroelasticContactInfo< T > &  info)

Clones this object in the same manner as the copy constructor.

See also
HydroelasticContactInfo(const HydroelasticContactInfo&)

◆ operator=() [2/2]

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

◆ quadrature_point_data()

const std::vector<HydroelasticQuadraturePointData<T> >& quadrature_point_data ( ) const

Gets the intermediate data, including tractions, computed by the quadrature process.


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