Skip to content

Commit

Permalink
attic: Remove uses of spruce (RobotLocomotion#12179)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Oct 10, 2019
1 parent 14b8a8d commit c9bef0e
Show file tree
Hide file tree
Showing 7 changed files with 20 additions and 21 deletions.
1 change: 1 addition & 0 deletions attic/manipulation/util/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ drake_cc_library(
"//attic/multibody:rigid_body_tree_construction",
"//attic/multibody/parsers",
"//attic/multibody/rigid_body_plant:compliant_contact_model",
"//common:filesystem",
"//common:find_resource",
],
)
Expand Down
7 changes: 2 additions & 5 deletions attic/manipulation/util/world_sim_tree_builder.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,7 @@
#include <map>
#include <utility>

#include <spruce.hh>

#include "drake/common/filesystem.h"
#include "drake/common/find_resource.h"
#include "drake/multibody/parsers/model_instance_id_table.h"
#include "drake/multibody/parsers/sdf_parser.h"
Expand Down Expand Up @@ -106,10 +105,8 @@ int WorldSimTreeBuilder<T>::AddModelInstanceToFrame(
auto it = model_map_.find(model_name);
DRAKE_THROW_UNLESS(it != model_map_.end());

spruce::path p(it->second);

// Converts the file extension to be lower case.
auto extension = p.extension();
string extension = filesystem::path(it->second).extension();
std::transform(extension.begin(), extension.end(), extension.begin(),
::tolower);

Expand Down
3 changes: 2 additions & 1 deletion attic/multibody/parsers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ drake_cc_googletest(
data = [":test_models"],
deps = [
":parsers",
"//common:filesystem",
"//common:find_resource",
],
)
Expand All @@ -83,8 +84,8 @@ drake_cc_googletest(
],
deps = [
":parsers",
"//common:filesystem",
"//common:find_resource",
"@spruce",
],
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
#include <string>

#include <gtest/gtest.h>
#include <spruce.hh>

#include "drake/common/filesystem.h"
#include "drake/common/find_resource.h"
#include "drake/multibody/joints/floating_base_types.h"
#include "drake/multibody/parsers/sdf_parser.h"
Expand Down Expand Up @@ -45,8 +45,7 @@ class DoublePendulumFramesTest : public ::testing::Test {

tree_ = make_unique<RigidBodyTree<double>>();

spruce::path spruce_path(file_name);
auto extension = spruce_path.extension();
string extension = filesystem::path(file_name).extension();
std::transform(extension.begin(), extension.end(), extension.begin(),
::tolower);
DRAKE_DEMAND(extension == ".urdf" || extension == ".sdf");
Expand Down
4 changes: 2 additions & 2 deletions attic/multibody/parsers/test/urdf_parser_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@
#include <string>

#include <gtest/gtest.h>
#include <spruce.hh>

#include "drake/common/filesystem.h"
#include "drake/common/find_resource.h"
#include "drake/multibody/joints/floating_base_types.h"
#include "drake/multibody/rigid_body_tree.h"
Expand Down Expand Up @@ -199,7 +199,7 @@ GTEST_TEST(URDFParserTest,
const string atlas_xml = FindResourceOrThrow(
"drake/examples/atlas/package.xml");
PackageMap package_map;
package_map.Add("Atlas", spruce::path(atlas_xml).root());
package_map.Add("Atlas", filesystem::path(atlas_xml).parent_path());

auto tree = make_unique<RigidBodyTree<double>>();
ASSERT_NO_THROW(AddModelInstanceFromUrdfFileSearchingInRosPackages(
Expand Down
2 changes: 1 addition & 1 deletion attic/multibody/shapes/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@ drake_cc_library(
visibility = ["//visibility:private"],
deps = [
"//common:essential",
"//common:filesystem",
"//common:unused",
"@spruce",
"@tinyobjloader",
],
)
Expand Down
19 changes: 10 additions & 9 deletions attic/multibody/shapes/geometry.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,13 @@
#include <algorithm>
#include <cstdio>
#include <fstream>
#include <iostream>
#include <stdexcept>

#include <spruce.hh>
#include <tiny_obj_loader.h>

#include "drake/common/drake_assert.h"
#include "drake/common/filesystem.h"
#include "drake/common/text_logging.h"

using std::ifstream;
Expand Down Expand Up @@ -274,27 +275,27 @@ bool Mesh::extractMeshVertices(Matrix3Xd& vertex_coordinates) const {
}

string Mesh::FindFileWithObjExtension() const {
spruce::path spath(resolved_filename_);
string ext = spath.extension();
drake::filesystem::path result(resolved_filename_);
string ext = result.extension();
std::transform(ext.begin(), ext.end(), ext.begin(), ::tolower);

if (ext.compare(".obj") == 0) {
// Checks if the file with the obj extension exists.
if (!spath.exists()) {
if (!drake::filesystem::exists(result)) {
throw std::runtime_error(
"Unable to open file \"" + spath.getStr() + "\".");
"Unable to open file \"" + result.string() + "\".");
}
} else {
// Tries changing the extension to obj.
spath.setExtension(".obj");
if (!spath.exists()) {
result.replace_extension(".obj");
if (!drake::filesystem::exists(result)) {
throw std::runtime_error(
"Unable to resolve an obj file from the filename \""
+ spath.getStr() + "\" provided.");
+ result.string() + "\" provided.");
}
}

return spath.getStr();
return result.string();
}

void Mesh::LoadObjFile(PointsVector* vertices, TrianglesVector* triangles,
Expand Down

0 comments on commit c9bef0e

Please sign in to comment.