Skip to content

Commit

Permalink
Move all hydroelastic geometry computations into scene graph (RobotLo…
Browse files Browse the repository at this point in the history
…comotion#12557)

1. Simplify HydroelasticEngine so that it defers to SG for contact
   surface calculation.
   - Remove HydroelasticEngine expression specialization.
2. Modify MBP so that it no longer relies on HydroelasticEngine to do
   geometric work.
3. Modify examples
   - rolling sphere demo now rolls the sphere on a *box* (instead of a
     currently unsupported plane).
4. Miscellaneous clean up
   - MBP_test wasn't testing the MBP::RegisterCollisionGeometry variant
     that took proximity properties.
   - mesh_intersection_test.cc tests for surface normal directions.
   - mesh_intersection no longer returns "empty" contact surfaces.
   - hydroelastic_callback now handles the case where there is no contact.
  • Loading branch information
SeanCurtis-TRI authored Jan 17, 2020
1 parent 06a510a commit 753bc66
Show file tree
Hide file tree
Showing 17 changed files with 351 additions and 936 deletions.
54 changes: 36 additions & 18 deletions examples/multibody/rolling_sphere/make_rolling_sphere_plant.cc
Original file line number Diff line number Diff line change
@@ -1,21 +1,30 @@
#include "drake/examples/multibody/rolling_sphere/make_rolling_sphere_plant.h"

#include <utility>

#include "drake/geometry/proximity_properties.h"
#include "drake/multibody/tree/uniform_gravity_field_element.h"

namespace drake {
namespace examples {
namespace multibody {
namespace bouncing_ball {

using drake::geometry::AddRigidHydroelasticProperties;
using drake::geometry::AddSoftHydroelasticProperties;
using drake::geometry::internal::kElastic;
using drake::geometry::internal::kFriction;
using drake::geometry::internal::kHcDissipation;
using drake::geometry::internal::kMaterialGroup;
using drake::geometry::ProximityProperties;
using drake::geometry::SceneGraph;
using drake::geometry::Sphere;
using drake::multibody::CoulombFriction;
using drake::multibody::MultibodyPlant;
using drake::multibody::RigidBody;
using drake::multibody::SpatialInertia;
using drake::multibody::UnitInertia;
using math::RigidTransformd;
using geometry::Sphere;
using geometry::HalfSpace;
using geometry::SceneGraph;
using drake::math::RigidTransformd;

std::unique_ptr<drake::multibody::MultibodyPlant<double>> MakeBouncingBallPlant(
double radius, double mass, double elastic_modulus, double dissipation,
Expand All @@ -31,27 +40,36 @@ std::unique_ptr<drake::multibody::MultibodyPlant<double>> MakeBouncingBallPlant(
if (scene_graph != nullptr) {
plant->RegisterAsSourceForSceneGraph(scene_graph);

Vector3<double> normal_W(0, 0, 1);
Vector3<double> point_W(0, 0, 0);

const RigidTransformd X_WG(HalfSpace::MakePose(normal_W, point_W));
// A half-space for the ground geometry.
plant->RegisterCollisionGeometry(plant->world_body(), X_WG, HalfSpace(),
"collision", surface_friction);
// TODO(SeanCurtis-TRI): Once SceneGraph supports hydroelastic contact
// between rigid half space and soft sphere, replace this box with the
// equivalent half space.
const double size = 5;
RigidTransformd X_WG{Vector3<double>(0, 0, -size / 2)};
ProximityProperties box_props;
AddRigidHydroelasticProperties(size, &box_props);
box_props.AddProperty(kMaterialGroup, kFriction, surface_friction);
plant->RegisterCollisionGeometry(plant->world_body(), X_WG,
geometry::Box(size, size, size),
"collision", std::move(box_props));

// Add visual for the ground.
plant->RegisterVisualGeometry(plant->world_body(), X_WG, HalfSpace(),
"visual");
plant->RegisterVisualGeometry(plant->world_body(), X_WG,
geometry::Box(size, size, size), "visual");

// Add sphere geometry for the ball.
// Pose of sphere geometry S in body frame B.
const RigidTransformd X_BS = RigidTransformd::Identity();
geometry::GeometryId sphere_geometry = plant->RegisterCollisionGeometry(
ball, X_BS, Sphere(radius), "collision", surface_friction);

// Set material properties for hydroelastics.
plant->set_elastic_modulus(sphere_geometry, elastic_modulus);
plant->set_hunt_crossley_dissipation(sphere_geometry, dissipation);
ProximityProperties ball_props;
// TODO(SeanCurtis-TRI): Simplify this with addition of
// geometry::AddContactMaterial().
ball_props.AddProperty(kMaterialGroup, kElastic, elastic_modulus);
ball_props.AddProperty(kMaterialGroup,
kHcDissipation, dissipation);
ball_props.AddProperty(kMaterialGroup, kFriction, surface_friction);
AddSoftHydroelasticProperties(radius, &ball_props);
plant->RegisterCollisionGeometry(ball, X_BS, Sphere(radius), "collision",
std::move(ball_props));

// Add visual for the ball.
const Vector4<double> orange(1.0, 0.55, 0.0, 1.0);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ namespace bouncing_ball {
/// The mass of the ball.
/// @param[in] elastic_modulus
/// The modulus of elasticity for the ball. Only used when modeled with the
/// hydroelastic model. See MultibodyPlant::set_elastic_modulus().
/// hydroelastic model.
/// @param[in] dissipation
/// The Hunt & Crossley dissipation constant for the ball. Only used with the
/// hydroelastic model. See MultibodyPlant::set_hunt_crossley_dissipation().
Expand Down
39 changes: 24 additions & 15 deletions geometry/proximity/mesh_intersection.h
Original file line number Diff line number Diff line change
Expand Up @@ -475,7 +475,9 @@ void AddPolygonToMeshData(
/** Samples a field on a two-dimensional manifold. The field is defined over
a volume mesh and the manifold is the intersection of the volume mesh and a
surface mesh. The resulting manifold's topology is a function of both the
volume and surface mesh topologies and has normals drawn from the surface mesh.
volume and surface mesh topologies. The winding of the resulting manifold's
faces will be such that its face normals will point in the same direction as
the input surface mesh's corresponding faces.
Computes the intersecting surface `surface_MN` between a soft geometry M
and a rigid geometry N, and sets the pressure field and the normal vector
field on `surface_MN`. This does not use any broadphase culling but compares
Expand All @@ -492,10 +494,12 @@ void AddPolygonToMeshData(
The pose of frame N in frame M.
@param[out] surface_MN_M
The intersecting surface between the volume mesh M and the surface N.
Vertex positions are measured and expressed in M's frame.
Vertex positions are measured and expressed in M's frame. If no
intersection exists, this will not change.
@param[out] e_MN
The sampled field values on the intersecting surface (samples to support
a linear mesh field -- i.e., one per vertex).
a linear mesh field -- i.e., one per vertex). If no intersection exists,
this will not change.
@note
The output surface mesh may have duplicate vertices.
*/
Expand Down Expand Up @@ -542,12 +546,12 @@ void SampleVolumeFieldOnSurface(
}

DRAKE_DEMAND(surface_vertices_M.size() == surface_e.size());
if (surface_vertices_M.size() > 0) {
*surface_MN_M = std::make_unique<SurfaceMesh<T>>(
std::move(surface_faces), std::move(surface_vertices_M));
*e_MN = std::make_unique<SurfaceMeshFieldLinear<T, T>>(
"e", std::move(surface_e), surface_MN_M->get());
}
if (surface_faces.empty()) return;

*surface_MN_M = std::make_unique<SurfaceMesh<T>>(
std::move(surface_faces), std::move(surface_vertices_M));
*e_MN = std::make_unique<SurfaceMeshFieldLinear<T, T>>(
"e", std::move(surface_e), surface_MN_M->get());
}

/** A variant of SampleVolumeFieldOnSurface but with broad-phase culling to
Expand Down Expand Up @@ -598,12 +602,12 @@ void SampleVolumeFieldOnSurface(
bvh_M.Collide(bvh_N, X_MN, callback);

DRAKE_DEMAND(surface_vertices_M.size() == surface_e.size());
if (surface_vertices_M.size() > 0) {
*surface_MN_M = std::make_unique<SurfaceMesh<T>>(
std::move(surface_faces), std::move(surface_vertices_M));
*e_MN = std::make_unique<SurfaceMeshFieldLinear<T, T>>(
"e", std::move(surface_e), surface_MN_M->get());
}
if (surface_faces.empty()) return;

*surface_MN_M = std::make_unique<SurfaceMesh<T>>(
std::move(surface_faces), std::move(surface_vertices_M));
*e_MN = std::make_unique<SurfaceMeshFieldLinear<T, T>>(
"e", std::move(surface_e), surface_MN_M->get());
}

/** Computes the contact surface between a soft geometry S and a rigid
Expand Down Expand Up @@ -643,6 +647,7 @@ void SampleVolumeFieldOnSurface(
rigid R | ooo |
| |
+----------------------+
If there is no contact, nullptr is returned.
*/
template <typename T>
std::unique_ptr<ContactSurface<T>>
Expand Down Expand Up @@ -720,6 +725,10 @@ ComputeContactSurfaceFromSoftVolumeRigidSurface(
// Transform the mesh from the S frame to the world frame.
surface_SR->TransformVertices(X_WS);

// The contact surface is documented as having the normals pointing *out* of
// the second surface and into the first. This mesh intersection creates a
// surface mesh with normals pointing out of the rigid surface, so we make
// sure the ids are ordered so that the rigid is the second id.
return std::make_unique<ContactSurface<T>>(id_S, id_R, std::move(surface_SR),
std::move(e_SR));
}
Expand Down
10 changes: 10 additions & 0 deletions geometry/proximity/test/mesh_intersection_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -710,6 +710,16 @@ GTEST_TEST(MeshIntersectionTest, SampleVolumeFieldOnSurface) {
const double e = e_field->Evaluate(face0, centroid);
const double expect_e = 0.5;
EXPECT_NEAR(expect_e, e, kEps);

// Test the face normals of resulting mesh. Because the 'trivial' surface mesh
// is a single triangle, all triangles in the resulting mesh should have the
// same normal.
using FIndex = SurfaceMesh<double>::ElementIndex;
ASSERT_TRUE(
CompareMatrices(rigid_N->face_normal(FIndex{0}), Vector3d::UnitZ()));
for (FIndex f(0); f < surface->num_faces(); ++f) {
EXPECT_TRUE(CompareMatrices(surface->face_normal(f), Vector3d::UnitZ()));
}
}

// Generates a volume mesh of an octahedron comprising of eight tetrahedral
Expand Down
8 changes: 5 additions & 3 deletions geometry/query_results/contact_surface.h
Original file line number Diff line number Diff line change
Expand Up @@ -158,9 +158,11 @@ class ContactSurface {
@param mesh_W The surface mesh of the contact surface 𝕊ₘₙ between M
and N. The mesh vertices are defined in the world frame.
@param e_MN Represents the scalar field eₘₙ on the surface mesh.
@pre The face normals in `mesh_W` point *out of* geometry M and *into* N.
@note If the id_M is greater than the id_N, we will swap M and N (making any
necessary changes to keep the surface consistent with that labeling).
@pre The face normals in `mesh_W` point *out of* geometry N and *into* M.
@note If `id_M > id_N`, the labels will be swapped and the normals of the
mesh reversed (to maintain the documented invariants). Comparing the
input parameters with the members of the resulting %ContactSurface will
reveal if such a swap has occurred.
*/
ContactSurface(
GeometryId id_M, GeometryId id_N, std::unique_ptr<SurfaceMesh<T>> mesh_W,
Expand Down
15 changes: 2 additions & 13 deletions multibody/hydroelastics/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -45,12 +45,8 @@ drake_cc_library(
"hydroelastic_engine.h",
],
deps = [
":contact_surface_from_level_set",
":hydroelastic_field",
":hydroelastic_field_sphere",
":level_set_field",
"//common:essential",
"//geometry:scene_graph",
"//geometry:scene_graph_inspector",
],
)

Expand Down Expand Up @@ -96,17 +92,10 @@ drake_cc_googletest(

drake_cc_googletest(
name = "hydroelastic_engine_test",
data = [
"test/sphere_vs_plane.sdf",
],
deps = [
":hydroelastic_engine",
"//common:find_resource",
"//common/test_utilities:eigen_matrix_compare",
"//common/test_utilities:expect_throws_message",
"//math:geometric_transform",
"//multibody/parsing",
"//multibody/plant",
"//geometry:scene_graph",
],
)

Expand Down
4 changes: 4 additions & 0 deletions multibody/hydroelastics/contact_surface_from_level_set.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,10 @@ namespace multibody {
namespace hydroelastics {
#ifndef DRAKE_DOXYGEN_CXX
namespace internal {

// TODO(SeanCurtis-TRI): The contents of this file are no longer used. Refactor
// this into geometry as appropriate.

// This table essentially assigns an index to each edge in the tetrahedron. Each
// edge is represented by its pair of vertex indexes.
using Edge = std::pair<int, int>;
Expand Down
Loading

0 comments on commit 753bc66

Please sign in to comment.