Skip to content

Commit

Permalink
proximity: Don't warn when parsing meshes with mtl files
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri committed Apr 29, 2021
1 parent 61ff899 commit 9ce447e
Show file tree
Hide file tree
Showing 4 changed files with 63 additions and 32 deletions.
11 changes: 7 additions & 4 deletions bindings/pydrake/geometry_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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<const std::string&, double>(
&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) {
Expand Down
67 changes: 42 additions & 25 deletions geometry/proximity/obj_to_surface_mesh.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,9 @@

#include <fstream>
#include <istream>
#include <memory>
#include <numeric>
#include <optional>
#include <stdexcept>
#include <string>
#include <utility>
Expand All @@ -12,6 +14,7 @@
#include <tiny_obj_loader.h>

#include "drake/common/drake_assert.h"
#include "drake/common/filesystem.h"
#include "drake/common/text_logging.h"
#include "drake/geometry/proximity/surface_mesh.h"

Expand All @@ -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
Expand Down Expand Up @@ -111,39 +108,36 @@ void TinyObjToSurfaceFaces(const tinyobj::mesh_t& mesh,
}
}

#endif // #ifndef DRAKE_DOXYGEN_CXX

} // namespace

SurfaceMesh<double> 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<double> ReadObjToSurfaceMesh(std::istream* input_stream,
const double scale) {
SurfaceMesh<double> DoReadObjToSurfaceMesh(
std::istream* input_stream,
const double scale,
const std::optional<std::string>& mtl_base_dir,
const std::function<void(std::string_view)> on_warning) {
tinyobj::attrib_t attrib; // Used for vertices.
std::vector<tinyobj::shape_t> shapes; // Used for triangles.
std::vector<tinyobj::material_t> materials; // Not used.
std::string warn;
std::string err;
// Ignore material-library file.
tinyobj::MaterialReader* readMatFn = nullptr;
std::unique_ptr<tinyobj::MaterialReader> readMatFn;
if (mtl_base_dir) {
readMatFn = std::make_unique<tinyobj::MaterialFileReader>(*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.");
Expand All @@ -169,5 +163,28 @@ SurfaceMesh<double> ReadObjToSurfaceMesh(std::istream* input_stream,
return SurfaceMesh<double>(std::move(faces), std::move(vertices));
}

} // namespace

SurfaceMesh<double> ReadObjToSurfaceMesh(
const std::string& filename,
const double scale,
std::function<void(std::string_view)> 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<double> 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
10 changes: 8 additions & 2 deletions geometry/proximity/obj_to_surface_mesh.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include <istream>
#include <string>
#include <string_view>
#include <vector>

#include "drake/geometry/proximity/surface_mesh.h"
Expand All @@ -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<double> ReadObjToSurfaceMesh(const std::string& filename,
double scale = 1.0);
SurfaceMesh<double> ReadObjToSurfaceMesh(
const std::string& filename,
double scale = 1.0,
std::function<void(std::string_view)> on_warning = {});

/**
Overload of @ref ReadObjToSurfaceMesh(const std::string&, double) with the
Expand Down
7 changes: 6 additions & 1 deletion geometry/proximity/test/obj_to_surface_mesh_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,12 @@ GTEST_TEST(ObjToSurfaceMeshTest, TinyObjToSurfaceFaces) {
GTEST_TEST(ObjToSurfaceMeshTest, ReadObjToSurfaceMesh) {
const std::string filename =
FindResourceOrThrow("drake/geometry/test/quad_cube.obj");
SurfaceMesh<double> surface = ReadObjToSurfaceMesh(filename);
const auto fail_on_warning = [](std::string_view message) {
throw std::runtime_error(fmt::format(
"Unexpected warning: {}", message));
};
SurfaceMesh<double> surface = ReadObjToSurfaceMesh(
filename, 1.0, fail_on_warning);

ASSERT_EQ(surface.num_vertices(), 8);
ASSERT_EQ(surface.num_faces(), 12);
Expand Down

0 comments on commit 9ce447e

Please sign in to comment.