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.
T | The 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 | |
ContactResults & | operator= (const ContactResults &) |
ContactResults & | operator= (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... | |
ContactResults | ( | ) |
ContactResults | ( | const ContactResults< T > & | ) |
|
default |
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.
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.
int num_deformable_contacts | ( | ) | const |
Returns the number of deformable contacts.
int num_hydroelastic_contacts | ( | ) | const |
Returns the number of hydroelastic contacts.
int num_point_pair_contacts | ( | ) | const |
Returns the number of point pair contacts.
ContactResults& operator= | ( | const ContactResults< T > & | ) |
|
default |
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.
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.
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.
selector | Boolean predicate that returns true to select which HydroelasticContactInfo. |