Drake
Drake C++ Documentation
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...
 
int num_deformable_contacts () const
 Returns the number of deformable 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...
 
const DeformableContactInfo< T > & deformable_contact_info (int i) const
 Retrieves the ith DeformableContactInfo instance. More...
 
const MultibodyPlant< T > * plant () const
 Returns the plant that produced these contact results. More...
 
ContactResults< T > SelectHydroelastic (std::function< bool(const HydroelasticContactInfo< T > &)> selector) const
 Returns ContactResults with only HydroelasticContactInfo instances satisfying the selection criterion and with all PointPairContactInfo instances. More...
 

Constructor & Destructor Documentation

◆ ContactResults() [1/3]

◆ ContactResults() [2/3]

ContactResults ( const ContactResults< T > &  )

◆ ContactResults() [3/3]

ContactResults ( ContactResults< T > &&  )
default

Member Function Documentation

◆ deformable_contact_info()

const DeformableContactInfo<T>& deformable_contact_info ( int  i) const

Retrieves the ith DeformableContactInfo instance.

The input index i must be in the range [0, num_deformable_contacts()) or this method throws.

◆ 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()) or this method throws.

◆ num_deformable_contacts()

int num_deformable_contacts ( ) const

Returns the number of deformable contacts.

◆ 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

◆ plant()

const MultibodyPlant<T>* plant ( ) const

Returns the plant that produced these contact results.

In most cases the result will be non-null, but default-constructed results might have nulls.

◆ 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()) or this method throws.

◆ SelectHydroelastic()

ContactResults<T> SelectHydroelastic ( std::function< bool(const HydroelasticContactInfo< T > &)>  selector) const

Returns ContactResults with only HydroelasticContactInfo instances satisfying the selection criterion and with all PointPairContactInfo instances.

Parameters
selectorBoolean predicate that returns true to select which HydroelasticContactInfo.
Note
It uses deep copy.

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