Drake
ContactResults< T > Class Template Reference

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

#include <drake/multibody/multibody_tree/multibody_plant/contact_results.h>

Public Member Functions

 ContactResults ()=default
 
void Clear ()
 Clears the set of contact information for when the old data becomes invalid. More...
 
int num_contacts () const
 Returns the number of unique collision element pairs in contact. More...
 
void AddContactInfo (const PointPairContactInfo< T > &point_pair_info)
 Add a new contact pair result to the set of contact pairs stored by this class. More...
 
const PointPairContactInfo< T > & contact_info (int i) const
 Retrieves the ith PointPairContactInfo instance. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 ContactResults (const ContactResults &)=default
 
ContactResultsoperator= (const ContactResults &)=default
 
 ContactResults (ContactResults &&)=default
 
ContactResultsoperator= (ContactResults &&)=default
 

Detailed Description

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

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

Template Parameters
TThe scalar type. It must be a valid Eigen scalar.

Instantiated templates for the following ScalarTypes are provided:

  • double
  • AutoDiffXd

Constructor & Destructor Documentation

ContactResults ( const ContactResults< T > &  )
default
ContactResults ( ContactResults< T > &&  )
default
ContactResults ( )
default

Member Function Documentation

void AddContactInfo ( const PointPairContactInfo< T > &  point_pair_info)

Add a new contact pair result to the set of contact pairs stored by this class.

Here is the caller graph for this function:

void Clear ( )

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

Here is the caller graph for this function:

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

Retrieves the ith PointPairContactInfo instance.

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

int num_contacts ( ) const

Returns the number of unique collision element pairs in contact.

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

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