-
Notifications
You must be signed in to change notification settings - Fork 1.3k
/
refine_mesh.cc
84 lines (74 loc) · 2.89 KB
/
refine_mesh.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
#include <filesystem>
#include <gflags/gflags.h>
#include "drake/common/text_logging.h"
#include "drake/geometry/proximity/detect_zero_simplex.h"
#include "drake/geometry/proximity/mesh_to_vtk.h"
#include "drake/geometry/proximity/volume_mesh_refiner.h"
#include "drake/geometry/proximity/vtk_to_volume_mesh.h"
namespace drake {
namespace geometry {
namespace {
int do_main(int argc, char* argv[]) {
gflags::SetUsageMessage(
"[INPUT-FILE] [OUTPUT-FILE]\n"
"\n"
"Refine a tetrahedral mesh of a compliant-hydroelastic geometry in\n"
"the input VTK file to eliminate problematic tetrahedra,\n"
"internal triangles, and internal edges with all boundary vertices.\n"
"They define zero pressure in the interior volume creating a void\n"
"space of no hydroelastic contact.\n"
"\n"
"If the input has no problems, no output file is written.\n"
"\n"
"After building this tool from source; for example:\n"
" drake $ bazel build //geometry/proximity:refine_mesh\n"
"Run it in your data directory; for example:\n"
" data $ /path/to/drake/bazel-bin/geometry/proximity/refine_mesh "
"input.vtk output.vtk");
gflags::ParseCommandLineFlags(&argc, &argv, true);
if (argc < 2) {
drake::log()->error("missing input filename");
return 1;
}
if (argc < 3) {
drake::log()->error("missing output filename");
return 1;
}
VolumeMesh<double> mesh = internal::ReadVtkToVolumeMesh(argv[1]);
std::vector<int> bad_tets =
internal::DetectTetrahedronWithAllBoundaryVertices(mesh);
std::vector<internal::SortedTriplet<int>> bad_triangles =
internal::DetectInteriorTriangleWithAllBoundaryVertices(mesh);
std::vector<SortedPair<int>> bad_edges =
internal::DetectInteriorEdgeWithAllBoundaryVertices(mesh);
drake::log()->info(
"Found {} bad tets, {} bad triangles, and {} bad edges."
"The mesh has {} tets and {} vertices.",
bad_tets.size(), bad_triangles.size(), bad_edges.size(),
mesh.tetrahedra().size(), mesh.vertices().size());
bool found_bad =
(!bad_tets.empty() || !bad_triangles.empty() || !bad_edges.empty());
if (!found_bad) {
drake::log()->info(
"No problems found in input mesh '{}';"
" not writing an output mesh.",
argv[1]);
return 0;
}
VolumeMesh<double> refined_mesh = internal::VolumeMeshRefiner(mesh).Refine();
std::filesystem::path outfile(argv[2]);
internal::WriteVolumeMeshToVtk(outfile.string(), refined_mesh,
"refined by //geometry/proximity:refine_mesh");
drake::log()->info(
"wrote refined mesh to file '{}' with {} tets and {} "
"vertices.",
outfile.string(), refined_mesh.tetrahedra().size(),
refined_mesh.vertices().size());
return 0;
}
} // namespace
} // namespace geometry
} // namespace drake
int main(int argc, char* argv[]) {
return drake::geometry::do_main(argc, argv);
}