forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
drake_assert_and_throw.cc
87 lines (76 loc) · 2.67 KB
/
drake_assert_and_throw.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
// This file contains the implementation of both drake_assert and drake_throw.
/* clang-format off to disable clang-format-includes */
#include "drake/common/drake_assert.h"
#include "drake/common/drake_throw.h"
/* clang-format on */
#include <atomic>
#include <cstdlib>
#include <iostream>
#include <sstream>
#include <stdexcept>
#include <string>
#include "drake/common/drake_assertion_error.h"
#include "drake/common/never_destroyed.h"
namespace drake {
namespace internal {
namespace {
// Singleton to manage assertion configuration.
struct AssertionConfig {
static AssertionConfig& singleton() {
static never_destroyed<AssertionConfig> global;
return global.access();
}
std::atomic<bool> assertion_failures_are_exceptions;
};
// Stream into @p out the given failure details; only @p condition may be null.
void PrintFailureDetailTo(std::ostream& out, const char* condition,
const char* func, const char* file, int line) {
out << "Failure at " << file << ":" << line << " in " << func << "()";
if (condition) {
out << ": condition '" << condition << "' failed.";
} else {
out << ".";
}
}
} // namespace
// Declared in drake_assert.h.
void Abort(const char* condition, const char* func, const char* file,
int line) {
std::cerr << "abort: ";
PrintFailureDetailTo(std::cerr, condition, func, file, line);
std::cerr << std::endl;
std::abort();
}
// Declared in drake_throw.h.
void Throw(const char* condition, const char* func, const char* file,
int line) {
std::ostringstream what;
PrintFailureDetailTo(what, condition, func, file, line);
throw assertion_error(what.str().c_str());
}
// Declared in drake_assert.h.
void AssertionFailed(const char* condition, const char* func, const char* file,
int line) {
if (AssertionConfig::singleton().assertion_failures_are_exceptions) {
Throw(condition, func, file, line);
} else {
Abort(condition, func, file, line);
}
}
} // namespace internal
} // namespace drake
// Configures the DRAKE_ASSERT and DRAKE_DEMAND assertion failure handling
// behavior.
//
// By default, assertion failures will result in an ::abort(). If this method
// has ever been called, failures will result in a thrown exception instead.
//
// Assertion configuration has process-wide scope. Changes here will affect
// all assertions within the current process.
//
// This method is intended ONLY for use by pydrake bindings, and thus is not
// declared in any header file, to discourage anyone from using it.
extern "C" void drake_set_assertion_failure_to_throw_exception() {
drake::internal::AssertionConfig::singleton().
assertion_failures_are_exceptions = true;
}