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.

Template Parameters
TMust be one of drake's default scalar types.

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

Public Member Functions

 ContactResults ()
 
void Clear ()
 Clears the set of contact information for when the old data becomes invalid. More...
 
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...
 
void AddContactInfo (const PointPairContactInfo< T > &point_pair_info)
 Add a new contact pair result to this. More...
 
void AddContactInfo (HydroelasticContactInfo< T > &&hydroelastic_contact_info)
 Add a new hydroelastic contact to this. 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...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 ContactResults (const ContactResults &)=default
 
ContactResultsoperator= (const ContactResults &)=default
 
 ContactResults (ContactResults &&)=default
 
ContactResultsoperator= (ContactResults &&)=default
 

Constructor & Destructor Documentation

◆ ContactResults() [1/3]

ContactResults ( const ContactResults< T > &  )
default

◆ ContactResults() [2/3]

ContactResults ( ContactResults< T > &&  )
default

◆ ContactResults() [3/3]

ContactResults ( )
default

Member Function Documentation

◆ AddContactInfo() [1/2]

void AddContactInfo ( const PointPairContactInfo< T > &  point_pair_info)

Add a new contact pair result to this.

◆ AddContactInfo() [2/2]

void AddContactInfo ( HydroelasticContactInfo< T > &&  hydroelastic_contact_info)

Add a new hydroelastic contact to this.

◆ Clear()

void Clear ( )

Clears the set of contact information for when the old data becomes invalid.

◆ 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= ( ContactResults< T > &&  )
default

◆ operator=() [2/2]

ContactResults& operator= ( const 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 files: