Skip to content

Commit

Permalink
Add and use drake::temp_directory function instead of using /tmp
Browse files Browse the repository at this point in the history
  • Loading branch information
Jamie Snape committed Mar 29, 2018
1 parent 54dde2c commit 75e6bd8
Show file tree
Hide file tree
Showing 17 changed files with 126 additions and 15 deletions.
1 change: 1 addition & 0 deletions automotive/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -381,6 +381,7 @@ drake_cc_library(
":trajectory_car",
"//automotive/maliput/api",
"//automotive/maliput/utility",
"//common:temp_directory",
"//lcm",
"//multibody/parsers",
"//multibody/rigid_body_plant:drake_visualizer",
Expand Down
6 changes: 4 additions & 2 deletions automotive/automotive_simulator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include "drake/automotive/maliput/utility/generate_urdf.h"
#include "drake/automotive/prius_vis.h"
#include "drake/common/drake_throw.h"
#include "drake/common/temp_directory.h"
#include "drake/common/text_logging.h"
#include "drake/lcm/drake_lcm.h"
#include "drake/lcmt_viewer_draw.hpp"
Expand Down Expand Up @@ -443,10 +444,11 @@ void AutomotiveSimulator<T>::GenerateAndLoadRoadNetworkUrdf() {
std::string filename = road_->id().string();
std::transform(filename.begin(), filename.end(), filename.begin(),
[](char ch) { return ch == ' ' ? '_' : ch; });
const std::string tmpdir = drake::temp_directory();
maliput::utility::GenerateUrdfFile(road_.get(),
"/tmp", filename,
tmpdir, filename,
maliput::utility::ObjFeatures());
const std::string urdf_filepath = "/tmp/" + filename + ".urdf";
const std::string urdf_filepath = tmpdir + "/" + filename + ".urdf";
parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
urdf_filepath,
drake::multibody::joints::kFixed,
Expand Down
5 changes: 5 additions & 0 deletions bindings/pydrake/common_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#include "drake/common/drake_assertion_error.h"
#include "drake/common/drake_path.h"
#include "drake/common/find_resource.h"
#include "drake/common/temp_directory.h"

namespace drake {
namespace pydrake {
Expand Down Expand Up @@ -50,6 +51,10 @@ PYBIND11_MODULE(_common_py, m) {
"e.g., drake/examples/pendulum/Pendulum.urdf. Raises an exception "
"if the resource was not found.",
py::arg("resource_path"));
m.def("temp_directory", &temp_directory,
"Returns a directory location suitable for temporary files that is "
"the value of the environment variable TEST_TMPDIR if defined or "
"otherwise /tmp. Any trailing / will be stripped from the output.");
// Returns the fully-qualified path to the root of the `drake` source tree.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
Expand Down
9 changes: 7 additions & 2 deletions bindings/pydrake/test/common_test.py
Original file line number Diff line number Diff line change
@@ -1,11 +1,12 @@
from __future__ import absolute_import, division, print_function

import os
import unittest
import pydrake.common


class TestCommon(unittest.TestCase):
def testDrakeDemandThrows(self):
def test_drake_demand_throws(self):
# Drake's assertion errors should turn into SystemExit by default,
# without the user needing to do anything special. Here, we trigger a
# C++ assertion failure from Python and confirm that an exception with
Expand All @@ -23,7 +24,11 @@ def testDrakeDemandThrows(self):
" condition 'false' failed",
]))

def testDrakeFindResourceOrThrow(self):
def test_find_resource_or_throw(self):
pydrake.common.FindResourceOrThrow(
'drake/examples/atlas/urdf/atlas_convex_hull.urdf'
)

def test_temp_directory(self):
self.assertEqual(os.environ.get('TEST_TMPDIR'),
pydrake.common.temp_directory())
18 changes: 18 additions & 0 deletions common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ drake_cc_library(
":sorted_vectors_have_intersection",
":symbolic",
":symbolic_decompose",
":temp_directory",
":type_safe_index",
":unused",
],
Expand Down Expand Up @@ -355,6 +356,16 @@ drake_cc_library(
],
)

drake_cc_library(
name = "temp_directory",
srcs = ["temp_directory.cc"],
hdrs = ["temp_directory.h"],
deps = [
":essential",
"@spruce",
],
)

