Skip to content

Commit

Permalink
autodiffxd tests: Establish heap use baselines (RobotLocomotion#14018)
Browse files Browse the repository at this point in the history
* autodiffxd tests: Establish heap use baselines

Relevant to: RobotLocomotion#13985

Extend and use LimitMalloc to measure and enforce heap use of AutoDiffXd
math operators. These limits will help clarify the effect of subsequent
changes on the implementation of AutoDiffXd.

Summary of changes

* LimitMalloc:
  * Add params() accessor and .min_num_allocations parameter
  * Adjust error messages for clarity
  * Extend unit tests to cover new features
  * Disarm automatically under leak sanitizer builds
* Introduce autodiffxd_heap_test
  * Add cases for global function overrides in autodiffxd.h
  • Loading branch information
rpoyner-tri authored Sep 9, 2020
1 parent 71dbe45 commit 84aba35
Show file tree
Hide file tree
Showing 5 changed files with 266 additions and 22 deletions.
8 changes: 8 additions & 0 deletions common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -627,6 +627,14 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "autodiffxd_heap_test",
deps = [
":autodiff",
"//common/test_utilities:limit_malloc",
],
)

drake_cc_googletest(
name = "autodiff_overloads_test",
deps = [
Expand Down
126 changes: 126 additions & 0 deletions common/test/autodiffxd_heap_test.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,126 @@
#include <gtest/gtest.h>

#include "drake/common/autodiff.h"
#include "drake/common/eigen_types.h"
#include "drake/common/test_utilities/limit_malloc.h"

using Eigen::VectorXd;

namespace drake {
namespace test {
namespace {

// Provide some autodiff variables that don't expire at scope end for test
// cases.
class AutoDiffXdHeapTest : public ::testing::Test {
protected:
AutoDiffXd x_{0.4, Eigen::VectorXd::Ones(3)};
AutoDiffXd y_{0.3, Eigen::VectorXd::Ones(3)};
};

// @note The test cases use a sum in function arguments to induce a temporary
// that can potentially be consumed by pass-by-value optimizations. As of this
// writing, none of the tested functions uses the optimization, so current heap
// counts are a baseline for the existing implementations.

// @note The tests cases use `volatile` variables to prevent optimizers from
// removing the tested function calls entirely. As of this writing, there is no
// evidence that the technique is strictly necessary. However, future
// implementations may be vulnerable to dead-code elimination.

TEST_F(AutoDiffXdHeapTest, Abs) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = abs(x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Abs2) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = abs2(x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Acos) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = acos(x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Asin) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = asin(x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Atan) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = atan(x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Atan2) {
LimitMalloc guard({.max_num_allocations = 8, .min_num_allocations = 8});
volatile auto v = atan2(x_ + y_, y_);
volatile auto w = atan2(x_, x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Cos) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = cos(x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Cosh) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = cosh(x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Exp) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = exp(x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Log) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = log(x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Min) {
LimitMalloc guard({.max_num_allocations = 4, .min_num_allocations = 4});
volatile auto v = min(x_ + y_, y_);
volatile auto w = min(x_, x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Max) {
LimitMalloc guard({.max_num_allocations = 4, .min_num_allocations = 4});
volatile auto v = max(x_ + y_, y_);
volatile auto w = max(x_, x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Pow) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = pow(x_ + y_, 2.0);
}

TEST_F(AutoDiffXdHeapTest, Sin) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = sin(x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Sinh) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = sinh(x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Sqrt) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = sqrt(x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Tan) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = tan(x_ + y_);
}

TEST_F(AutoDiffXdHeapTest, Tanh) {
LimitMalloc guard({.max_num_allocations = 2, .min_num_allocations = 2});
volatile auto v = tanh(x_ + y_);
}

} // namespace
} // namespace test
} // namespace drake
49 changes: 47 additions & 2 deletions common/test_utilities/limit_malloc.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,17 @@
#define DRAKE_NO_SANITIZE
#endif

// Declare this function here so its definition can follow the
// platform-specific enabling of observations.
static void EvaluateMinNumAllocations(int observed, int min_num_allocations);

// LimitMalloc does not work properly with leak sanitizer builds. Check this
// predicate and disarm to avoid erroneous results.
static bool IsLeakSanitizerBuild() {
static const bool is_lsan{!!std::getenv("LSAN_OPTIONS")};
return is_lsan;
}

namespace drake {
namespace test {
namespace {
Expand Down Expand Up @@ -45,6 +56,7 @@ class Monitor {
}

int num_allocations() const { return observed_num_allocations_.load(); }
const LimitMallocParams& params() const { return args_; }

private:
void ObserveAllocation();
Expand Down Expand Up @@ -140,6 +152,8 @@ class ActiveMonitor {
};

void Monitor::ObserveAllocation() {
if (IsLeakSanitizerBuild()) { return; }

bool failure = false;

// Check the allocation-call limit.
Expand All @@ -155,8 +169,9 @@ void Monitor::ObserveAllocation() {

// Report an error (but re-enable malloc before doing so!).
ActiveMonitor::reset();
std::cerr << "abort due to malloc #" << observed << " while LimitMalloc("
<< args_.max_num_allocations << ") in effect";
std::cerr << "abort due to malloc #" << observed
<< " while max_num_allocations = "
<< args_.max_num_allocations << " in effect";
std::cerr << std::endl;
// TODO(jwnimmer-tri) It would be nice to print a backtrace here.
std::abort();
Expand All @@ -167,6 +182,10 @@ void Monitor::ObserveAllocation() {
LimitMalloc::LimitMalloc() : LimitMalloc({ .max_num_allocations = 0 }) {}

LimitMalloc::LimitMalloc(LimitMallocParams args) {
// Make sure the leak-sanitizer check is warm before trying it within a
// malloc call stack.
IsLeakSanitizerBuild();

// Prepare a monitor with our requested limits.
auto monitor = std::make_shared<Monitor>(this, std::move(args));

Expand All @@ -181,12 +200,23 @@ int LimitMalloc::num_allocations() const {
return ActiveMonitor::load()->num_allocations();
}

const LimitMallocParams& LimitMalloc::params() const {
return ActiveMonitor::load()->params();
}

LimitMalloc::~LimitMalloc() {
// Copy out the monitor's data before we delete it.
const int observed = num_allocations();
const LimitMallocParams args = params();

// De-activate our Monitor.
auto prior = ActiveMonitor::reset();

if (!(prior && prior->has_owner(this))) {
std::cerr << "LimitMalloc dtor invariant failure\n";
}

::EvaluateMinNumAllocations(observed, args.min_num_allocations);
}

} // namespace test
Expand Down Expand Up @@ -215,6 +245,21 @@ void* realloc(void* ptr, size_t size) {
drake::test::ActiveMonitor::realloc(ptr, size, is_noop);
return result;
}

static void EvaluateMinNumAllocations(int observed, int min_num_allocations) {
if (IsLeakSanitizerBuild()) { return; }

if ((min_num_allocations >= 0) && (observed < min_num_allocations)) {
std::cerr << "abort due to scope end with "
<< observed << " mallocs while min_num_allocations = "
<< min_num_allocations << " in effect";
std::cerr << std::endl;
std::abort();
}
}
#else
// Evaluating the minimum is a no-op when no counts are observed.
static void EvaluateMinNumAllocations(int observed, int min_num_allocations) {}
#endif

#undef DRAKE_NO_SANITIZE
8 changes: 8 additions & 0 deletions common/test_utilities/limit_malloc.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,10 @@ struct LimitMallocParams {
/// When less than zero, there is no limit on the number of calls.
int max_num_allocations{-1};

/// Minimum calls to malloc, calloc, or realloc (totaled as one).
/// When less than zero, there is no limit on the number of calls.
int min_num_allocations{-1};

/// Whether a realloc() that leaves its `ptr` unchanged should be ignored.
bool ignore_realloc_noops{false};
};
Expand All @@ -17,6 +21,7 @@ struct LimitMallocParams {
/// etc.) should be disallowed or curtailed.
///
/// @note This class is currently a no-op on macOS.
/// @note This class is currently a no-op in leak sanitizer runs.
///
/// Example:
/// @code
Expand Down Expand Up @@ -58,6 +63,9 @@ class LimitMalloc final {
/// Returns the number of allocations observed so far.
int num_allocations() const;

/// Returns the parameters structure used to construct this object.
const LimitMallocParams& params() const;

// We write this out by hand, to avoid depending on Drake *at all*.
/// @name Does not allow copy, move, or assignment
//@{
Expand Down
Loading

0 comments on commit 84aba35

Please sign in to comment.