From 3a5b93b3e29e9d0233259d3543829e93485c90f5 Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Wed, 17 Jan 2024 18:00:01 -0800 Subject: [PATCH] [geometry] Meshcat's server returns 404 (not 200) on failures This is also an opportunity to start to carve helper functions and classes out into separate files for easier maintenance. Two of the new functions are public and widely relevant: ReadFile and ReadFileOrThrow. --- .../pydrake/geometry/test/visualizers_test.py | 12 ++ common/BUILD.bazel | 1 + common/find_resource.cc | 24 +++- common/find_resource.h | 9 ++ common/test/find_resource_test.cc | 18 +-- common/yaml/test/yaml_doxygen_test.cc | 12 +- common/yaml/test/yaml_io_test.cc | 12 +- geometry/BUILD.bazel | 14 ++- geometry/meshcat.cc | 106 ++++++------------ geometry/meshcat_internal.cc | 61 ++++++++++ geometry/meshcat_internal.h | 24 ++++ geometry/render_gl/internal_shader_program.cc | 12 +- .../internal_render_client.cc | 8 +- geometry/test/meshcat_internal_test.cc | 28 +++++ multibody/parsing/package_map.cc | 6 +- .../parsing/test/package_map_remote_test.cc | 5 +- multibody/parsing/test/parser_test.cc | 18 +-- .../test/process_model_directives_test.cc | 9 +- solvers/BUILD.bazel | 2 + solvers/gurobi_solver.cc | 8 +- solvers/test/snopt_solver_test.cc | 25 ++--- 21 files changed, 244 insertions(+), 170 deletions(-) create mode 100644 geometry/meshcat_internal.cc create mode 100644 geometry/meshcat_internal.h create mode 100644 geometry/test/meshcat_internal_test.cc diff --git a/bindings/pydrake/geometry/test/visualizers_test.py b/bindings/pydrake/geometry/test/visualizers_test.py index 81e67b58f357..ff0ba0a4e191 100644 --- a/bindings/pydrake/geometry/test/visualizers_test.py +++ b/bindings/pydrake/geometry/test/visualizers_test.py @@ -261,6 +261,18 @@ def test_meshcat(self): # The pose is None because no meshcat session has broadcast its pose. self.assertIsNone(meshcat.GetTrackedCameraPose()) + def test_meshcat_404(self): + meshcat = mut.Meshcat() + + good_url = meshcat.web_url() + with urllib.request.urlopen(good_url) as response: + self.assertTrue(response.read(1)) + + bad_url = f"{good_url}/no_such_file" + with self.assertRaisesRegex(Exception, "HTTP.*404"): + with urllib.request.urlopen(bad_url) as response: + response.read(1) + def test_meshcat_animation(self): animation = mut.MeshcatAnimation(frames_per_second=64) self.assertEqual(animation.frames_per_second(), 64) diff --git a/common/BUILD.bazel b/common/BUILD.bazel index 381a94da829f..2fed8cc23b30 100644 --- a/common/BUILD.bazel +++ b/common/BUILD.bazel @@ -919,6 +919,7 @@ drake_cc_googletest( ":drake_path", ":find_resource", "//common/test_utilities:expect_no_throw", + "//common/test_utilities:expect_throws_message", ], ) diff --git a/common/find_resource.cc b/common/find_resource.cc index 2948328296d5..86d4e5857ca3 100644 --- a/common/find_resource.cc +++ b/common/find_resource.cc @@ -1,7 +1,9 @@ #include "drake/common/find_resource.h" #include -#include +#include +#include +#include #include #include @@ -291,4 +293,24 @@ string FindResourceOrThrow(const string& resource_path) { return FindResource(resource_path).get_absolute_path_or_throw(); } +std::optional ReadFile(const std::filesystem::path& path) { + std::optional result; + std::ifstream input(path, std::ios::binary); + if (input.is_open()) { + std::stringstream content; + content << input.rdbuf(); + result.emplace(std::move(content).str()); + } + return result; +} + +std::string ReadFileOrThrow(const std::filesystem::path& path) { + std::optional result = ReadFile(path); + if (!result) { + throw std::runtime_error( + fmt::format("Error reading from '{}'", path.string())); + } + return std::move(*result); +} + } // namespace drake diff --git a/common/find_resource.h b/common/find_resource.h index d517da9b959e..521063807a50 100644 --- a/common/find_resource.h +++ b/common/find_resource.h @@ -1,5 +1,6 @@ #pragma once +#include #include #include #include @@ -125,4 +126,12 @@ std::string FindResourceOrThrow(const std::string& resource_path); /// copy of Drake, in case other methods have failed. extern const char* const kDrakeResourceRootEnvironmentVariableName; +/// Returns the content of the file at the given path, or nullopt if it cannot +/// be read. Note that the path is a filesystem path, not a `resource_path`. +std::optional ReadFile(const std::filesystem::path& path); + +/// Returns the content of the file at the given path, or throws if it cannot +/// be read. Note that the path is a filesystem path, not a `resource_path`. +std::string ReadFileOrThrow(const std::filesystem::path& path); + } // namespace drake diff --git a/common/test/find_resource_test.cc b/common/test/find_resource_test.cc index a40c55aa1a5c..07c777e950e7 100644 --- a/common/test/find_resource_test.cc +++ b/common/test/find_resource_test.cc @@ -2,10 +2,8 @@ #include #include -#include #include #include -#include #include #include @@ -16,6 +14,7 @@ #include "drake/common/drake_path.h" #include "drake/common/drake_throw.h" #include "drake/common/test_utilities/expect_no_throw.h" +#include "drake/common/test_utilities/expect_throws_message.h" using std::string; @@ -84,13 +83,8 @@ GTEST_TEST(FindResourceTest, FoundDeclaredData) { // The path is the correct answer. ASSERT_FALSE(absolute_path.empty()); EXPECT_EQ(absolute_path[0], '/'); - std::ifstream input(absolute_path, std::ios::binary); - ASSERT_TRUE(input); - std::stringstream buffer; - buffer << input.rdbuf(); - EXPECT_EQ( - buffer.str(), - "Test data for drake/common/test/find_resource_test.cc.\n"); + EXPECT_EQ(ReadFileOrThrow(absolute_path), + "Test data for drake/common/test/find_resource_test.cc.\n"); // Sugar works the same way. EXPECT_EQ(FindResourceOrThrow(relpath), absolute_path); @@ -120,5 +114,11 @@ GTEST_TEST(GetDrakePathTest, PathIncludesDrake) { EXPECT_TRUE(std::filesystem::exists(expected)); } +GTEST_TEST(ReadFileTest, NoSuchPath) { + EXPECT_FALSE(ReadFile("/foo/bar/missing")); + DRAKE_EXPECT_THROWS_MESSAGE(ReadFileOrThrow("/foo/bar/missing"), + "Error reading.*/foo/bar/missing.*"); +} + } // namespace } // namespace drake diff --git a/common/yaml/test/yaml_doxygen_test.cc b/common/yaml/test/yaml_doxygen_test.cc index 8de15985e797..b3b181ccde46 100644 --- a/common/yaml/test/yaml_doxygen_test.cc +++ b/common/yaml/test/yaml_doxygen_test.cc @@ -30,16 +30,6 @@ std::string WriteTemp(const std::string& data) { return filename; } -// Read data from a scratch file. -// (This is a test helper, not part of the Doxygen header.) -std::string ReadTemp(const std::string& filename) { - std::ifstream input(filename, std::ios::binary); - DRAKE_DEMAND(!input.fail()); - std::stringstream buffer; - buffer << input.rdbuf(); - return buffer.str(); -} - // This is an example from the Doxygen header. struct MyData { template @@ -80,7 +70,7 @@ GTEST_TEST(YamlDoxygenTest, ExamplesSaving) { SaveYamlFile(output_filename, data); // This data is an example from the Doxygen header. - const std::string output = ReadTemp(output_filename); + const std::string output = ReadFileOrThrow(output_filename); const std::string expected_output = R"""( foo: 4.0 bar: [5.0, 6.0] diff --git a/common/yaml/test/yaml_io_test.cc b/common/yaml/test/yaml_io_test.cc index 008951265aa8..dbc57c182594 100644 --- a/common/yaml/test/yaml_io_test.cc +++ b/common/yaml/test/yaml_io_test.cc @@ -21,14 +21,6 @@ namespace yaml { namespace test { namespace { -std::string ReadTestFileAsString(const std::string& filename) { - std::ifstream input(filename, std::ios::binary); - DRAKE_DEMAND(!input.fail()); - std::stringstream buffer; - buffer << input.rdbuf(); - return buffer.str(); -} - GTEST_TEST(YamlIoTest, LoadString) { const std::string data = R"""( value: @@ -182,7 +174,7 @@ GTEST_TEST(YamlIoTest, SaveFile) { const std::string filename = temp_directory() + "/SaveFile1.yaml"; const StringStruct data{.value = "save_file_1"}; SaveYamlFile(filename, data); - const auto result = ReadTestFileAsString(filename); + const auto result = ReadFileOrThrow(filename); EXPECT_EQ(result, "value: save_file_1\n"); } @@ -194,7 +186,7 @@ GTEST_TEST(YamlIoTest, SaveFileAllArgs) { data.value.insert({"save_file_4", 1.0}); ASSERT_EQ(data.value.size(), 2); SaveYamlFile(filename, data, child_name, {defaults}); - const auto result = ReadTestFileAsString(filename); + const auto result = ReadFileOrThrow(filename); EXPECT_EQ(result, "some_child:\n value:\n save_file_4: 1.0\n"); } diff --git a/geometry/BUILD.bazel b/geometry/BUILD.bazel index a3e99c0342d3..99fed27b2b47 100644 --- a/geometry/BUILD.bazel +++ b/geometry/BUILD.bazel @@ -452,13 +452,18 @@ drake_cc_googletest( drake_cc_library( name = "meshcat", - srcs = ["meshcat.cc"], + srcs = [ + "meshcat.cc", + "meshcat_internal.cc", + ], hdrs = [ "meshcat.h", + "meshcat_internal.h", "meshcat_types_internal.h", ], data = [":meshcat_resources"], install_hdrs_exclude = [ + "meshcat_internal.h", "meshcat_types_internal.h", ], interface_deps = [ @@ -535,6 +540,13 @@ drake_cc_googletest( ], ) +drake_cc_googletest( + name = "meshcat_internal_test", + deps = [ + ":meshcat", + ], +) + drake_cc_googletest( name = "meshcat_denied_test", allow_network = ["none"], diff --git a/geometry/meshcat.cc b/geometry/meshcat.cc index 694d99ba781a..85a1e9fd5a54 100644 --- a/geometry/meshcat.cc +++ b/geometry/meshcat.cc @@ -27,11 +27,11 @@ #include "drake/common/drake_throw.h" #include "drake/common/find_resource.h" #include "drake/common/network_policy.h" -#include "drake/common/never_destroyed.h" #include "drake/common/overloaded.h" #include "drake/common/scope_exit.h" #include "drake/common/ssize.h" #include "drake/common/text_logging.h" +#include "drake/geometry/meshcat_internal.h" #include "drake/geometry/meshcat_types_internal.h" #ifdef BOOST_VERSION @@ -43,44 +43,12 @@ extern "C" { void us_internal_free_closed_sockets(struct us_loop_t*); } +namespace drake { +namespace geometry { namespace { -std::string LoadResource(const std::string& resource_name) { - const std::string resource = drake::FindResourceOrThrow(resource_name); - std::ifstream file(resource.c_str(), std::ios::in); - if (!file.is_open()) - throw std::runtime_error("Error opening resource: " + resource_name); - std::stringstream content; - content << file.rdbuf(); - file.close(); - return content.str(); -} -const std::string& GetStaticResource(std::string_view url_path) { - static const drake::never_destroyed meshcat_js( - LoadResource("drake/geometry/meshcat.js")); - static const drake::never_destroyed stats_js( - LoadResource("drake/geometry/stats.min.js")); - static const drake::never_destroyed meshcat_ico( - LoadResource("drake/geometry/meshcat.ico")); - static const drake::never_destroyed meshcat_html( - LoadResource("drake/geometry/meshcat.html")); - static const drake::never_destroyed empty; - if ((url_path == "/") || (url_path == "/index.html") || - (url_path == "/meshcat.html")) { - return meshcat_html.access(); - } - if (url_path == "/meshcat.js") { - return meshcat_js.access(); - } - if (url_path == "/stats.min.js") { - return stats_js.access(); - } - if (url_path == "/favicon.ico") { - return meshcat_ico.access(); - } - drake::log()->warn("Ignoring Meshcat http request for {}", url_path); - return empty.access(); -} +using math::RigidTransformd; +using math::RotationMatrixd; template [[noreturn]] void ThrowThingNotFound(std::string_view thing, @@ -95,16 +63,6 @@ template thing, name, thing, fmt::join(keys, ", "))); } -} // namespace - -namespace drake { -namespace geometry { - -namespace { - -using math::RigidTransformd; -using math::RotationMatrixd; - constexpr static bool kSsl = false; constexpr static bool kIsServer = true; struct PerSocketData { @@ -284,20 +242,15 @@ class MeshcatShapeReifier : public ShapeReifier { std::string format = extension; format.erase(0, 1); // remove the . from the extension - std::ifstream input(filename, std::ios::binary | std::ios::ate); - if (!input.is_open()) { + std::optional maybe_mesh_data = ReadFile(filename); + if (!maybe_mesh_data) { drake::log()->warn("Meshcat: Could not open mesh filename {}", filename); return; } // We simply dump the binary contents of the file into the data field of the // message. The javascript meshcat takes care of the rest. - const int obj_size = input.tellg(); - input.seekg(0, std::ios::beg); - std::string mesh_data; - mesh_data.reserve(obj_size); - mesh_data.assign(std::istreambuf_iterator(input), - std::istreambuf_iterator()); + std::string mesh_data = std::move(*maybe_mesh_data); // TODO(russt): MeshCat.jl/src/mesh_files.jl loads dae with textures, also. @@ -330,14 +283,9 @@ class MeshcatShapeReifier : public ShapeReifier { std::filesystem::path(filename).parent_path(); // Read .mtl file into geometry.mtl_library. - std::ifstream mtl_stream(basedir / mtllib, std::ios::ate); - if (mtl_stream.is_open()) { - int mtl_size = mtl_stream.tellg(); - mtl_stream.seekg(0, std::ios::beg); - meshfile_object.mtl_library.reserve(mtl_size); - meshfile_object.mtl_library.assign( - std::istreambuf_iterator(mtl_stream), - std::istreambuf_iterator()); + if (std::optional maybe_mtl_data = + ReadFile(basedir / mtllib)) { + meshfile_object.mtl_library = std::move(*maybe_mtl_data); // Scan .mtl file for map_ lines. For each, load the file and add // the contents to geometry.resources. @@ -640,7 +588,7 @@ class Meshcat::Impl { } // Fetch the index once to be sure that we preload the content. - GetStaticResource("/"); + DRAKE_DEMAND(internal::GetMeshcatStaticResource("/").has_value()); std::promise> app_promise; std::future> app_future = app_promise.get_future(); @@ -1596,7 +1544,7 @@ class Meshcat::Impl { // outer function calls into here using appropriate deferred handling. std::string CalcStandaloneHtml() const { DRAKE_DEMAND(IsThread(websocket_thread_id_)); - std::string html = GetStaticResource("/"); + std::string html{internal::GetMeshcatStaticResource("/").value()}; // Insert the javascript directly into the html. std::vector> js_paths{ @@ -1604,10 +1552,12 @@ class Meshcat::Impl { {" src=\"stats.min.js\"", "/stats.min.js"}, }; for (const auto& [src_link, url] : js_paths) { + const std::string_view url_data = + internal::GetMeshcatStaticResource(url).value(); const size_t js_pos = html.find(src_link); DRAKE_DEMAND(js_pos != std::string::npos); html.erase(js_pos, src_link.size()); - html.insert(js_pos + 1, GetStaticResource(url)); + html.insert(js_pos + 1, url_data); } // Replace the javascript code in the original html file which connects via @@ -1957,20 +1907,30 @@ class Meshcat::Impl { void HandleHttpGet(std::string_view url_path, uWS::HttpResponse* response) const { DRAKE_DEMAND(IsThread(websocket_thread_id_)); - drake::log()->debug("Meshcat GET on {}", url_path); + drake::log()->debug("Meshcat: GET {}", url_path); + // Handle the magic download URL. if (url_path == "/download") { - const std::string output = CalcStandaloneHtml(); + const std::string content = CalcStandaloneHtml(); response->writeHeader("Content-Type", "text/html; charset=utf-8"); response->writeHeader("Content-Disposition", "attachment; filename=\"meshcat.html\""); - response->end(output); + response->end(content); return; } - const std::string& content = GetStaticResource(url_path); - if (content.substr(0, 15) == "") { - response->writeHeader("Content-Type", "text/html; charset=utf-8"); + // Handle static (i.e., compiled-in) files. + if (const std::optional content = + internal::GetMeshcatStaticResource(url_path)) { + if (content->substr(0, 15) == "") { + response->writeHeader("Content-Type", "text/html; charset=utf-8"); + } + response->end(*content); + return; } - response->end(content); + // Unknown URL. + log()->warn("Meshcat: Failed http request for unknown URL {}", url_path); + response->writeStatus("404 Not Found"); + response->writeHeader("Cache-Control:", "no-cache"); + response->end(""); } // This function is a callback from a WebSocketBehavior. However, unit tests diff --git a/geometry/meshcat_internal.cc b/geometry/meshcat_internal.cc new file mode 100644 index 000000000000..b9639394aa67 --- /dev/null +++ b/geometry/meshcat_internal.cc @@ -0,0 +1,61 @@ +#include "drake/geometry/meshcat_internal.h" + +#include +#include +#include +#include + +#include + +#include "drake/common/find_resource.h" +#include "drake/common/never_destroyed.h" + +namespace fs = std::filesystem; + +namespace drake { +namespace geometry { +namespace internal { + +namespace { + +std::string LoadResource(const std::string& resource_name) { + const std::string resource = FindResourceOrThrow(resource_name); + std::optional content = ReadFile(resource); + if (!content) { + throw std::runtime_error( + fmt::format("Error opening resource: {}", resource_name)); + } + return std::move(*content); +} + +} // namespace + +std::optional GetMeshcatStaticResource( + std::string_view url_path) { + static const drake::never_destroyed meshcat_js( + LoadResource("drake/geometry/meshcat.js")); + static const drake::never_destroyed stats_js( + LoadResource("drake/geometry/stats.min.js")); + static const drake::never_destroyed meshcat_ico( + LoadResource("drake/geometry/meshcat.ico")); + static const drake::never_destroyed meshcat_html( + LoadResource("drake/geometry/meshcat.html")); + if ((url_path == "/") || (url_path == "/index.html") || + (url_path == "/meshcat.html")) { + return meshcat_html.access(); + } + if (url_path == "/meshcat.js") { + return meshcat_js.access(); + } + if (url_path == "/stats.min.js") { + return stats_js.access(); + } + if (url_path == "/favicon.ico") { + return meshcat_ico.access(); + } + return {}; +} + +} // namespace internal +} // namespace geometry +} // namespace drake diff --git a/geometry/meshcat_internal.h b/geometry/meshcat_internal.h new file mode 100644 index 000000000000..bb362a8c1f18 --- /dev/null +++ b/geometry/meshcat_internal.h @@ -0,0 +1,24 @@ +#pragma once + +#include +#include +#include + +namespace drake { +namespace geometry { +namespace internal { + +/* Returns the static content for the given URL, or nullopt when the URL is +invalid. The valid static resource URLs are: +- `/` +- `/favicon.ico` +- `/index.html` +- `/meshcat.html` +- `/meshcat.js` +- `/stats.min.js` */ +std::optional GetMeshcatStaticResource( + std::string_view url_path); + +} // namespace internal +} // namespace geometry +} // namespace drake diff --git a/geometry/render_gl/internal_shader_program.cc b/geometry/render_gl/internal_shader_program.cc index 32bd2f5b7e6f..15173d3c0aa2 100644 --- a/geometry/render_gl/internal_shader_program.cc +++ b/geometry/render_gl/internal_shader_program.cc @@ -4,10 +4,13 @@ #include #include #include +#include #include #include +#include "drake/common/find_resource.h" + namespace drake { namespace geometry { namespace render_gl { @@ -90,13 +93,10 @@ void ShaderProgram::LoadFromSources(const std::string& vertex_shader_source, namespace { std::string LoadFile(const std::string& filename) { - std::ifstream file(filename.c_str(), std::ios::in); - if (!file.is_open()) + std::optional content = ReadFile(filename); + if (!content) throw std::runtime_error("Error opening shader file: " + filename); - std::stringstream content; - content << file.rdbuf(); - file.close(); - return content.str(); + return std::move(*content); } } // namespace diff --git a/geometry/render_gltf_client/internal_render_client.cc b/geometry/render_gltf_client/internal_render_client.cc index 1028e6fb4ccf..20e0942f5c9d 100644 --- a/geometry/render_gltf_client/internal_render_client.cc +++ b/geometry/render_gltf_client/internal_render_client.cc @@ -11,6 +11,7 @@ #include +#include "drake/common/find_resource.h" #include "drake/common/sha256.h" #include "drake/common/temp_directory.h" #include "drake/common/text_logging.h" @@ -178,11 +179,8 @@ std::string RenderClient::RenderOnServer( const std::string& data_path = response.data_path.value(); const std::uintmax_t bin_size = fs::file_size(data_path); if (bin_size > 0 && bin_size < 8192) { - std::ifstream bin_in(data_path, std::ios::binary); - if (bin_in.is_open()) { - std::stringstream buff; - buff << bin_in.rdbuf(); - server_message = buff.str(); + if (std::optional data = ReadFile(data_path)) { + server_message = std::move(*data); } } } diff --git a/geometry/test/meshcat_internal_test.cc b/geometry/test/meshcat_internal_test.cc new file mode 100644 index 000000000000..1b5bade1ecb4 --- /dev/null +++ b/geometry/test/meshcat_internal_test.cc @@ -0,0 +1,28 @@ +#include "drake/geometry/meshcat_internal.h" + +#include + +namespace drake { +namespace geometry { +namespace internal { +namespace { + +GTEST_TEST(MeshcatInternalTest, GetMeshcatStaticResource) { + // This matches the list of URLs in the API doc. + const std::vector urls{ + "/", "/favicon.ico", "/index.html", "/meshcat.html", + "/meshcat.js", "/stats.min.js", + }; + for (const auto& url : urls) { + SCOPED_TRACE(fmt::format("url = {}", url)); + const std::optional result = + GetMeshcatStaticResource(url); + ASSERT_TRUE(result); + EXPECT_FALSE(result->empty()); + } +} + +} // namespace +} // namespace internal +} // namespace geometry +} // namespace drake diff --git a/multibody/parsing/package_map.cc b/multibody/parsing/package_map.cc index 82752b8c725f..6fd9b5765601 100644 --- a/multibody/parsing/package_map.cc +++ b/multibody/parsing/package_map.cc @@ -7,7 +7,6 @@ #include #include #include -#include #include #include #include @@ -367,10 +366,7 @@ const std::string& PackageData::GetPathWithAutomaticFetching( const int returncode = std::system(command.c_str()); if (returncode != 0) { // Try to read the error message text from the downloader. - std::ifstream error_file(error_filename); - std::stringstream error_stream; - error_stream << error_file.rdbuf(); - std::string error = error_stream.str(); + std::string error = ReadFile(error_filename).value_or(""); if (error.empty()) { error = fmt::format("returncode == {}", returncode); } diff --git a/multibody/parsing/test/package_map_remote_test.cc b/multibody/parsing/test/package_map_remote_test.cc index a82e35d9cf9c..29a4557db26a 100644 --- a/multibody/parsing/test/package_map_remote_test.cc +++ b/multibody/parsing/test/package_map_remote_test.cc @@ -94,10 +94,7 @@ TEST_F(PackageMapRemoteTest, ActuallyFetch) { EXPECT_TRUE(fs::is_regular_file(readme_path)) << readme_path; // Double-check the file content. - std::ifstream readme(readme_path); - std::stringstream buffer; - buffer << readme.rdbuf(); - EXPECT_EQ(buffer.str(), "This package is empty.\n"); + EXPECT_EQ(ReadFileOrThrow(readme_path), "This package is empty.\n"); } // Fetch a remote zip file, then again with a different strip_prefix. diff --git a/multibody/parsing/test/parser_test.cc b/multibody/parsing/test/parser_test.cc index 7105f959faac..5f24c44c8454 100644 --- a/multibody/parsing/test/parser_test.cc +++ b/multibody/parsing/test/parser_test.cc @@ -1,8 +1,6 @@ #include "drake/multibody/parsing/parser.h" #include -#include -#include #include @@ -15,14 +13,6 @@ namespace drake { namespace multibody { namespace { -std::string ReadEntireFile(const std::string& file_name) { - std::ifstream input(file_name); - DRAKE_DEMAND(input.good()); - std::stringstream result; - result << input.rdbuf(); - return result.str(); -} - GTEST_TEST(FileParserTest, BasicTest) { const std::string sdf_name = FindResourceOrThrow( "drake/multibody/benchmarks/acrobot/acrobot.sdf"); @@ -131,7 +121,7 @@ GTEST_TEST(FileParserTest, BasicStringTest) { // Load an SDF via string using plural method. { - const std::string sdf_contents = ReadEntireFile(sdf_name); + const std::string sdf_contents = ReadFileOrThrow(sdf_name); MultibodyPlant plant(0.0); Parser dut(&plant); const std::vector ids = @@ -142,7 +132,7 @@ GTEST_TEST(FileParserTest, BasicStringTest) { // Load an URDF via string using plural method. { - const std::string urdf_contents = ReadEntireFile(urdf_name); + const std::string urdf_contents = ReadFileOrThrow(urdf_name); MultibodyPlant plant(0.0); Parser dut(&plant); const std::vector ids = @@ -153,7 +143,7 @@ GTEST_TEST(FileParserTest, BasicStringTest) { // Load an MJCF via string using plural method. { - const std::string xml_contents = ReadEntireFile(xml_name); + const std::string xml_contents = ReadFileOrThrow(xml_name); MultibodyPlant plant(0.0); Parser dut(&plant); const std::vector ids = @@ -164,7 +154,7 @@ GTEST_TEST(FileParserTest, BasicStringTest) { // Load a DMD.YAML via string using plural method. { - const std::string dmd_contents = ReadEntireFile(dmd_name); + const std::string dmd_contents = ReadFileOrThrow(dmd_name); MultibodyPlant plant(0.0); Parser dut(&plant); const std::vector ids = diff --git a/multibody/parsing/test/process_model_directives_test.cc b/multibody/parsing/test/process_model_directives_test.cc index 3c7dc91ff01a..3ab3692b0954 100644 --- a/multibody/parsing/test/process_model_directives_test.cc +++ b/multibody/parsing/test/process_model_directives_test.cc @@ -1,9 +1,7 @@ #include "drake/multibody/parsing/process_model_directives.h" #include -#include #include -#include #include #include @@ -98,12 +96,9 @@ GTEST_TEST(ProcessModelDirectivesTest, BasicSmokeTest) { // Smoke test of the most basic model directives, now loading from string. GTEST_TEST(ProcessModelDirectivesTest, FromString) { - std::ifstream file_stream( - FindResourceOrThrow(std::string(kTestDir) + "/add_scoped_sub.dmd.yaml")); - std::stringstream yaml; - yaml << file_stream.rdbuf(); ModelDirectives station_directives = - LoadModelDirectivesFromString(yaml.str()); + LoadModelDirectivesFromString(ReadFileOrThrow(FindResourceOrThrow( + std::string(kTestDir) + "/add_scoped_sub.dmd.yaml"))); const MultibodyPlant empty_plant(0.0); diff --git a/solvers/BUILD.bazel b/solvers/BUILD.bazel index bf3f93f90448..639313f989d8 100644 --- a/solvers/BUILD.bazel +++ b/solvers/BUILD.bazel @@ -806,6 +806,7 @@ drake_cc_variant_library( ], deps_enabled = [ "//math:eigen_sparse_triplet", + "//common:find_resource", "//common:scope_exit", "//common:scoped_singleton", "@gurobi//:gurobi_c", @@ -1718,6 +1719,7 @@ drake_cc_googletest( ":quadratic_program_examples", ":second_order_cone_program_examples", ":snopt_solver", + "//common:find_resource", "//common:temp_directory", "//common/test_utilities:eigen_matrix_compare", "//common/test_utilities:expect_throws_message", diff --git a/solvers/gurobi_solver.cc b/solvers/gurobi_solver.cc index 387dffa6b680..2d0dea3f32a7 100644 --- a/solvers/gurobi_solver.cc +++ b/solvers/gurobi_solver.cc @@ -24,6 +24,7 @@ #include "gurobi_c.h" #include "drake/common/drake_assert.h" +#include "drake/common/find_resource.h" #include "drake/common/scope_exit.h" #include "drake/common/scoped_singleton.h" #include "drake/common/text_logging.h" @@ -1084,12 +1085,7 @@ bool IsGrbLicenseFileLocalHost() { if (grb_license_file == nullptr) { return false; } - std::ifstream stream{grb_license_file}; - const std::string contents{std::istreambuf_iterator{stream}, - std::istreambuf_iterator{}}; - if (stream.fail()) { - return false; - } + const std::string contents = ReadFile(grb_license_file).value_or(""); return contents.find("HOSTID") != std::string::npos; } } // namespace diff --git a/solvers/test/snopt_solver_test.cc b/solvers/test/snopt_solver_test.cc index bf5b8e62ca40..f7dfb0b3f4fb 100644 --- a/solvers/test/snopt_solver_test.cc +++ b/solvers/test/snopt_solver_test.cc @@ -9,6 +9,7 @@ #include #include +#include "drake/common/find_resource.h" #include "drake/common/temp_directory.h" #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/common/test_utilities/expect_throws_message.h" @@ -367,22 +368,10 @@ GTEST_TEST(SnoptTest, MultiThreadTest) { if (!kUsingAsan) { // The print file contents should be the same for single vs multi. - std::string contents_single; - { - std::ifstream input(single_threaded[i].print_file, std::ios::binary); - ASSERT_TRUE(input); - std::stringstream buffer; - buffer << input.rdbuf(); - contents_single = buffer.str(); - } - std::string contents_multi; - { - std::ifstream input(multi_threaded[i].print_file, std::ios::binary); - ASSERT_TRUE(input); - std::stringstream buffer; - buffer << input.rdbuf(); - contents_multi = buffer.str(); - } + std::string contents_single = + ReadFileOrThrow(single_threaded[i].print_file); + std::string contents_multi = + ReadFileOrThrow(multi_threaded[i].print_file); for (auto* contents : {&contents_single, &contents_multi}) { // Scrub some volatile text output. *contents = std::regex_replace(*contents, std::regex("..... seconds"), @@ -390,11 +379,11 @@ GTEST_TEST(SnoptTest, MultiThreadTest) { *contents = std::regex_replace( *contents, std::regex(".Printer........................\\d"), "(Printer).............. ####"); - } - EXPECT_EQ(contents_single, contents_multi); } + EXPECT_EQ(contents_single, contents_multi); } } +} class AutoDiffOnlyCost final : public drake::solvers::Cost { public: