From 9ce447ec4cefb1ba04c5674d882170d5853d527c Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Thu, 29 Apr 2021 11:31:30 -0700 Subject: [PATCH] proximity: Don't warn when parsing meshes with mtl files --- bindings/pydrake/geometry_py.cc | 11 +-- geometry/proximity/obj_to_surface_mesh.cc | 67 ++++++++++++------- geometry/proximity/obj_to_surface_mesh.h | 10 ++- .../test/obj_to_surface_mesh_test.cc | 7 +- 4 files changed, 63 insertions(+), 32 deletions(-) diff --git a/bindings/pydrake/geometry_py.cc b/bindings/pydrake/geometry_py.cc index 0f9cfd5325e6..de2c36603950 100644 --- a/bindings/pydrake/geometry_py.cc +++ b/bindings/pydrake/geometry_py.cc @@ -1283,11 +1283,14 @@ void DoScalarIndependentDefinitions(py::module m) { py_rvp::reference_internal, py::arg("diffuse"), doc.MakePhongIllustrationProperties.doc); - m.def("ReadObjToSurfaceMesh", - py::overload_cast( - &geometry::ReadObjToSurfaceMesh), + m.def( + "ReadObjToSurfaceMesh", + [](const std::string& filename, double scale) { + return geometry::ReadObjToSurfaceMesh(filename, scale); + }, py::arg("filename"), py::arg("scale") = 1.0, - doc.ReadObjToSurfaceMesh.doc_2args_filename_scale); + // N.B. We have not bound the optional "on_warning" argument. + doc.ReadObjToSurfaceMesh.doc_3args); } void def_geometry(py::module m) { diff --git a/geometry/proximity/obj_to_surface_mesh.cc b/geometry/proximity/obj_to_surface_mesh.cc index cff83a1bb24c..689fe5f2f004 100644 --- a/geometry/proximity/obj_to_surface_mesh.cc +++ b/geometry/proximity/obj_to_surface_mesh.cc @@ -2,7 +2,9 @@ #include #include +#include #include +#include #include #include #include @@ -12,6 +14,7 @@ #include #include "drake/common/drake_assert.h" +#include "drake/common/filesystem.h" #include "drake/common/text_logging.h" #include "drake/geometry/proximity/surface_mesh.h" @@ -23,12 +26,6 @@ namespace { // TODO(DamrongGuoy): Refactor the tinyobj usage between here and // ProximityEngine. -// TODO(DamrongGuoy): Remove the guard DRAKE_DOXYGEN_CXX when we fixed -// issue#11130 "doxygen: Do not emit for `*.cc` files, also ignore -// `internal` namespace when appropriate". - -#ifndef DRAKE_DOXYGEN_CXX - /* Converts vertices of tinyobj to vertices of SurfaceMesh. @param tinyobj_vertices @@ -111,39 +108,36 @@ void TinyObjToSurfaceFaces(const tinyobj::mesh_t& mesh, } } -#endif // #ifndef DRAKE_DOXYGEN_CXX - -} // namespace - -SurfaceMesh ReadObjToSurfaceMesh(const std::string& filename, - const double scale) { - std::ifstream input_stream(filename); - if (!input_stream.is_open()) { - throw std::runtime_error("Cannot open file '" + filename +"'"); - } - return ReadObjToSurfaceMesh(&input_stream, scale); -} - -SurfaceMesh ReadObjToSurfaceMesh(std::istream* input_stream, - const double scale) { +SurfaceMesh DoReadObjToSurfaceMesh( + std::istream* input_stream, + const double scale, + const std::optional& mtl_base_dir, + const std::function on_warning) { tinyobj::attrib_t attrib; // Used for vertices. std::vector shapes; // Used for triangles. std::vector materials; // Not used. std::string warn; std::string err; - // Ignore material-library file. - tinyobj::MaterialReader* readMatFn = nullptr; + std::unique_ptr readMatFn; + if (mtl_base_dir) { + readMatFn = std::make_unique(*mtl_base_dir); + } // triangulate non-triangle faces. bool triangulate = true; bool ret = tinyobj::LoadObj( - &attrib, &shapes, &materials, &warn, &err, input_stream, readMatFn, + &attrib, &shapes, &materials, &warn, &err, input_stream, readMatFn.get(), triangulate); if (!ret || !err.empty()) { throw std::runtime_error("Error parsing Wavefront obj file : " + err); } if (!warn.empty()) { - drake::log()->warn("Warning parsing Wavefront obj file : {}", warn); + warn = "Warning parsing Wavefront obj file : " + warn; + if (on_warning) { + on_warning(warn); + } else { + drake::log()->warn("{}", warn); + } } if (shapes.size() == 0) { throw std::runtime_error("The Wavefront obj file has no faces."); @@ -169,5 +163,28 @@ SurfaceMesh ReadObjToSurfaceMesh(std::istream* input_stream, return SurfaceMesh(std::move(faces), std::move(vertices)); } +} // namespace + +SurfaceMesh ReadObjToSurfaceMesh( + const std::string& filename, + const double scale, + std::function on_warning) { + std::ifstream input_stream(filename); + if (!input_stream.is_open()) { + throw std::runtime_error("Cannot open file '" + filename +"'"); + } + const std::string mtl_base_dir = + filesystem::path(filename).parent_path().string() + "/"; + return DoReadObjToSurfaceMesh(&input_stream, scale, mtl_base_dir, + std::move(on_warning)); +} + +SurfaceMesh ReadObjToSurfaceMesh(std::istream* input_stream, + const double scale) { + DRAKE_THROW_UNLESS(input_stream != nullptr); + return DoReadObjToSurfaceMesh(input_stream, scale, + std::nullopt /* mtl_base_dir */, {} /* on_warning*/); +} + } // namespace geometry } // namespace drake diff --git a/geometry/proximity/obj_to_surface_mesh.h b/geometry/proximity/obj_to_surface_mesh.h index b13896a793ac..b9bcd61d724b 100644 --- a/geometry/proximity/obj_to_surface_mesh.h +++ b/geometry/proximity/obj_to_surface_mesh.h @@ -2,6 +2,7 @@ #include #include +#include #include #include "drake/geometry/proximity/surface_mesh.h" @@ -19,12 +20,17 @@ namespace geometry { A valid file name with absolute path or relative path. @param scale An optional scale to coordinates. + @param on_warning + An optional callback that will receive warning message(s) encountered + while reading the mesh. When not provided, drake::log() will be used. @throws std::runtime_error if `filename` doesn't have a valid file path, or the file has no faces. @return surface mesh */ -SurfaceMesh ReadObjToSurfaceMesh(const std::string& filename, - double scale = 1.0); +SurfaceMesh ReadObjToSurfaceMesh( + const std::string& filename, + double scale = 1.0, + std::function on_warning = {}); /** Overload of @ref ReadObjToSurfaceMesh(const std::string&, double) with the diff --git a/geometry/proximity/test/obj_to_surface_mesh_test.cc b/geometry/proximity/test/obj_to_surface_mesh_test.cc index 742a8fd07a80..7e110ffb8c68 100644 --- a/geometry/proximity/test/obj_to_surface_mesh_test.cc +++ b/geometry/proximity/test/obj_to_surface_mesh_test.cc @@ -76,7 +76,12 @@ GTEST_TEST(ObjToSurfaceMeshTest, TinyObjToSurfaceFaces) { GTEST_TEST(ObjToSurfaceMeshTest, ReadObjToSurfaceMesh) { const std::string filename = FindResourceOrThrow("drake/geometry/test/quad_cube.obj"); - SurfaceMesh surface = ReadObjToSurfaceMesh(filename); + const auto fail_on_warning = [](std::string_view message) { + throw std::runtime_error(fmt::format( + "Unexpected warning: {}", message)); + }; + SurfaceMesh surface = ReadObjToSurfaceMesh( + filename, 1.0, fail_on_warning); ASSERT_EQ(surface.num_vertices(), 8); ASSERT_EQ(surface.num_faces(), 12);