A class containing information regarding contact response between two bodies including:
| T | The 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 | |
| PointPairContactInfo & | operator= (const PointPairContactInfo &)=default |
| PointPairContactInfo (PointPairContactInfo &&)=default | |
| PointPairContactInfo & | operator= (PointPairContactInfo &&)=default |
|
default |
|
default |
| 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.
| bodyA_index | Index that references body A in this contact pair. |
| bodyB_index | Index that references body B in this contact pair. |
| f_Bc_W | Force on body B applied at contact point C, expressed in the world frame W. |
| p_WC | Position of the contact point C in the world frame W. |
| separation_speed | Separation 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_speed | Slip speed, that is, the magnitude of the relative tangential velocity at the contact point in meters per second. A non-negative value always. |
| point_pair | Additional 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. |
| BodyIndex bodyA_index | ( | ) | const |
Returns the index of body A in the contact pair.
| BodyIndex bodyB_index | ( | ) | const |
Returns the index of body B in the contact pair.
| 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.
| const Vector3<T>& contact_point | ( | ) | const |
Returns the position p_WC of the contact point C in the world frame W.
|
default |
|
default |
| 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().
| 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.
| const T& slip_speed | ( | ) | const |
Returns the slip speed between body A and B at contact point C.