Drake
Drake C++ Documentation
PointPairContactInfo< T > Class Template Reference

Detailed Description

template<typename T>
class drake::multibody::PointPairContactInfo< T >

A class containing information regarding contact response between two bodies including:

  • The pair of bodies that are contacting, referenced by their BodyIndex.
  • A resultant contact force.
  • A contact point.
  • Separation speed.
  • Slip speed.
Template Parameters
TThe scalar type, which must be one of the default scalars.

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

Public Member Functions

 PointPairContactInfo (BodyIndex bodyA_index, BodyIndex bodyB_index, const Vector3< T > &f_Bc_W, const Vector3< T > &p_WC, const T &separation_speed, const T &slip_speed, const drake::geometry::PenetrationAsPointPair< T > &point_pair)
 Constructs the contact information for a given pair of two colliding bodies. More...
 
BodyIndex bodyA_index () const
 Returns the index of body A in the contact pair. More...
 
BodyIndex bodyB_index () const
 Returns the index of body B in the contact pair. More...
 
const Vector3< T > & contact_force () const
 Returns the contact force f_Bc_W on B at contact point C expressed in the world frame W. More...
 
const Vector3< T > & contact_point () const
 Returns the position p_WC of the contact point C in the world frame W. More...
 
const T & slip_speed () const
 Returns the slip speed between body A and B at contact point C. More...
 
const T & separation_speed () const
 Returns the separation speed between body A and B along the normal direction (see PenetrationAsPointPair::nhat_BA_W) at the contact point. More...
 
const drake::geometry::PenetrationAsPointPair< T > & point_pair () const
 Returns additional information for the geometric contact query for this pair as a PenetrationAsPointPair. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 PointPairContactInfo (const PointPairContactInfo &)=default
 
PointPairContactInfooperator= (const PointPairContactInfo &)=default
 
 PointPairContactInfo (PointPairContactInfo &&)=default
 
PointPairContactInfooperator= (PointPairContactInfo &&)=default
 

Constructor & Destructor Documentation

◆ PointPairContactInfo() [1/3]

PointPairContactInfo ( const PointPairContactInfo< T > &  )
default

◆ PointPairContactInfo() [2/3]

◆ PointPairContactInfo() [3/3]

PointPairContactInfo ( BodyIndex  bodyA_index,
BodyIndex  bodyB_index,
const Vector3< T > &  f_Bc_W,
const Vector3< T > &  p_WC,
const T &  separation_speed,
const T &  slip_speed,
const drake::geometry::PenetrationAsPointPair< T > &  point_pair 
)

Constructs the contact information for a given pair of two colliding bodies.

Parameters
bodyA_indexIndex that references body A in this contact pair.
bodyB_indexIndex that references body B in this contact pair.
f_Bc_WForce on body B applied at contact point C, expressed in the world frame W.
p_WCPosition of the contact point C in the world frame W.
separation_speedSeparation speed along the normal direction between body A and body B, in meters per second. A positive value indicates bodies are moving apart. A negative value indicates bodies are moving towards each other.
slip_speedSlip speed, that is, the magnitude of the relative tangential velocity at the contact point in meters per second. A non-negative value always.
point_pairAdditional point pair information for this contact info. Refer to the documentation for PenetrationAsPointPair for further details. It is expected that the body indexed by bodyA_index is the same body that contains the geometry indexed by point_pair.id_A. Likewise for the body indexed by bodyB_index and the body contining geometry with id point_pair.id_B.
Precondition
The two body indexes must reference bodies from the same MultibodyPlant. Contact values should likewise be generated by the same MultibodyPlant.

Member Function Documentation

◆ bodyA_index()

BodyIndex bodyA_index ( ) const

Returns the index of body A in the contact pair.

◆ bodyB_index()

BodyIndex bodyB_index ( ) const

Returns the index of body B in the contact pair.

◆ contact_force()

const Vector3<T>& contact_force ( ) const

Returns the contact force f_Bc_W on B at contact point C expressed in the world frame W.

◆ contact_point()

const Vector3<T>& contact_point ( ) const

Returns the position p_WC of the contact point C in the world frame W.

◆ operator=() [1/2]

PointPairContactInfo& operator= ( PointPairContactInfo< T > &&  )
default

◆ operator=() [2/2]

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

◆ point_pair()

const drake::geometry::PenetrationAsPointPair<T>& point_pair ( ) const

Returns additional information for the geometric contact query for this pair as a PenetrationAsPointPair.

The body containing point_pair().id_A is the same body indexed by bodyA_index(). Likewise, the body containing point_pair().id_B is the same body indexed by bodyB_index().

◆ separation_speed()

const T& separation_speed ( ) const

Returns the separation speed between body A and B along the normal direction (see PenetrationAsPointPair::nhat_BA_W) at the contact point.

It is defined positive for bodies moving apart in the normal direction.

◆ slip_speed()

const T& slip_speed ( ) const

Returns the slip speed between body A and B at contact point C.


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