Skip to content

Commit 2702a84

Browse files
[geometry] Add precomputed values to VolumeMesh and MeshFieldLinear (#22097)
1 parent 7968e51 commit 2702a84

File tree

7 files changed

+423
-49
lines changed

7 files changed

+423
-49
lines changed

bindings/pydrake/geometry/geometry_py_meshes.cc

+6-1
Original file line numberDiff line numberDiff line change
@@ -122,6 +122,10 @@ void DoScalarDependentDefinitions(py::module m, T) {
122122
cls_doc.tetrahedra.doc)
123123
.def("num_elements", &Class::num_elements, cls_doc.num_elements.doc)
124124
.def("num_vertices", &Class::num_vertices, cls_doc.num_vertices.doc)
125+
.def("inward_normal", &Class::inward_normal, py::arg("e"), py::arg("f"),
126+
cls_doc.inward_normal.doc)
127+
.def("edge_vector", &Class::edge_vector, py::arg("e"), py::arg("a"),
128+
py::arg("b"), cls_doc.edge_vector.doc)
125129
.def("CalcTetrahedronVolume", &Class::CalcTetrahedronVolume,
126130
py::arg("e"), cls_doc.CalcTetrahedronVolume.doc)
127131
.def("CalcVolume", &Class::CalcVolume, cls_doc.CalcVolume.doc)
@@ -177,7 +181,8 @@ void DoScalarIndependentDefinitions(py::module m) {
177181
.def(py::init<int, int, int, int>(), py::arg("v0"), py::arg("v1"),
178182
py::arg("v2"), py::arg("v3"), cls_doc.ctor.doc_4args)
179183
// TODO(SeanCurtis-TRI): Bind constructor that takes array of ints.
180-
.def("vertex", &Class::vertex, py::arg("i"), cls_doc.vertex.doc);
184+
.def("vertex", &Class::vertex, py::arg("i"), cls_doc.vertex.doc)
185+
.def("num_vertices", &Class::num_vertices, cls_doc.num_vertices.doc);
181186
DefCopyAndDeepCopy(&cls);
182187
}
183188
}

bindings/pydrake/geometry/test/meshes_test.py

+13
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
import pydrake.geometry as mut
22
import pydrake.geometry._testing as mut_testing
3+
from pydrake.common.test_utilities import numpy_compare
34

45
import copy
56
import unittest
@@ -141,6 +142,8 @@ def test_volume_mesh(self):
141142
self.assertIsInstance(dut.vertex(v=0), np.ndarray)
142143
self.assertIsInstance(dut.num_elements(), int)
143144
self.assertIsInstance(dut.num_vertices(), int)
145+
self.assertIsInstance(dut.inward_normal(e=0, f=0), np.ndarray)
146+
self.assertIsInstance(dut.edge_vector(e=0, a=0, b=1), np.ndarray)
144147

145148
# Sanity check some calculations
146149
self.assertAlmostEqual(dut.CalcTetrahedronVolume(e=1), 1/6.0,
@@ -154,9 +157,19 @@ def test_volume_mesh(self):
154157
self.assertIsInstance(dut.tetrahedra()[0], mut.VolumeElement)
155158
self.assertEqual(len(dut.vertices()), 5)
156159

160+
numpy_compare.assert_float_equal(
161+
dut.inward_normal(e=0, f=3), (-1., 0., 0.))
162+
numpy_compare.assert_float_equal(
163+
dut.inward_normal(e=1, f=3), (1., 0., 0.))
164+
numpy_compare.assert_float_equal(
165+
dut.edge_vector(e=0, a=1, b=3), (-1., 0., 0.))
166+
numpy_compare.assert_float_equal(
167+
dut.edge_vector(e=1, a=1, b=3), (1., 0., 0.))
168+
157169
# Now check the VolumeElement bindings.
158170
tetrahedron0 = dut.element(e=0)
159171
self.assertEqual(tetrahedron0.vertex(i=0), 2)
172+
self.assertEqual(tetrahedron0.num_vertices(), 4)
160173

161174
def test_convert_volume_to_surface_mesh(self):
162175
# Use the volume mesh from `test_volume_mesh()`.

geometry/proximity/mesh_field_linear.h

+64-1
Original file line numberDiff line numberDiff line change
@@ -198,6 +198,7 @@ class MeshFieldLinear {
198198
static_cast<int>(values_at_Mo_.size()));
199199
}
200200
}
201+
CalcMinAndMaxValues();
201202
}
202203

203204
/** (Advanced) Constructor variant which receives the pre-computed,
@@ -224,6 +225,7 @@ class MeshFieldLinear {
224225
DRAKE_DEMAND(static_cast<int>(gradients_.size()) == mesh_->num_elements());
225226

226227
CalcValueAtMeshOriginForAllElements();
228+
CalcMinAndMaxValues();
227229
}
228230

229231
/** @returns true iff the gradient field could not be computed, and the mesh
@@ -238,10 +240,40 @@ class MeshFieldLinear {
238240
@pre v ∈ [0, this->mesh().num_vertices()).
239241
*/
240242
const T& EvaluateAtVertex(int v) const {
241-
DRAKE_ASSERT(v >= 0 && v < mesh_->num_vertices());
243+
DRAKE_DEMAND(v >= 0 && v < mesh_->num_vertices());
242244
return values_[v];
243245
}
244246

