Skip to content

Commit

Permalink
[geometry] Add surface mesh and bvh to SoftGeometry
Browse files Browse the repository at this point in the history
  • Loading branch information
joemasterjohn committed Oct 30, 2024
1 parent ffbb365 commit 402fde4
Show file tree
Hide file tree
Showing 6 changed files with 208 additions and 5 deletions.
2 changes: 2 additions & 0 deletions geometry/proximity/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -431,6 +431,8 @@ drake_cc_library(
":tessellation_strategy",
":triangle_surface_mesh",
":volume_mesh",
":volume_mesh_topology",
":volume_to_surface_mesh",
"//common:copyable_unique_ptr",
"//common:essential",
"//geometry:geometry_ids",
Expand Down
8 changes: 7 additions & 1 deletion geometry/proximity/hydroelastic_internal.cc
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,13 @@ SoftMesh& SoftMesh::operator=(const SoftMesh& s) {
// the new mesh. So, we use CloneAndSetMesh() instead.
pressure_ = s.pressure().CloneAndSetMesh(mesh_.get());
bvh_ = make_unique<Bvh<Obb, VolumeMesh<double>>>(s.bvh());

surface_mesh_ =
std::make_unique<TriangleSurfaceMesh<double>>(s.surface_mesh());
surface_element_to_volume_element_ = std::make_unique<std::vector<TetFace>>(
s.surface_element_to_volume_element());
bvh_surface_mesh_ = std::make_unique<Bvh<Obb, TriangleSurfaceMesh<double>>>(
s.bvh_surface_mesh());
mesh_topology_ = std::make_unique<VolumeMeshTopology>(s.mesh_topology());
return *this;
}

Expand Down
78 changes: 78 additions & 0 deletions geometry/proximity/hydroelastic_internal.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <unordered_set>
#include <utility>
#include <variant>
#include <vector>

#include "drake/common/copyable_unique_ptr.h"
#include "drake/common/drake_assert.h"
Expand All @@ -15,6 +16,8 @@
#include "drake/geometry/proximity/bvh.h"
#include "drake/geometry/proximity/triangle_surface_mesh.h"
#include "drake/geometry/proximity/volume_mesh_field.h"
#include "drake/geometry/proximity/volume_mesh_topology.h"
#include "drake/geometry/proximity/volume_to_surface_mesh.h"
#include "drake/geometry/proximity_properties.h"
#include "drake/geometry/shape_specification.h"

Expand All @@ -39,6 +42,14 @@ class SoftMesh {
pressure_(std::move(pressure)),
bvh_(std::make_unique<Bvh<Obb, VolumeMesh<double>>>(*mesh_)) {
DRAKE_ASSERT(mesh_.get() == &pressure_->mesh());
surface_element_to_volume_element_ =
std::make_unique<std::vector<TetFace>>();
surface_mesh_ = std::make_unique<TriangleSurfaceMesh<double>>(
ConvertVolumeToSurfaceMeshWithBoundaryVertices(
*mesh_, nullptr, surface_element_to_volume_element_.get()));
bvh_surface_mesh_ =
std::make_unique<Bvh<Obb, TriangleSurfaceMesh<double>>>(*surface_mesh_);
mesh_topology_ = std::make_unique<VolumeMeshTopology>(*mesh_);
}

SoftMesh(const SoftMesh& s) { *this = s; }
Expand All @@ -50,6 +61,10 @@ class SoftMesh {
DRAKE_DEMAND(mesh_ != nullptr);
return *mesh_;
}
const TriangleSurfaceMesh<double>& surface_mesh() const {
DRAKE_DEMAND(surface_mesh_ != nullptr);
return *surface_mesh_;
}
const VolumeMeshFieldLinear<double, double>& pressure() const {
DRAKE_DEMAND(pressure_ != nullptr);
return *pressure_;
Expand All @@ -58,11 +73,27 @@ class SoftMesh {
DRAKE_DEMAND(bvh_ != nullptr);
return *bvh_;
}
const Bvh<Obb, TriangleSurfaceMesh<double>>& bvh_surface_mesh() const {
DRAKE_DEMAND(bvh_surface_mesh_ != nullptr);
return *bvh_surface_mesh_;
}
const std::vector<TetFace>& surface_element_to_volume_element() const {
return *surface_element_to_volume_element_;
}
const VolumeMeshTopology& mesh_topology() const {
DRAKE_DEMAND(mesh_topology_ != nullptr);
return *mesh_topology_;
}

private:
std::unique_ptr<VolumeMesh<double>> mesh_;
std::unique_ptr<VolumeMeshFieldLinear<double, double>> pressure_;
std::unique_ptr<Bvh<Obb, VolumeMesh<double>>> bvh_;

std::unique_ptr<TriangleSurfaceMesh<double>> surface_mesh_;
std::unique_ptr<Bvh<Obb, TriangleSurfaceMesh<double>>> bvh_surface_mesh_;
std::unique_ptr<VolumeMeshTopology> mesh_topology_;
std::unique_ptr<std::vector<TetFace>> surface_element_to_volume_element_;
};

/* Defines a soft half space. The half space is defined such that the half
Expand Down Expand Up @@ -185,6 +216,53 @@ class SoftGeometry {
return std::get<SoftHalfSpace>(geometry_).margin;
}

/* Returns a reference to the surface mesh of the underlying volume mesh --
calling this will throw if is_half_space() returns `true`. */
const TriangleSurfaceMesh<double>& surface_mesh() const {
if (is_half_space()) {
throw std::runtime_error(
"SoftGeometry::surface_mesh() cannot be invoked for soft half space");
}
return std::get<SoftMesh>(geometry_).surface_mesh();
}

/* Returns a reference to the bounding volume hierarchy for the surface mesh
-- calling this will throw if is_half_space() returns `true`. */
const Bvh<Obb, TriangleSurfaceMesh<double>>& bvh_surface_mesh() const {
if (is_half_space()) {
throw std::runtime_error(
"SoftGeometry::bvh_surface_mesh() cannot be invoked for soft half "
"space");
}
return std::get<SoftMesh>(geometry_).bvh_surface_mesh();
}

/* Returns a reference to the surface element to volume element mapping. The
returned vector has the same size as this->surface_mesh().num_elements(). The
`TetFace` at index i gives the index of the volume element in this->mesh()
that the surface mesh element belongs to. -- calling this will throw if
is_half_space() returns `true`. */
const std::vector<TetFace>& surface_element_to_volume_element() const {
if (is_half_space()) {
throw std::runtime_error(
"SoftGeometry::surface_element_to_volume_element() cannot be invoked "
"for soft "
"half space");
}
return std::get<SoftMesh>(geometry_).surface_element_to_volume_element();
}

/* Returns a reference to the mesh topology for this->mesh() -- calling this
will throw if is_half_space() returns `true`. */
const VolumeMeshTopology& mesh_topology() const {
if (is_half_space()) {
throw std::runtime_error(
"SoftGeometry::mesh_topology() cannot be invoked for soft half "
"space");
}
return std::get<SoftMesh>(geometry_).mesh_topology();
}

//@}

private:
Expand Down
Loading

0 comments on commit 402fde4

Please sign in to comment.