Drake
ContactResults< T > Class Template Reference

Detailed Description

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

A container class storing the contact results information for each contact pair for a given state of the simulation.

Note that copying this data structure is expensive when num_hydroelastic_contacts() > 0 because a deep copy is performed.

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

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

Public Member Functions

 ContactResults ()
 
 ContactResults (const ContactResults &)
 
 ContactResults (ContactResults &&)=default
 
ContactResultsoperator= (const ContactResults &)
 
ContactResultsoperator= (ContactResults &&)=default
 
int num_point_pair_contacts () const
 Returns the number of point pair contacts. More...
 
int num_hydroelastic_contacts () const
 Returns the number of hydroelastic contacts. More...
 
const PointPairContactInfo< T > & point_pair_contact_info (int i) const
 Retrieves the ith PointPairContactInfo instance. More...
 
const HydroelasticContactInfo< T > & hydroelastic_contact_info (int i) const
 Retrieves the ith HydroelasticContactInfo instance. More...
 

Constructor & Destructor Documentation

◆ ContactResults() [1/3]

◆ ContactResults() [2/3]

ContactResults ( const ContactResults< T > &  )

◆ ContactResults() [3/3]

ContactResults ( ContactResults< T > &&  )
default

Member Function Documentation

◆ hydroelastic_contact_info()

const HydroelasticContactInfo<T>& hydroelastic_contact_info ( int  i) const

Retrieves the ith HydroelasticContactInfo instance.

The input index i must be in the range [0, num_hydroelastic_contacts() - 1] or this method aborts.

◆ num_hydroelastic_contacts()

int num_hydroelastic_contacts ( ) const

Returns the number of hydroelastic contacts.

◆ num_point_pair_contacts()

int num_point_pair_contacts ( ) const

Returns the number of point pair contacts.

◆ operator=() [1/2]

ContactResults& operator= ( const ContactResults< T > &  )

◆ operator=() [2/2]

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

◆ point_pair_contact_info()

const PointPairContactInfo<T>& point_pair_contact_info ( int  i) const

Retrieves the ith PointPairContactInfo instance.

The input index i must be in the range [0, num_point_pair_contacts() - 1] or this method aborts.


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