drake_cc_library(
name = "text_logging_gflags",
hdrs = ["text_logging_gflags.h"],
Expand Down Expand Up @@ -942,6 +953,13 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "temp_directory_test",
deps = [
":temp_directory",
],
)

drake_cc_googletest(
name = "text_logging_test",
deps = [
Expand Down
2 changes: 2 additions & 0 deletions common/proto/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ drake_cc_library(
deps = [
":matlab_rpc",
"//common:essential",
"//common:temp_directory",
],
)

Expand All @@ -55,6 +56,7 @@ drake_cc_library(
deps = [
":call_matlab",
"//common:copyable_unique_ptr",
"//common:temp_directory",
],
)

Expand Down
4 changes: 3 additions & 1 deletion common/proto/call_matlab.cc
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@

#include "drake/common/drake_assert.h"
#include "drake/common/never_destroyed.h"
#include "drake/common/temp_directory.h"

namespace drake {
namespace common {
Expand Down Expand Up @@ -117,7 +118,8 @@ CreateOutputStream(const std::string& filename) {

void PublishCallMatlab(const MatlabRPC& message) {
// TODO(russt): Provide option for setting the filename.
static auto raw_output = CreateOutputStream("/tmp/matlab_rpc");
const std::string output_file = temp_directory() + "/matlab_rpc";
static auto raw_output = CreateOutputStream(output_file);
PublishCall(raw_output.get(), message);
}

Expand Down
6 changes: 3 additions & 3 deletions common/proto/call_python.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include <memory>

#include "drake/common/proto/matlab_rpc.pb.h"
#include "drake/common/temp_directory.h"

namespace drake {
namespace common {
Expand All @@ -27,14 +28,13 @@ void ToMatlabArray(const PythonRemoteVariable& var, MatlabArray* matlab_array) {

namespace {

const char kFilenameDefault[] = "/tmp/python_rpc";

auto GetPythonOutputStream(const std::string* filename = nullptr) {
static std::unique_ptr<google::protobuf::io::FileOutputStream> raw_output;
if (!raw_output) {
// If we do not yet have a file, create it.
const std::string filename_default = temp_directory() + "/python_rpc";
raw_output =
internal::CreateOutputStream(filename ? *filename : kFilenameDefault);
internal::CreateOutputStream(filename ? *filename : filename_default);
} else {
// If we already have a file, ensure that this does not come from
// `CallPythonInit`.
Expand Down
7 changes: 3 additions & 4 deletions common/proto/call_python_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -242,9 +242,6 @@ def magic(N):
locals())


_FILENAME_DEFAULT = "/tmp/python_rpc"


class CallPythonClient(object):
"""Provides a client to receive Python commands.
Expand All @@ -255,7 +252,9 @@ def __init__(self, filename=None, stop_on_error=True,
scope_globals=None, scope_locals=None,
threaded=True, wait=False):
if filename is None:
self.filename = _FILENAME_DEFAULT
# TODO(jamiesnape): Use drake.common.temp_directory.
temp_directory = os.environ.get("TEST_TMPDIR", "/tmp")
self.filename = os.path.join(temp_directory, "python_rpc")
else:
self.filename = filename
# Scope. Give it access to everything here.
Expand Down
2 changes: 1 addition & 1 deletion common/proto/test/call_python_full_test.sh
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ cc_bin=${cur}/call_python_test
py_client_cli=${cur}/call_python_client_cli
# TODO(eric.cousineau): Use `tempfile` once we can choose which file C++
# uses.
filename=$(mktemp)
filename="${TEST_TMPDIR}/python_rpc"
done_file=${filename}_done

cc_bin_flags=
Expand Down
24 changes: 24 additions & 0 deletions common/temp_directory.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
#include "drake/common/temp_directory.h"

#include <cstdlib>

#include <spruce.hh>

#include "drake/common/drake_throw.h"

namespace drake {

std::string temp_directory() {
// TODO(jamiesnape): Use mkdtemp instead of simply returning /tmp for
// applications that do not require a hardcoded /tmp.
const char* path_str = nullptr;
(path_str = std::getenv("TEST_TMPDIR")) || (path_str = "/tmp");

// Spruce normalizes the path and strips any trailing /.
spruce::path path(path_str);
DRAKE_THROW_UNLESS(path.isDir());

return path.getStr();
}

} // namespace drake
14 changes: 14 additions & 0 deletions common/temp_directory.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
#pragma once

#include <string>

namespace drake {

/// Returns a directory location suitable for temporary files.
/// @return The value of the environment variable TEST_TMPDIR if defined or
/// otherwise /tmp. Any trailing / will be stripped from the output.
/// @throws std::runtime_error If the path referred to by TEST_TMPDIR or /tmp
/// does not exist or is not a directory.
std::string temp_directory();

} // namespace drake
35 changes: 35 additions & 0 deletions common/test/temp_directory_test.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
#include "drake/common/temp_directory.h"

#include <cstdlib>
#include <string>

#include <gtest/gtest.h>

namespace drake {
namespace {

GTEST_TEST(TempDirectoryTest, TestTmpdirSet) {
const char* test_tmpdir = std::getenv("TEST_TMPDIR");
ASSERT_STRNE(nullptr, test_tmpdir);

const std::string temp_directory_with_test_tmpdir_set = temp_directory();
EXPECT_NE('/', temp_directory_with_test_tmpdir_set.back());
EXPECT_EQ(std::string(test_tmpdir), temp_directory_with_test_tmpdir_set);
}

GTEST_TEST(TempDirectoryTest, TestTmpdirUnset) {
const char* test_tmpdir = std::getenv("TEST_TMPDIR");
ASSERT_STRNE(nullptr, test_tmpdir);

const int unset_result = ::unsetenv("TEST_TMPDIR");
ASSERT_EQ(0, unset_result);

const std::string temp_directory_with_test_tmpdir_unset = temp_directory();
EXPECT_EQ("/tmp", temp_directory_with_test_tmpdir_unset);

const int setenv_result = ::setenv("TEST_TMPDIR", test_tmpdir, 1);
ASSERT_EQ(0, setenv_result);
}

} // namespace
} // namespace drake
3 changes: 2 additions & 1 deletion matlab/call_matlab_client.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

#include "drake/common/drake_assert.h"
#include "drake/common/proto/matlab_rpc.pb.h"
#include "drake/common/temp_directory.h"
#include "drake/common/unused.h"

namespace {
Expand Down Expand Up @@ -101,7 +102,7 @@ void mexFunction(int nlhs, mxArray* plhs[], int nrhs, const mxArray* prhs[]) {
drake::unused(nlhs);
drake::unused(plhs);

std::string filename = "/tmp/matlab_rpc";
std::string filename = drake::temp_directory() + "/matlab_rpc";

if (nrhs == 1) {
filename = mxGetStdString(prhs[0]);
Expand Down
1 change: 1 addition & 0 deletions solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -1117,6 +1117,7 @@ drake_cc_googletest(
":mathematical_program_test_util",
":optimization_examples",
":quadratic_program_examples",
"//common:temp_directory",
"//common/test_utilities:eigen_matrix_compare",
"@spruce",
],
Expand Down
3 changes: 2 additions & 1 deletion solvers/test/snopt_solver_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include <gtest/gtest.h>
#include <spruce.hh>

#include "drake/common/temp_directory.h"
#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/solvers/mathematical_program.h"
#include "drake/solvers/test/linear_program_examples.h"
Expand Down Expand Up @@ -88,7 +89,7 @@ GTEST_TEST(SnoptTest, TestSetOption) {
EXPECT_EQ(result, SolutionResult::kIterationLimit);

// This is to verify we can set the print out file.
std::string print_file = std::string(::getenv("TEST_TMPDIR")) + "/snopt.out";
std::string print_file = temp_directory() + "/snopt.out";
std::cout << print_file << std::endl;
EXPECT_FALSE(spruce::path(print_file).exists());
prog.SetSolverOption(SnoptSolver::id(), "Print file", print_file);
Expand Down
1 change: 1 addition & 0 deletions tools/install/libdrake/build_components.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,7 @@ LIBDRAKE_COMPONENTS = [
"//common:sorted_vectors_have_intersection",
"//common:symbolic",
"//common:symbolic_decompose",
"//common:temp_directory",
"//common:text_logging_gflags_h",
"//common:type_safe_index",
"//common:unused",
Expand Down

0 comments on commit 75e6bd8

Please sign in to comment.