A class containing information regarding contact and contact response between two geometries belonging to a pair of bodies with at least one of them being a deformable body.
This class provides:
The two geometries are denoted as A and B respectively with geometry A guaranteed to be belonging to a deformable body.
T | The scalar type, which must be one of the default scalars. |
#include <drake/multibody/plant/deformable_contact_info.h>
Public Member Functions | |
DeformableContactInfo (geometry::GeometryId id_A, geometry::GeometryId id_B, geometry::PolygonSurfaceMesh< T > contact_mesh_W, SpatialForce< T > F_Ac_W, std::vector< DeformableContactPointData< T >> contact_point_data) | |
Constructs a DeformableContactInfo. More... | |
geometry::GeometryId | id_A () const |
The geometry id of geometry A, guaranteed to belong to a deformable body in contact. More... | |
geometry::GeometryId | id_B () const |
The geometry id of geometry B. More... | |
const geometry::PolygonSurfaceMesh< T > & | contact_mesh () const |
Returns a reference to the contact mesh expressed in the world frame. More... | |
const SpatialForce< T > & | F_Ac_W () const |
Gets the spatial force applied on the deformable body associated with geometry A, at the centroid point C of the contact surface mesh, and expressed in the world frame W. More... | |
const std::vector< DeformableContactPointData< T > > & | contact_point_data () const |
Gets the contact point data, including tractions and slip velocities, at each contact point located at the centroid of each element of the contact mesh. More... | |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable | |
DeformableContactInfo (const DeformableContactInfo &)=default | |
DeformableContactInfo & | operator= (const DeformableContactInfo &)=default |
DeformableContactInfo (DeformableContactInfo &&)=default | |
DeformableContactInfo & | operator= (DeformableContactInfo &&)=default |
|
default |
|
default |
DeformableContactInfo | ( | geometry::GeometryId | id_A, |
geometry::GeometryId | id_B, | ||
geometry::PolygonSurfaceMesh< T > | contact_mesh_W, | ||
SpatialForce< T > | F_Ac_W, | ||
std::vector< DeformableContactPointData< T >> | contact_point_data | ||
) |
Constructs a DeformableContactInfo.
[in] | id_A | The geometry id of the deformable geometry A. |
[in] | id_B | The geometry id of geometry B. |
[in] | contact_mesh_W | The contact mesh between geometries A and B in the world frame. |
[in] | F_Ac_W | Spatial force acting on body A, at contact mesh centroid C, and expressed in the world frame. |
[in] | contact_point_data | The vector of per-contact-point data where the contact points are sampled at the centroid of each face of the contact mesh. This vector is ordered the same way as the faces of contact_mesh_W . |
const geometry::PolygonSurfaceMesh<T>& contact_mesh | ( | ) | const |
Returns a reference to the contact mesh expressed in the world frame.
const std::vector<DeformableContactPointData<T> >& contact_point_data | ( | ) | const |
Gets the contact point data, including tractions and slip velocities, at each contact point located at the centroid of each element of the contact mesh.
Ordered the same way as the faces of contact_mesh()`.
const SpatialForce<T>& F_Ac_W | ( | ) | const |
Gets the spatial force applied on the deformable body associated with geometry A, at the centroid point C of the contact surface mesh, and expressed in the world frame W.
geometry::GeometryId id_A | ( | ) | const |
The geometry id of geometry A, guaranteed to belong to a deformable body in contact.
geometry::GeometryId id_B | ( | ) | const |
The geometry id of geometry B.
|
default |
|
default |