247+
/** (Advanced) Evaluates the minimum field value on an element.
248+
@param e The index of the element.
249+
@pre e ∈ [0, this->mesh().num_elements()).
250+
*/
251+
const T& EvaluateMin(int e) const {
252+
DRAKE_DEMAND(e >= 0 && e < mesh_->num_elements());
253+
return min_values_[e];
254+
}
255+
256+
/** (Advanced) Evaluates the maximum field value on an element.
257+
@param e The index of the element.
258+
@pre e ∈ [0, this->mesh().num_elements()).
259+
*/
260+
const T& EvaluateMax(int e) const {
261+
DRAKE_DEMAND(e >= 0 && e < mesh_->num_elements());
262+
return max_values_[e];
263+
}
264+
265+
/** (Advanced) Evaluates the linear function associated with element e at the
266+
mesh origin Mo.
267+
@param e The index of the element.
268+
@pre e ∈ [0, this->mesh().num_elements()).
269+
@pre The field has valid gradients.
270+
*/
271+
const T& EvaluateAtMo(int e) const {
272+
DRAKE_DEMAND(e >= 0 && e < mesh_->num_elements());
273+
DRAKE_DEMAND(e < ssize(values_at_Mo_));
274+
return values_at_Mo_[e];
275+
}
276+
245277
/** Evaluates the field value at a location on an element.
246278
247279
The return type depends on both the field's scalar type `T` and the
@@ -361,8 +393,14 @@ class MeshFieldLinear {
361393
return new_mesh_field;
362394
}
363395

396+
/** The mesh M to which this field refers. */
364397
const MeshType& mesh() const { return *mesh_; }
398+
/** The field value at each vertex. */
365399
const std::vector<T>& values() const { return values_; }
400+
/** The minimum field value on each element. */
401+
const std::vector<T>& min_values() const { return min_values_; }
402+
/** The maximum field value on each element. */
403+
const std::vector<T>& max_values() const { return max_values_; }
366404

367405
// TODO(#12173): Consider NaN==NaN to be true in equality tests.
368406
/** Checks to see whether the given MeshFieldLinear object is equal via deep
@@ -416,6 +454,25 @@ class MeshFieldLinear {
416454
}
417455
}
418456

457+
void CalcMinAndMaxValues() {
458+
min_values_.clear();
459+
max_values_.clear();
460+
min_values_.reserve(this->mesh().num_elements());
461+
max_values_.reserve(this->mesh().num_elements());
462+
for (int e = 0; e < this->mesh().num_elements(); ++e) {
463+
T min, max;
464+
min = max = values_[this->mesh().element(e).vertex(0)];
465+
466+
for (int i = 1; i < mesh().element(e).num_vertices(); ++i) {
467+
min = std::min(min, values_[this->mesh().element(e).vertex(i)]);
468+
max = std::max(max, values_[this->mesh().element(e).vertex(i)]);
469+
}
470+
471+
min_values_.emplace_back(min);
472+
max_values_.emplace_back(max);
473+
}
474+
}
475+
419476
std::optional<Vector3<T>> MaybeCalcGradientVector(int e) const {
420477
// In the case of the PolygonSurfaceMesh, where kVertexPerElement is marked
421478
// as "indeterminate" (aka -1), we'll simply use the first three vertices.
@@ -454,6 +511,12 @@ class MeshFieldLinear {
454511
// The field values are indexed in the same way as vertices, i.e.,
455512
// values_[i] is the field value for the mesh vertices_[i].
456513
std::vector<T> values_;
514+
// Stores the minimum value of the field for each element, i.e.,
515+
// min_values_[i] is the minimum field value on the domain of elements_[i].
516+
std::vector<T> min_values_;
517+
// Stores the maximum value of the field for each element, i.e.,
518+
// min_values_[i] is the minimum field value on the domain of elements_[i].
519+
std::vector<T> max_values_;
457520
// The gradients are indexed in the same way as elements, i.e.,
458521
// gradients_[i] is the gradient vector on elements_[i]. The elements could
459522
// be tetrahedra for VolumeMesh or triangles for TriangleSurfaceMesh.

geometry/proximity/test/mesh_field_linear_test.cc

+17
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,23 @@ GTEST_TEST(MeshFieldLinearTest, EvaluateAtVertex) {
6868
EXPECT_EQ(mesh_field->EvaluateAtVertex(3), 3);
6969
}
7070

71+
GTEST_TEST(MeshFieldLinearTest, EvaluateMinAndMaxAndMo) {
72+
auto mesh = GenerateMesh<double>();
73+
constexpr double kEps = std::numeric_limits<double>::epsilon();
74+
75+
// Arbitrary values such that min and max are unique on each element.
76+
std::vector<double> e_values = {1., -2., 2., 3.};
77+
auto mesh_field =
78+
std::make_unique<MeshFieldLinear<double, TriangleSurfaceMesh<double>>>(
79+
std::move(e_values), mesh.get());
80+
EXPECT_EQ(mesh_field->EvaluateMin(0), -2);
81+
EXPECT_EQ(mesh_field->EvaluateMin(1), 1);
82+
EXPECT_EQ(mesh_field->EvaluateMax(0), 2);
83+
EXPECT_EQ(mesh_field->EvaluateMax(1), 3);
84+
EXPECT_NEAR(mesh_field->EvaluateAtMo(0), 1, kEps);
85+
EXPECT_NEAR(mesh_field->EvaluateAtMo(1), 1, kEps);
86+
}
87+
7188
// Tests CloneAndSetMesh(). We use `double` and TriangleSurfaceMesh<double> as
7289
// representative arguments for type parameters.
7390
GTEST_TEST(MeshFieldLinearTest, TestDoCloneWithMesh) {

0 commit comments

Comments
 (0)