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.

This class is immutable, so can be efficiently copied and moved.

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

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

Public Member Functions

 ContactResults ()=default
 Constructs an empty ContactResults. More...
 
 ContactResults (std::vector< PointPairContactInfo< T >> &&point_pair, std::vector< HydroelasticContactInfo< T >> &&hydroelastic={}, std::vector< DeformableContactInfo< T >> &&deformable={}, std::shared_ptr< const void > &&backing_store={})
 Constructs a ContactResults with the given contact infos. More...
 
 ~ContactResults ()
 
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 a selective copy of this object. 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/4]

ContactResults ( const ContactResults< T > &  )
default

◆ ContactResults() [2/4]

ContactResults ( ContactResults< T > &&  )
default

◆ ContactResults() [3/4]

ContactResults ( )
default

Constructs an empty ContactResults.

◆ ContactResults() [4/4]

ContactResults ( std::vector< PointPairContactInfo< T >> &&  point_pair,
std::vector< HydroelasticContactInfo< T >> &&  hydroelastic = {},
std::vector< DeformableContactInfo< T >> &&  deformable = {},
std::shared_ptr< const void > &&  backing_store = {} 
)
explicit

Constructs a ContactResults with the given contact infos.

(Advanced) The optional backing_store argument allows the caller to keep alive type-erased shared_ptr data that is referenced by the contact infos. This object will hold the backing_store until this object is destroyed. Because backing_store is type-erased (a pointer to void), it can keep alive any kind of necessary storage, e.g., a cache entry whose declaration is not available to this header file, and call sites can change how that storage ends up being organized without any changes to this file.

◆ ~ContactResults()

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

◆ operator=() [2/2]

ContactResults& operator= ( const 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 a selective copy of this object.

Only HydroelasticContactInfo instances satisfying the selection criterion are copied; all other contacts (point_pair and deformable) are unconditionally copied.

Parameters
selectorBoolean predicate that returns true to select which HydroelasticContactInfo.
Note
It uses deep copy (unless the operation is trivially identifiable as being vacuous, e.g., when num_hydroelastic_contacts() == 0).

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