Upgrade WPILib and upgraded compilers to C++17
I haven't touched the CTRE libraries yet, although they may need to be
upgraded as well.
Note that this change makes it so that you need either Ubuntu 18.04 or
later or debian buster or later in order to build the code (you may be
able to build code for the roborio on older operating systems, but
running the tests will not work normally).
Change-Id: I0cfa37fe37f830edde6d305e1f50414c369098e4
diff --git a/WORKSPACE b/WORKSPACE
index b6b51eb..34d12e3 100644
--- a/WORKSPACE
+++ b/WORKSPACE
@@ -84,10 +84,10 @@
)
http_archive(
- name = "clang_3p6_repo",
- build_file = "@//tools/cpp/clang_3p6:clang_3p6.BUILD",
- sha256 = "5ee9e04c55c2c99d0c0f83722102a49e98f485fc274f73111b33a7ac4e34e03e",
- url = "http://www.frc971.org/Build-Dependencies/clang_3p6.tar.gz",
+ name = "clang_6p0_repo",
+ build_file = "@//tools/cpp/clang_6p0:clang_6p0.BUILD",
+ sha256 = "7c5dc0f124fbd26e440797a851466e7f852da27d9f1562c74059b5a34c294cc9",
+ url = "http://frc971.org/Build-Dependencies/clang_6p0.tar.gz",
)
local_repository(
@@ -127,20 +127,21 @@
http_archive(
name = "arm_frc_linux_gnueabi_repo",
build_file = "@//tools/cpp/arm-frc-linux-gnueabi:arm-frc-linux-gnueabi.BUILD",
- sha256 = "d627c5e437db99780a938392499ef71aecbfb0e9b3fffd53bde7e402a6af4f32",
- strip_prefix = "frc2019/roborio/",
- url = "http://www.frc971.org/Build-Dependencies/FRC-2019-Linux-Toolchain-6.3.0-v2019-3.tar.gz",
+ sha256 = "043a5b047c2af9cf80d146d8327b588264c98a01e0f3f41e3564dd2bbbc95c0e",
+ strip_prefix = "frc2020/roborio/",
+ url = "http://frc971.org/Build-Dependencies/FRC-2020-Linux-Toolchain-7.3.0.tar.gz",
)
# Recompressed version of the one downloaded from Linaro at
-# <https://releases.linaro.org/15.05/components/toolchain/binaries/arm-linux-gnueabihf/gcc-linaro-4.9-2015.05-x86_64_arm-linux-gnueabihf.tar.xz>,
+# <https://releases.linaro.org/components/toolchain/binaries/7.4-2019.02/arm-linux-gnueabihf/gcc-linaro-7.4.1-2019.02-x86_64_arm-linux-gnueabihf.tar.xz>
# with workarounds for <https://github.com/bazelbuild/bazel/issues/574> and the
# top-level folder stripped off.
http_archive(
- name = "linaro_linux_gcc_4_9_repo",
- build_file = "@//:compilers/linaro_linux_gcc_4.9.BUILD",
- sha256 = "25e97bcb0af4fd7cd626d5bb1b303c7d2cb13acf2474e335e3d431d1a53fbb52",
- url = "http://www.frc971.org/Build-Dependencies/gcc-linaro-4.9-2015.05-x86_64_arm-linux-gnueabihf.tar.gz",
+ name = "linaro_linux_gcc_repo",
+ build_file = "@//:compilers/linaro_linux_gcc.BUILD",
+ sha256 = "3c951cf1941d0fa06d64cc0d5e88612b209d8123b273fa26c16d70bd7bc6b163",
+ strip_prefix = "gcc-linaro-7.4.1-2019.02-x86_64_arm-linux-gnueabihf",
+ url = "http://frc971.org/Build-Dependencies/gcc-linaro-7.4.1-2019.02-x86_64_arm-linux-gnueabihf.tar.xz",
)
new_git_repository(
@@ -175,12 +176,13 @@
# Generated with:
# git fetch https://github.com/wpilibsuite/ni-libraries master
-# git archive --output=allwpilib_ni-libraries_4785480.tar.gz --format=tar.gz 4785480
+# git archive --output=allwpilib_ni-libraries_89316203.tar.gz --format=tar.gz 89316203
http_archive(
name = "allwpilib_ni_libraries_2019",
build_file = "@//debian:ni-libraries-2019.BUILD",
- sha256 = "2cdcde3391f36877b7533e15d0f36baf696b27c1107b77192a8200e26f13278c",
- url = "http://www.frc971.org/Build-Dependencies/allwpilib_ni-libraries_4785480.tar.gz",
+ sha256 = "09232c6207168dbeafb815f8249940ad3aa46b9176b58e760c5a5233cb15c381",
+ strip_prefix = "ni-libraries-893162037bb36c6171e14be15c6cef9be0053c4a",
+ url = "http://frc971.org/Build-Dependencies/allwpilib_ni-libraries_89316203.zip",
)
# Downloaded from:
diff --git a/aos/actions/actor.h b/aos/actions/actor.h
index f5629a6..3cc4d9e 100644
--- a/aos/actions/actor.h
+++ b/aos/actions/actor.h
@@ -132,6 +132,7 @@
}
break;
}
+ [[fallthrough]];
case State::RUNNING_ACTION: {
++running_count_;
const uint32_t running_id = goal.run();
diff --git a/aos/configuration.cc b/aos/configuration.cc
index bcb67ba..c7fa2a3 100644
--- a/aos/configuration.cc
+++ b/aos/configuration.cc
@@ -7,9 +7,9 @@
#include <arpa/inet.h>
#include <ifaddrs.h>
#include <unistd.h>
+#include <string_view>
#include "absl/container/btree_set.h"
-#include "absl/strings/string_view.h"
#include "aos/configuration_generated.h"
#include "aos/flatbuffer_merge.h"
#include "aos/json_to_flatbuffer.h"
@@ -139,16 +139,17 @@
}
// Extracts the folder part of a path. Returns ./ if there is no path.
-absl::string_view ExtractFolder(const absl::string_view filename) {
+std::string_view ExtractFolder(
+ const std::string_view filename) {
auto last_slash_pos = filename.find_last_of("/\\");
- return last_slash_pos == absl::string_view::npos
- ? absl::string_view("./")
+ return last_slash_pos == std::string_view::npos
+ ? std::string_view("./")
: filename.substr(0, last_slash_pos + 1);
}
FlatbufferDetachedBuffer<Configuration> ReadConfig(
- const absl::string_view path, absl::btree_set<std::string> *visited_paths) {
+ const std::string_view path, absl::btree_set<std::string> *visited_paths) {
flatbuffers::DetachedBuffer buffer = JsonToFlatbuffer(
util::ReadFileToStringOrDie(path), ConfigurationTypeTable());
@@ -223,7 +224,7 @@
// Compares (c < p) a channel, and a name, type tuple.
bool CompareChannels(const Channel *c,
- ::std::pair<absl::string_view, absl::string_view> p) {
+ ::std::pair<std::string_view, std::string_view> p) {
int name_compare = c->name()->string_view().compare(p.first);
if (name_compare == 0) {
return c->type()->string_view() < p.second;
@@ -236,24 +237,24 @@
// Compares for equality (c == p) a channel, and a name, type tuple.
bool EqualsChannels(const Channel *c,
- ::std::pair<absl::string_view, absl::string_view> p) {
+ ::std::pair<std::string_view, std::string_view> p) {
return c->name()->string_view() == p.first &&
c->type()->string_view() == p.second;
}
// Compares (c < p) an application, and a name;
-bool CompareApplications(const Application *a, absl::string_view name) {
+bool CompareApplications(const Application *a, std::string_view name) {
return a->name()->string_view() < name;
};
// Compares for equality (c == p) an application, and a name;
-bool EqualsApplications(const Application *a, absl::string_view name) {
+bool EqualsApplications(const Application *a, std::string_view name) {
return a->name()->string_view() == name;
}
// Maps name for the provided maps. Modifies name.
void HandleMaps(const flatbuffers::Vector<flatbuffers::Offset<aos::Map>> *maps,
- absl::string_view *name) {
+ std::string_view *name) {
// For the same reason we merge configs in reverse order, we want to process
// maps in reverse order. That lets the outer config overwrite channels from
// the inner configs.
@@ -384,15 +385,15 @@
}
FlatbufferDetachedBuffer<Configuration> ReadConfig(
- const absl::string_view path) {
+ const std::string_view path) {
// We only want to read a file once. So track the visited files in a set.
absl::btree_set<std::string> visited_paths;
return MergeConfiguration(ReadConfig(path, &visited_paths));
}
-const Channel *GetChannel(const Configuration *config, absl::string_view name,
- absl::string_view type,
- absl::string_view application_name) {
+const Channel *GetChannel(const Configuration *config, std::string_view name,
+ std::string_view type,
+ std::string_view application_name) {
VLOG(1) << "Looking up { \"name\": \"" << name << "\", \"type\": \"" << type
<< "\" }";
diff --git a/aos/configuration.h b/aos/configuration.h
index e777f41..b837391 100644
--- a/aos/configuration.h
+++ b/aos/configuration.h
@@ -6,7 +6,8 @@
#include <netinet/in.h>
#include <arpa/inet.h>
-#include "absl/strings/string_view.h"
+#include <string_view>
+
#include "aos/configuration_generated.h"
#include "aos/flatbuffers.h"
@@ -19,7 +20,7 @@
// Reads a json configuration. This includes all imports and merges. Note:
// duplicate imports will result in a CHECK.
FlatbufferDetachedBuffer<Configuration> ReadConfig(
- const absl::string_view path);
+ const std::string_view path);
// Sorts and merges entries in a config.
FlatbufferDetachedBuffer<Configuration> MergeConfiguration(
@@ -36,14 +37,15 @@
//
// If the application name is empty, it is ignored. Maps are processed in
// reverse order, and application specific first.
-const Channel *GetChannel(const Configuration *config,
- const absl::string_view name,
- const absl::string_view type,
- const absl::string_view application_name);
-inline const Channel *GetChannel(const Flatbuffer<Configuration> &config,
- const absl::string_view name,
- const absl::string_view type,
- const absl::string_view application_name) {
+const Channel *GetChannel(
+ const Configuration *config, const std::string_view name,
+ const std::string_view type,
+ const std::string_view application_name);
+inline const Channel *GetChannel(
+ const Flatbuffer<Configuration> &config,
+ const std::string_view name,
+ const std::string_view type,
+ const std::string_view application_name) {
return GetChannel(&config.message(), name, type, application_name);
}
diff --git a/aos/controls/control_loop_test.h b/aos/controls/control_loop_test.h
index b8ebc67..6a8e975 100644
--- a/aos/controls/control_loop_test.h
+++ b/aos/controls/control_loop_test.h
@@ -26,7 +26,7 @@
public:
// Builds a control loop test with the provided configuration. Note: this
// merges and sorts the config to reduce user errors.
- ControlLoopTestTemplated(absl::string_view configuration,
+ ControlLoopTestTemplated(std::string_view configuration,
::std::chrono::nanoseconds dt = kTimeTick)
: ControlLoopTestTemplated(
configuration::MergeConfiguration(
diff --git a/aos/events/event_loop.h b/aos/events/event_loop.h
index 34e55a8..fde7273 100644
--- a/aos/events/event_loop.h
+++ b/aos/events/event_loop.h
@@ -3,8 +3,8 @@
#include <atomic>
#include <string>
+#include <string_view>
-#include "absl/strings/string_view.h"
#include "aos/configuration.h"
#include "aos/configuration_generated.h"
#include "aos/flatbuffers.h"
@@ -79,7 +79,7 @@
virtual bool Send(const void *data, size_t size) = 0;
// Returns the name of this sender.
- virtual const absl::string_view name() const = 0;
+ virtual const std::string_view name() const = 0;
const Channel *channel() const { return channel_; }
@@ -175,7 +175,7 @@
Builder MakeBuilder();
// Returns the name of the underlying queue.
- const absl::string_view name() const { return sender_->name(); }
+ const std::string_view name() const { return sender_->name(); }
private:
friend class EventLoop;
@@ -231,7 +231,7 @@
// Makes a class that will always fetch the most recent value
// sent to the provided channel.
template <typename T>
- Fetcher<T> MakeFetcher(const absl::string_view channel_name) {
+ Fetcher<T> MakeFetcher(const std::string_view channel_name) {
const Channel *channel = configuration::GetChannel(
configuration_, channel_name, T::GetFullyQualifiedName(), name());
CHECK(channel != nullptr)
@@ -244,7 +244,7 @@
// Makes class that allows constructing and sending messages to
// the provided channel.
template <typename T>
- Sender<T> MakeSender(const absl::string_view channel_name) {
+ Sender<T> MakeSender(const std::string_view channel_name) {
const Channel *channel = configuration::GetChannel(
configuration_, channel_name, T::GetFullyQualifiedName(), name());
CHECK(channel != nullptr)
@@ -262,16 +262,16 @@
// TODO(parker): Need to support ::std::bind. For now, use lambdas.
// TODO(austin): Do we need a functor? Or is a std::function good enough?
template <typename Watch>
- void MakeWatcher(const absl::string_view name, Watch &&w);
+ void MakeWatcher(const std::string_view name, Watch &&w);
// The passed in function will be called when the event loop starts.
// Use this to run code once the thread goes into "real-time-mode",
virtual void OnRun(::std::function<void()> on_run) = 0;
// Sets the name of the event loop. This is the application name.
- virtual void set_name(const absl::string_view name) = 0;
+ virtual void set_name(const std::string_view name) = 0;
// Gets the name of the event loop.
- virtual const absl::string_view name() const = 0;
+ virtual const std::string_view name() const = 0;
// Creates a timer that executes callback when the timer expires
// Returns a TimerHandle for configuration of the timer
diff --git a/aos/events/event_loop_tmpl.h b/aos/events/event_loop_tmpl.h
index 9910d4d..bfd9775 100644
--- a/aos/events/event_loop_tmpl.h
+++ b/aos/events/event_loop_tmpl.h
@@ -27,7 +27,7 @@
}
template <typename Watch>
-void EventLoop::MakeWatcher(const absl::string_view channel_name, Watch &&w) {
+void EventLoop::MakeWatcher(const std::string_view channel_name, Watch &&w) {
using T = typename watch_message_type_trait<Watch>::message_type;
const Channel *channel = configuration::GetChannel(
configuration_, channel_name, T::GetFullyQualifiedName(), name());
diff --git a/aos/events/shm_event_loop.cc b/aos/events/shm_event_loop.cc
index 8fed31e..c05187b 100644
--- a/aos/events/shm_event_loop.cc
+++ b/aos/events/shm_event_loop.cc
@@ -101,12 +101,12 @@
}
private:
- void MkdirP(absl::string_view path) {
+ void MkdirP(std::string_view path) {
struct stat st;
auto last_slash_pos = path.find_last_of("/");
- std::string folder(last_slash_pos == absl::string_view::npos
- ? absl::string_view("")
+ std::string folder(last_slash_pos == std::string_view::npos
+ ? std::string_view("")
: path.substr(0, last_slash_pos));
if (stat(folder.c_str(), &st) == -1) {
PCHECK(errno == ENOENT);
@@ -126,10 +126,10 @@
};
// Returns the portion of the path after the last /.
-absl::string_view Filename(absl::string_view path) {
+std::string_view Filename(std::string_view path) {
auto last_slash_pos = path.find_last_of("/");
- return last_slash_pos == absl::string_view::npos
+ return last_slash_pos == std::string_view::npos
? path
: path.substr(last_slash_pos + 1, path.size());
}
@@ -297,7 +297,7 @@
return true;
}
- const absl::string_view name() const override { return name_; }
+ const std::string_view name() const override { return name_; }
private:
const ShmEventLoop *shm_event_loop_;
diff --git a/aos/events/shm_event_loop.h b/aos/events/shm_event_loop.h
index e859201..577a98d 100644
--- a/aos/events/shm_event_loop.h
+++ b/aos/events/shm_event_loop.h
@@ -59,10 +59,10 @@
void SetRuntimeRealtimePriority(int priority) override;
- void set_name(const absl::string_view name) override {
+ void set_name(const std::string_view name) override {
name_ = std::string(name);
}
- const absl::string_view name() const override { return name_; }
+ const std::string_view name() const override { return name_; }
int priority() const { return priority_; }
diff --git a/aos/events/simulated_event_loop.cc b/aos/events/simulated_event_loop.cc
index d374bb7..f65e75d 100644
--- a/aos/events/simulated_event_loop.cc
+++ b/aos/events/simulated_event_loop.cc
@@ -144,7 +144,7 @@
return Send(size);
}
- const absl::string_view name() const override {
+ const std::string_view name() const override {
return simulated_channel_->name();
}
@@ -368,10 +368,10 @@
scheduler_->Schedule(scheduler_->monotonic_now(), on_run);
}
- void set_name(const absl::string_view name) override {
+ void set_name(const std::string_view name) override {
name_ = std::string(name);
}
- const absl::string_view name() const override { return name_; }
+ const std::string_view name() const override { return name_; }
SimulatedChannel *GetSimulatedChannel(const Channel *channel);
diff --git a/aos/flatbuffers.h b/aos/flatbuffers.h
index fc91cf9..b48dc1f 100644
--- a/aos/flatbuffers.h
+++ b/aos/flatbuffers.h
@@ -2,8 +2,8 @@
#define AOS_FLATBUFFERS_H_
#include <array>
+#include <string_view>
-#include "absl/strings/string_view.h"
#include "flatbuffers/flatbuffers.h"
namespace aos {
@@ -127,7 +127,7 @@
class FlatbufferString : public Flatbuffer<T> {
public:
// Builds a flatbuffer using the contents of the string.
- FlatbufferString(const absl::string_view data) : data_(data) {}
+ FlatbufferString(const std::string_view data) : data_(data) {}
// Builds a Flatbuffer by copying the data from the other flatbuffer.
FlatbufferString(const Flatbuffer<T> &other) {
data_ = std::string(other.data(), other.size());
@@ -161,7 +161,7 @@
// From a usage point of view, pointers to the data are very different than
// pointers to the tables.
template <typename T>
-class FlatbufferDetachedBuffer : public Flatbuffer<T> {
+class FlatbufferDetachedBuffer final : public Flatbuffer<T> {
public:
// Builds a Flatbuffer by taking ownership of the buffer.
FlatbufferDetachedBuffer(flatbuffers::DetachedBuffer &&buffer)
diff --git a/aos/ipc_lib/lockless_queue_death_test.cc b/aos/ipc_lib/lockless_queue_death_test.cc
index 4f1d7e4..6b3f7c5 100644
--- a/aos/ipc_lib/lockless_queue_death_test.cc
+++ b/aos/ipc_lib/lockless_queue_death_test.cc
@@ -8,6 +8,7 @@
#include <unistd.h>
#include <wait.h>
#include <chrono>
+#include <functional>
#include <memory>
#include <thread>
diff --git a/aos/json_to_flatbuffer.cc b/aos/json_to_flatbuffer.cc
index 34cdffe..9549c1f 100644
--- a/aos/json_to_flatbuffer.cc
+++ b/aos/json_to_flatbuffer.cc
@@ -3,7 +3,8 @@
#include <cstddef>
#include "stdio.h"
-#include "absl/strings/string_view.h"
+#include <string_view>
+
#include "aos/flatbuffer_utils.h"
#include "aos/json_tokenizer.h"
#include "flatbuffers/flatbuffers.h"
@@ -124,7 +125,7 @@
// Parses the json into a flatbuffer. Returns either an empty vector on
// error, or a vector with the flatbuffer data in it.
- flatbuffers::DetachedBuffer Parse(const absl::string_view data,
+ flatbuffers::DetachedBuffer Parse(const std::string_view data,
const flatbuffers::TypeTable *typetable) {
flatbuffers::uoffset_t end = 0;
bool result = DoParse(typetable, data, &end);
@@ -149,7 +150,8 @@
// Parses the flatbuffer. This is a second method so we can do easier
// cleanup at the top level. Returns true on success.
bool DoParse(const flatbuffers::TypeTable *typetable,
- const absl::string_view data, flatbuffers::uoffset_t *table_end);
+ const std::string_view data,
+ flatbuffers::uoffset_t *table_end);
// Adds *_value for the provided field. If we are in a vector, queues the
// data up in vector_elements. Returns true on success.
@@ -200,7 +202,7 @@
};
bool JsonParser::DoParse(const flatbuffers::TypeTable *typetable,
- const absl::string_view data,
+ const std::string_view data,
flatbuffers::uoffset_t *table_end) {
::std::vector<const flatbuffers::TypeTable *> stack;
@@ -765,7 +767,8 @@
} // namespace
flatbuffers::DetachedBuffer JsonToFlatbuffer(
- const absl::string_view data, const flatbuffers::TypeTable *typetable) {
+ const std::string_view data,
+ const flatbuffers::TypeTable *typetable) {
JsonParser p;
return p.Parse(data, typetable);
}
diff --git a/aos/json_to_flatbuffer.h b/aos/json_to_flatbuffer.h
index 183e6b2..94b982a 100644
--- a/aos/json_to_flatbuffer.h
+++ b/aos/json_to_flatbuffer.h
@@ -3,8 +3,8 @@
#include <cstddef>
#include <string>
+#include <string_view>
-#include "absl/strings/string_view.h"
#include "aos/flatbuffers.h"
#include "flatbuffers/flatbuffers.h"
@@ -12,7 +12,8 @@
// Parses the flatbuffer into the vector, or returns an empty vector.
flatbuffers::DetachedBuffer JsonToFlatbuffer(
- const absl::string_view data, const flatbuffers::TypeTable *typetable);
+ const std::string_view data,
+ const flatbuffers::TypeTable *typetable);
// Converts a flatbuffer into a Json string.
// multi_line controls if the Json is written out on multiple lines or one.
diff --git a/aos/json_tokenizer.cc b/aos/json_tokenizer.cc
index e3aa7ea..aa92762 100644
--- a/aos/json_tokenizer.cc
+++ b/aos/json_tokenizer.cc
@@ -31,7 +31,7 @@
}
bool Tokenizer::Consume(const char *token) {
- const absl::string_view original = data_;
+ const std::string_view original = data_;
while (true) {
// Finishing the token is success.
if (*token == '\0') {
@@ -58,7 +58,7 @@
bool Tokenizer::ConsumeString(::std::string *s) {
// Under no conditions is it acceptible to run out of data while parsing a
// string. Any AtEnd checks should confirm that.
- const absl::string_view original = data_;
+ const std::string_view original = data_;
if (AtEnd()) {
return false;
}
@@ -69,7 +69,7 @@
}
ConsumeChar();
- absl::string_view last_parsed_data = data_;
+ std::string_view last_parsed_data = data_;
*s = ::std::string();
while (true) {
@@ -134,7 +134,7 @@
// Under no conditions is it acceptible to run out of data while parsing a
// number. Any AtEnd() checks should confirm that.
*s = ::std::string();
- const absl::string_view original = data_;
+ const std::string_view original = data_;
// Consume the leading - unconditionally.
Consume("-");
diff --git a/aos/json_tokenizer.h b/aos/json_tokenizer.h
index 3058d7d..5b41da1 100644
--- a/aos/json_tokenizer.h
+++ b/aos/json_tokenizer.h
@@ -2,10 +2,9 @@
#define AOS_JSON_TOKENIZER_H_
#include <string>
+#include <string_view>
#include <vector>
-#include "absl/strings/string_view.h"
-
namespace aos {
// This class implements the state machine at json.org
@@ -14,7 +13,7 @@
// whitespace.
class Tokenizer {
public:
- Tokenizer(const absl::string_view data) : data_(data) {}
+ Tokenizer(const std::string_view data) : data_(data) {}
enum class TokenType {
kEnd,
@@ -48,7 +47,7 @@
// Returns true if we are at the end of the input.
bool AtEnd() { return data_.size() == 0; }
- const absl::string_view data_left() const { return data_; }
+ const std::string_view data_left() const { return data_; }
private:
// Consumes a single character.
@@ -87,7 +86,7 @@
State state_ = State::kExpectObjectStart;
// Data pointer.
- absl::string_view data_;
+ std::string_view data_;
// Current line number used for printing debug.
int linenumber_ = 0;
diff --git a/aos/logging/log_displayer.cc b/aos/logging/log_displayer.cc
index fe902c0..24bebbd 100644
--- a/aos/logging/log_displayer.cc
+++ b/aos/logging/log_displayer.cc
@@ -164,7 +164,7 @@
case 'N':
filter_exact_name = optarg;
filter_name = nullptr;
- filter_length = strlen(filter_name);
+ filter_length = strlen(filter_exact_name);
break;
case 'l':
filter_level = ::aos::logging::str_log(optarg);
diff --git a/aos/mutex/mutex_test.cc b/aos/mutex/mutex_test.cc
index cc659a5..53b47ca 100644
--- a/aos/mutex/mutex_test.cc
+++ b/aos/mutex/mutex_test.cc
@@ -252,8 +252,12 @@
private:
virtual void Run() override {
- if (lock_) ASSERT_FALSE(mutex_->Lock());
- if (unlock_) mutex_->Unlock();
+ if (lock_) {
+ ASSERT_FALSE(mutex_->Lock());
+ }
+ if (unlock_) {
+ mutex_->Unlock();
+ }
}
Mutex *const mutex_;
diff --git a/aos/starter/starter.cc b/aos/starter/starter.cc
index 8b137ff..6860cc4 100644
--- a/aos/starter/starter.cc
+++ b/aos/starter/starter.cc
@@ -696,6 +696,8 @@
"child %d actually dumped core. "
"falling through to killed by signal case\n",
pid);
+ [[fallthrough]];
+ /* FALLTHRU */
case CLD_KILLED:
// If somebody (possibly us) sent it SIGTERM that means that they just
// want it to stop, so it stopping isn't a WARNING.
@@ -772,7 +774,7 @@
// permissions on a roboRIO.
AOS_CHECK(system("echo 0 > /proc/sys/vm/overcommit_memory") == 0);
#endif
-
+
libevent_base = EventBaseUniquePtr(event_base_new());
std::string core_touch_file = "/tmp/starter.";
@@ -817,7 +819,7 @@
aos::InitNRT();
std::ifstream list_file(child_list_file);
-
+
while (true) {
std::string child_name;
getline(list_file, child_name);
diff --git a/aos/type_traits/type_traits.h b/aos/type_traits/type_traits.h
index 45268d5..e1fa7b4 100644
--- a/aos/type_traits/type_traits.h
+++ b/aos/type_traits/type_traits.h
@@ -4,22 +4,6 @@
#include <type_traits>
namespace aos {
-#if ((__GNUC__ < 5))
-namespace {
-template<typename Tp>
-struct has_trivial_copy_assign : public std::integral_constant<bool,
-// This changed between 4.4.5 and 4.6.3. Unless somebody discovers otherwise,
-// 4.6 seems like a reasonable place to switch.
-#if ((__GNUC__ < 4) || (__GNUC__ == 4 && __GNUC_MINOR__ < 6)) && !defined(__clang__)
- ::std::has_trivial_assign<Tp>::value> {};
-#elif (__clang_major__ < 5)
- ::std::has_trivial_copy_assign<Tp>::value> {};
-#else
- ::std::is_trivially_copy_assignable<Tp>::value> {};
-#endif
-
-} // namespace
-#endif
// A class template that determines whether or not it is safe to pass a type
// through the shared memory system (aka whether or not you can memcpy it).
@@ -31,19 +15,7 @@
// See also (3.9) [basic.types] in the C++11 standard.
template <typename Tp>
struct shm_ok : public std::integral_constant<
- bool,
-#if ((__GNUC__ < 5))
-#if (__clang_major__ > 5)
- (::std::is_trivially_copy_constructible<Tp>::value &&
- ::aos::has_trivial_copy_assign<Tp>::value)
-#else
- (::std::has_trivial_copy_constructor<Tp>::value &&
- ::aos::has_trivial_copy_assign<Tp>::value)
-#endif
-#else
- (::std::is_trivially_copy_constructible<Tp>::value)
-#endif
- > {
+ bool, (::std::is_trivially_copy_constructible<Tp>::value)> {
};
} // namespace aos
diff --git a/aos/util/file.cc b/aos/util/file.cc
index f78239a..af1f85b 100644
--- a/aos/util/file.cc
+++ b/aos/util/file.cc
@@ -3,14 +3,15 @@
#include <fcntl.h>
#include <unistd.h>
-#include "absl/strings/string_view.h"
+#include <string_view>
+
#include "aos/scoped/scoped_fd.h"
#include "glog/logging.h"
namespace aos {
namespace util {
-::std::string ReadFileToStringOrDie(const absl::string_view filename) {
+::std::string ReadFileToStringOrDie(const std::string_view filename) {
::std::string r;
ScopedFD fd(open(::std::string(filename).c_str(), O_RDONLY));
PCHECK(fd.get() != -1) << ": opening " << filename;
@@ -26,8 +27,8 @@
return r;
}
-void WriteStringToFileOrDie(const absl::string_view filename,
- const absl::string_view contents) {
+void WriteStringToFileOrDie(const std::string_view filename,
+ const std::string_view contents) {
::std::string r;
ScopedFD fd(open(::std::string(filename).c_str(),
O_CREAT | O_WRONLY | O_TRUNC, S_IRWXU));
diff --git a/aos/util/file.h b/aos/util/file.h
index 5d354a7..3aebd87 100644
--- a/aos/util/file.h
+++ b/aos/util/file.h
@@ -2,19 +2,18 @@
#define AOS_UTIL_FILE_H_
#include <string>
-
-#include "absl/strings/string_view.h"
+#include <string_view>
namespace aos {
namespace util {
// Returns the complete contents of filename. LOG(FATAL)s if any errors are
// encountered.
-::std::string ReadFileToStringOrDie(const absl::string_view filename);
+::std::string ReadFileToStringOrDie(const std::string_view filename);
// Creates filename if it doesn't exist and sets the contents to contents.
-void WriteStringToFileOrDie(const absl::string_view filename,
- const absl::string_view contents);
+void WriteStringToFileOrDie(const std::string_view filename,
+ const std::string_view contents);
} // namespace util
} // namespace aos
diff --git a/aos/vision/blob/threshold.h b/aos/vision/blob/threshold.h
index f126b14..95330c5 100644
--- a/aos/vision/blob/threshold.h
+++ b/aos/vision/blob/threshold.h
@@ -3,6 +3,7 @@
#include <array>
#include <condition_variable>
+#include <functional>
#include <mutex>
#include <thread>
diff --git a/aos/vision/image/image_dataset.cc b/aos/vision/image/image_dataset.cc
index 33bf0e4..a15ccb4 100644
--- a/aos/vision/image/image_dataset.cc
+++ b/aos/vision/image/image_dataset.cc
@@ -37,10 +37,10 @@
res.reserve(pos.size() + 1);
i = 0;
for (auto p : pos) {
- res.emplace_back(std::string(inp.substr(i, p - i)));
+ res.emplace_back(inp.substr(i, p - i));
i = p + 1;
}
- res.emplace_back(std::string(inp.substr(i)));
+ res.emplace_back(inp.substr(i));
return res;
}
} // namespace
diff --git a/aos/vision/image/image_types.h b/aos/vision/image/image_types.h
index aff7056..fba6a10 100644
--- a/aos/vision/image/image_types.h
+++ b/aos/vision/image/image_types.h
@@ -6,7 +6,7 @@
#include <memory>
#include <sstream>
-#include "absl/strings/string_view.h"
+#include <string_view>
namespace aos {
namespace vision {
@@ -20,7 +20,7 @@
};
// This will go into c++17. No sense writing my own version.
-using DataRef = absl::string_view;
+using DataRef = std::string_view;
// Represents the dimensions of an image.
struct ImageFormat {
diff --git a/compilers/linaro_linux_gcc_4.9.BUILD b/compilers/linaro_linux_gcc.BUILD
similarity index 100%
rename from compilers/linaro_linux_gcc_4.9.BUILD
rename to compilers/linaro_linux_gcc.BUILD
diff --git a/debian/BUILD b/debian/BUILD
index 503274c..0cb12e7 100644
--- a/debian/BUILD
+++ b/debian/BUILD
@@ -111,15 +111,16 @@
download_packages(
name = "download_clang_deps",
excludes = [
- "libblas.so.3",
+ "lib32stdc++6",
+ "libstdc++6",
],
force_includes = [
"libc6",
"libc6-dev",
],
packages = [
- "clang-3.6",
- "clang-format-3.6",
+ "clang-6.0",
+ "clang-format-6.0",
"gcc",
"gfortran",
],
@@ -226,7 +227,7 @@
)
generate_deb_tarball(
- name = "clang_3p6",
+ name = "clang_6p0",
files = clang_debs,
)
diff --git a/debian/clang.bzl b/debian/clang.bzl
index ade9c87..6bb9fcf 100644
--- a/debian/clang.bzl
+++ b/debian/clang.bzl
@@ -1,61 +1,135 @@
files = {
- "binutils_2.25-5+deb8u1_amd64.deb": "d9e6ac61d1d5bf63b632923c9f678d8fb64d3f9f82a0e31a8229e6e5b0bbb89d",
- "clang-3.6_3.6.2~svn240577-1~exp1_amd64.deb": "7a93b5eaad24ab35273e091ae4bc6572c583062383d650e71396fd7ddacdbaca",
- "clang-format-3.6_3.6.2~svn240577-1~exp1_amd64.deb": "38c35cd8a4e89a8dbc4414ecad521f5e689e2f582004b77e95063fabf50779e0",
- "cpp-4.9_4.9.2-10_amd64.deb": "2ee30a0c6b1da7425a6f3566c24b272ad036917ebb0ec924253cd74b4c75c9ba",
- "cpp_4.9.2-2_amd64.deb": "e0d777817359da6dd7d003c164f12a55a8b889eb360ba2c945d5316ee7dbefd8",
- "gcc-4.9-base_4.9.2-10_amd64.deb": "f95eb436176050f52e85ed5eebe12c3d851b6788735df860e18a219647d330d8",
- "gcc-4.9_4.9.2-10_amd64.deb": "dcd093c20bfb35f56df0b66c75588d4d9a0b92a3c2e038ec0d7cc24ace393556",
- "gcc_4.9.2-2_amd64.deb": "b7a60f9bc12d8ac0bbce99160390f28ee4a2d1d94753d123a7016d0443e46518",
- "gfortran-4.9_4.9.2-10_amd64.deb": "d547df4955491b49e6373ac428ddb55bd22a14bbc9178ced7854de207a458610",
- "gfortran_4.9.2-2_amd64.deb": "d4ffdd8e2748b77800c59f6dfadaa1f39da014581bb6dbcdbb1363fbefaaf689",
- "libasan1_4.9.2-10_amd64.deb": "14ebaa9a941410083f146c97465965b3a845eb7230f7809577852b7e0e07ad6f",
- "libatomic1_4.9.2-10_amd64.deb": "6ec69b0aaa26fcc8a54198f420a38eb1e390dec942f2509313907c9ed65b9422",
- "libbsd0_0.7.0-2_amd64.deb": "86573a9b5b774f6a5e87ecfb52a8ab31ad5a8469d3971856fa91f4f6ea7f3c69",
- "libc-dev-bin_2.19-18+deb8u10_amd64.deb": "3f8f50528eb7194a990221c8863ab07573c26a17680b66b32039818aecf7bf5e",
- "libc6-dev_2.19-18+deb8u10_amd64.deb": "00ba98ce8879bdfde13eac699da718d3aaba904ea6a88d5e21e77d1e298d65eb",
- "libc6_2.19-18+deb8u10_amd64.deb": "0a95ee1c5bff7f73c1279b2b78f32d40da9025a76f93cb67c03f2867a7133e61",
- "libcilkrts5_4.9.2-10_amd64.deb": "cf955b9848308a2674788f35789b55ee4ad0ee6aa99b711feff5fcd99834634e",
- "libclang-common-3.6-dev_3.6.2~svn240577-1~exp1_amd64.deb": "ea5866423c00b709b1dac8821911939c99da91ec53495021e05741dd1440a61b",
- "libclang1-3.6_3.6.2~svn240577-1~exp1_amd64.deb": "abdb6bc82977074e5ac5b16fc9ca0034822900b0bf689c54a9a008a363548a95",
- "libcloog-isl4_0.18.2-1+b2_amd64.deb": "8bb4ba985d65ededbfc24d76d3610af57a70787b635841407558d25a7f06ff49",
- "libdb5.3_5.3.28-9+deb8u1_amd64.deb": "9740f05d3c6824911be1d80b71efbccf67a06fd3287d65b1e68666a7d356d51f",
- "libedit2_3.1-20140620-2_amd64.deb": "3a57eaaeaf34dae83ea5c9fa55b4600a686351d6138a5735c922c9dbb88d1248",
- "libexpat1_2.1.0-6+deb8u4_amd64.deb": "de7979297d0298271d71b4554772ba4da60ba6895ed86ca8fc9c1159c58913e4",
- "libffi6_3.1-2+deb8u1_amd64.deb": "100343fca79ff265abc62467c7085fca68b8764e8c2551302ab741c771e7f0aa",
- "libgcc-4.9-dev_4.9.2-10_amd64.deb": "f9de916a9c782c48d5ce6768b072466bd3ccfc988f27583d2395e7d7d8e91360",
- "libgcc1_4.9.2-10_amd64.deb": "a1402290165e8d91b396a33d79580a4501041e92bdb62ef23929a0c207cd9af9",
- "libgfortran-4.9-dev_4.9.2-10_amd64.deb": "a0b92248d47beb5468280e1164287d0810caccb87827d26a8ac5fe07fd2b4154",
- "libgfortran3_4.9.2-10_amd64.deb": "77798b64f1f042daca070e3edead2658ffed6a9dcf888ba8e22f6f140012510c",
- "libgmp10_6.0.0+dfsg-6_amd64.deb": "155a31b0f716aa3dcd7ee68e9bd57e0b76a6b31f4e41fb2d953e986315437082",
- "libgomp1_4.9.2-10_amd64.deb": "055bc5e737317c5d4f4edf6799d798e7055ce409caa6e1d4842a009a0f655c41",
- "libisl10_0.12.2-2_amd64.deb": "5a091cf30221e183d319f4906a746043be7220061f3b742b2ad958ee79ac01f7",
- "libitm1_4.9.2-10_amd64.deb": "190e4c25302beb4f92195d29d81181f00f9d06c468ae659a72faeae71bf35c55",
- "libllvm3.6_3.6.2~svn240577-1~exp1_amd64.deb": "a6a066bb7b8b43705b3e7ba98410a67bf504cbca5d38d6ced44e08d1f26456e5",
- "liblsan0_4.9.2-10_amd64.deb": "cdf4bd7a907b5d56d166efc00eb9eea4308ccc3305741bf11d082d9796451951",
- "libmpc3_1.0.2-1_amd64.deb": "0a252dcf89843ee8b402fd226c8fb552d69c82c7013a28e335ba36878468d959",
- "libmpfr4_3.1.2-2_amd64.deb": "1b6ef16024e7850c4f2d47dbe06cba1143ac36d5584db515f63d5fbd873e3eb2",
- "libncursesw5_5.9+20140913-1+deb8u2_amd64.deb": "9d8d80d077e0ca85ac4493173431df42fe8943a457bac35625433eb414d79eca",
- "libobjc-4.9-dev_4.9.2-10_amd64.deb": "4f9951761e93e24654c30fb4ac19a3548e09dee32e7206d3bcd417fae4803bc6",
- "libobjc4_4.9.2-10_amd64.deb": "dd23770923f1bedb27ace993ecae89938538537a23688edfd679900a8cfb37f4",
- "libpython-stdlib_2.7.9-1_amd64.deb": "5f9ffb96222498c764526a83cac48281a941ec6e8470db1a1f8e17e6236a5669",
- "libpython2.7-minimal_2.7.9-2+deb8u1_amd64.deb": "916e2c541aa954239cb8da45d1d7e4ecec232b24d3af8982e76bf43d3e1758f3",
- "libpython2.7-stdlib_2.7.9-2+deb8u1_amd64.deb": "cf1c9dfc12d6cfd42bb14bfb46ee3cec0f6ebc720a1419f017396739953b12c5",
- "libquadmath0_4.9.2-10_amd64.deb": "76b71fdb834434e7b6dde5ba343af9bacddb987ef8ad9c788442dbe4e236e78f",
- "libreadline6_6.3-8+b3_amd64.deb": "647948737fcfea4749368aa233b2d8b89032546ba4db2f0338239e9a7f4bda3e",
- "libsqlite3-0_3.8.7.1-1+deb8u2_amd64.deb": "969b13188c642196def3846e1e44e7923bcf1fa07374b0fd7fe766ea2ba11bd0",
- "libssl1.0.0_1.0.1t-1+deb8u7_amd64.deb": "d99de2cdca54484d23badc5683c7211b3a191977272d9e5281837af863dcdd56",
- "libstdc++-4.9-dev_4.9.2-10_amd64.deb": "d67f6f74530d6248e85129413f6cbc6984b7cb62fb0039b0affe63a49eb37416",
- "libstdc++6_4.9.2-10_amd64.deb": "f1509bbabd78e89c861de16931aec5988e1215649688fd4f8dfe1af875a7fbef",
- "libtinfo5_5.9+20140913-1+deb8u2_amd64.deb": "914cb3f1f52425ecd92c44aacdb3b1303b57db783ad53910c2bb1725a56ffbaf",
- "libtsan0_4.9.2-10_amd64.deb": "316ef9e1e0a25fbe6796ae9ca19c748c5d9188254f8daa8663353a4e365f0b53",
- "libubsan0_4.9.2-10_amd64.deb": "fb495d52df0f08d485827e3a81cb585e0360e9bf80dcb87871e88682ae175695",
- "linux-libc-dev_3.16.51-3+deb8u1_amd64.deb": "173310c9d5dc6d8d03d5272971c662d22cabe73d97a61352d65e0cdc81c58276",
- "mime-support_3.58_all.deb": "c05ebe8f38da4ff19d028c9f4680414149e5c7a746de13bc9db0a562796ed213",
- "multiarch-support_2.19-18+deb8u10_amd64.deb": "44dd803aa9270d80fc7265c72982f684c8fb904d366cedbfecd37cf78aa1ca78",
- "python-minimal_2.7.9-1_amd64.deb": "58649e19c19847e264b32ad8cb5a8f58477829e1afc2616c54cb0a1ef30496be",
- "python2.7-minimal_2.7.9-2+deb8u1_amd64.deb": "c89199f908d5a508d8d404efc0e1aef3d9db59ea23bd4532df9e59941643fcfb",
- "python2.7_2.7.9-2+deb8u1_amd64.deb": "00c99c8dc1cda85053c8bfc7ea34ae5c40408c54b498ca22d0e2cb6b0acb796c",
- "python_2.7.9-1_amd64.deb": "93dc9d03df366d658832fb238a6c1e6c57e5e57dd648145c2f57a8f3e2b419ed",
- "readline-common_6.3-8_all.deb": "8b91bce988c38798e565820919a600f1a58ca483d8406860cc37e847a55a6bfd",
+ "binutils-common_2.30-21ubuntu1~18.04.2_amd64.deb" :
+ "613cd8e74f59ea6a4153fe14f7e1e1579edfbf78f5b5dc9396cb3b3c87ab2697",
+ "binutils-x86-64-linux-gnu_2.30-21ubuntu1~18.04.2_amd64.deb" :
+ "66a3add010618a166e418eb14f21b0cc7b9c1b94fa70bc7c62bcbaf103c274c2",
+ "binutils_2.30-21ubuntu1~18.04.2_amd64.deb" :
+ "9f801fccd63d728fc438d0d9aa7dedf9335087307b1f29d5d4f8e08161ff6b7f",
+ "clang-6.0_6.0-1ubuntu2_amd64.deb" :
+ "a8ca3b38fd3b5ae54793ddcefa7c5023970ba0ae6d9dcfaef8c2cabaa7ae5914",
+ "clang-format-6.0_6.0-1ubuntu2_amd64.deb" :
+ "45837be701a0245a6fc7239d084d3a4cee20f9a2d8f5e5e9210c63fa062c7910",
+ "cpp-7_7.4.0-1ubuntu1~18.04.1_amd64.deb" :
+ "38d513408c134b0f0c10236b52d30ef09d5e4c0e092de52de51fa86c57988bc2",
+ "cpp_7.4.0-1ubuntu2.3_amd64.deb" :
+ "6587837e97571bf64e5b673d0f0923b52e3f4e601e15df3907f9a246dd3eaae4",
+ "gcc-7-base_7.4.0-1ubuntu1~18.04.1_amd64.deb" :
+ "8c4e1cf8e5fbe0b8b71119f39b298c35584b204c106d0982db5b7ce9006bfcc5",
+ "gcc-7_7.4.0-1ubuntu1~18.04.1_amd64.deb" :
+ "ac18fe3f92e34d6744e85d50ccdd21389a6a1f92fdf28be56cb9d93fdab8a6e7",
+ "gcc-8-base_8.3.0-6ubuntu1~18.04.1_amd64.deb" :
+ "89415e0e9d940c81e33959f366f1bad1a94cfecacb538eb897be0e6038781a94",
+ "gcc_7.4.0-1ubuntu2.3_amd64.deb" :
+ "7ef491f26b4c15b45c0221f106f1d44a17e168b5ec951a378ec46c9211d67de9",
+ "gfortran-7_7.4.0-1ubuntu1~18.04.1_amd64.deb" :
+ "bcb2da51c180dd4bbe98882ba679f48ec0acf93c87cce159b43c3a9bae5ddaad",
+ "gfortran_7.4.0-1ubuntu2.3_amd64.deb" :
+ "376fc704de5358e61c933f94cd45dd4f39cd044af8ffce04e8cb9acbe9f5fc17",
+ "lib32gcc1_8.3.0-6ubuntu1~18.04.1_amd64.deb" :
+ "1174aec225edfdd73891041631ea5bb42fee17fc260a01395bf59d1393225a55",
+ "libasan4_7.4.0-1ubuntu1~18.04.1_amd64.deb" :
+ "46b713b5f9331bf13db9b360b55274d9abce829bc35f9fac424d96e968858251",
+ "libatomic1_8.3.0-6ubuntu1~18.04.1_amd64.deb" :
+ "1d454264e0509b9715aca09b4398f609f6014da177d4559894a6ae4a01cd338e",
+ "libbinutils_2.30-21ubuntu1~18.04.2_amd64.deb" :
+ "e525a0143b4c3ed75acfe2845aa0525fbebf2215f063fb5d8bfb5b1ed548e2ef",
+ "libc-dev-bin_2.27-3ubuntu1_amd64.deb" :
+ "69ea1317b37cbd467eb7d216f5d23aa8831d926908e9e12477aa28bdc1d5e62b",
+ "libc6-dev_2.27-3ubuntu1_amd64.deb" :
+ "e426c70a940a7d0c5c95823a5fd01f26bd8bcb08d109df2f8c96c439da8dc440",
+ "libc6-i386_2.27-3ubuntu1_amd64.deb" :
+ "d21b6a22a58d6e784a2fd4c2d662b6448ce65907d9603307be7a0bcccd0357bd",
+ "libc6_2.27-3ubuntu1_amd64.deb" :
+ "1e1eb86fd646aa68f7144ec692b837b6b352d215880c6a2d0c92c19d36938427",
+ "libcc1-0_8.3.0-6ubuntu1~18.04.1_amd64.deb" :
+ "37f307ecdc7c798870acc5f2494f4630ee09b837bcf5559e6994ccf4b33e851a",
+ "libcilkrts5_7.4.0-1ubuntu1~18.04.1_amd64.deb" :
+ "fe9b2a0cf364bbe086fbb6e9d36ea05cc9ef1407b3e28f4d939d1f8dd810e396",
+ "libclang-common-6.0-dev_6.0-1ubuntu2_amd64.deb" :
+ "bcf3358a1619735ca3b1a344c8f2267381c113c73b41fe440444972d4e2f516d",
+ "libclang1-6.0_6.0-1ubuntu2_amd64.deb" :
+ "a8e927609413995ae9ac19d0c98a558a5f06d729f9d8c603f7403f9bc53f7e76",
+ "libdb5.3_5.3.28-13.1ubuntu1.1_amd64.deb" :
+ "abb7f569252604af9b123cd6c73195cbd54d7b7664479a85fd5fd12fe8ba3b5d",
+ "libedit2_3.1-20170329-1_amd64.deb" :
+ "414cc28beac456b78140b0a07558034c4a2987212b347401dbb6e1d375f11d32",
+ "libexpat1_2.2.5-3ubuntu0.2_amd64.deb" :
+ "d700a358e8139b5f31c96a3caef452d62388c05f7cf4d6e4f448a06c2c2da122",
+ "libffi6_3.2.1-8_amd64.deb" :
+ "fa26945b0aadfc72ec623c68be9cc59235a7fe42e2388f7015fd131f4fb06dc9",
+ "libgc1c2_7.4.2-8ubuntu1_amd64.deb" :
+ "42c5817659a73581666c93412b3cd2f19960958cd5d5cceb14931f1f5b9611cc",
+ "libgcc-7-dev_7.4.0-1ubuntu1~18.04.1_amd64.deb" :
+ "60e5ada69177a403f141a19e806bf89a7de79156cd954e36b96f714707e4ef06",
+ "libgcc1_8.3.0-6ubuntu1~18.04.1_amd64.deb" :
+ "1c0a4bf462fa00270158399becf17a2636c03aece77825d9bfff6158cc856295",
+ "libgfortran-7-dev_7.4.0-1ubuntu1~18.04.1_amd64.deb" :
+ "5c9f8bdde83937b6562d3581b3df74cd8c472e10518bc7741a4f97c2200db077",
+ "libgfortran4_7.4.0-1ubuntu1~18.04.1_amd64.deb" :
+ "c800a1b30c8de9871c0baa019b074076a902a150679ccf31bb3f6c8d9080e862",
+ "libgmp10_6.1.2+dfsg-2_amd64.deb" :
+ "5b4ea4fdbc5cf9b2eb9ce7b05de58a36b507982d9fa8c84765d41279e4645be1",
+ "libgomp1_8.3.0-6ubuntu1~18.04.1_amd64.deb" :
+ "359b9f701e4ef0396ac3eac1dcfbe5f0fda93c7dd8f9af93c48afeb693ae2886",
+ "libisl19_0.19-1_amd64.deb" :
+ "07a0827aba14140b1833ca19ced3f939b2d075646094926d43678a0d19cc942f",
+ "libitm1_8.3.0-6ubuntu1~18.04.1_amd64.deb" :
+ "01108e615b99e752411d1a208730a0e64b0bcd1002e243bd1bc2d5cb0fe1aaed",
+ "libjsoncpp1_1.7.4-3_amd64.deb" :
+ "c0467781913f8a59e60b63efcbf334f17058128076c1b265803d98e9e93815cd",
+ "libllvm6.0_6.0-1ubuntu2_amd64.deb" :
+ "62608aa70d922c8502d72d3f11a5c9d66f4bb680695cf9c7d6ff9acf9632a8a5",
+ "liblsan0_8.3.0-6ubuntu1~18.04.1_amd64.deb" :
+ "6d9ad502fdd0cd23e66f2b3c41475eab797cc06e762ae87e2a7c1ff5f7e45779",
+ "libmpc3_1.1.0-1_amd64.deb" :
+ "3c3c45aa50ce1ff753107766c6fea35a82c52ad11afcab0abfd0cd0c76730f87",
+ "libmpfr6_4.0.1-1_amd64.deb" :
+ "701990426b88d7af39237d6128078d8a4788c72d42e1b9a1b058a871e16ab7fb",
+ "libmpx2_8.3.0-6ubuntu1~18.04.1_amd64.deb" :
+ "7ec3f3b4d3e935bf2c4df78e8505bea077eb1028d6adfe0e6e89bb97d0580790",
+ "libncursesw5_6.1-1ubuntu1.18.04_amd64.deb" :
+ "d1a7a32fe88181d6f5adf7c52cb981359aa35b01bdbbf7218ddc240a4fdabd87",
+ "libobjc-7-dev_7.4.0-1ubuntu1~18.04.1_amd64.deb" :
+ "51f788e2c5ddf642213bf6000dfb98c9cdc8559fae37eba216fe3d8ffe84c9cb",
+ "libobjc4_8.3.0-6ubuntu1~18.04.1_amd64.deb" :
+ "45a93ad75d9faa4e76502df1d78779896147d817795f45eaac59baaffafbfa36",
+ "libpython-stdlib_2.7.15~rc1-1_amd64.deb" :
+ "2443d968497fb5850a7d2de82f81fcba7b3e61aecc34e61ecacc6f9f80954a6b",
+ "libpython2.7-minimal_2.7.15-4ubuntu4~18.04.2_amd64.deb" :
+ "b1cc0e956f18ee45de0afaa047f3f14a056cd40dad6a10290159562aee0f2783",
+ "libpython2.7-stdlib_2.7.15-4ubuntu4~18.04.2_amd64.deb" :
+ "83c3df1e43a18e73e9c492a79f7f0ea5a3a168bd81c7774d8d1413812bb3577f",
+ "libquadmath0_8.3.0-6ubuntu1~18.04.1_amd64.deb" :
+ "bb62897b975669c6010c3a9b28bced16abf89caa5d9f3dc60a2232e56579cedb",
+ "libreadline7_7.0-3_amd64.deb" :
+ "8706403267e95615f1b70db31ff16709361982728b308466346e01c20a743dd5",
+ "libsqlite3-0_3.22.0-1ubuntu0.1_amd64.deb" :
+ "199fbe096ee359eaf16e7e23871a1aa508bf055df0010c7c4321398f9484a220",
+ "libssl1.1_1.1.1-1ubuntu2.1~18.04.4_amd64.deb" :
+ "92887a27422e5bbc33f91e529f0cc071ee1bece0220ba94fe311e8f9280b2607",
+ "libstdc++-7-dev_7.4.0-1ubuntu1~18.04.1_amd64.deb" :
+ "5d1a1ce1bf23a0a7a61f4f5d32172505a37f62063994ed91940757e2c92b5a68",
+ "libstdc++6_8.3.0-6ubuntu1~18.04.1_amd64.deb" :
+ "9a84a882fa60f5f3f1fa0fee344d19ca7544cfe2472307095dc841c3ab0f8907",
+ "libtinfo5_6.1-1ubuntu1.18.04_amd64.deb" :
+ "bb4d4d80720149692ea0d5bca1a5dac57737afe447810ce69dd4a95107121da5",
+ "libtsan0_8.3.0-6ubuntu1~18.04.1_amd64.deb" :
+ "dfa5248fc7ea63f992c6b599a85105271583ec5c8f297f79e3c3ecd24a0e64da",
+ "libubsan0_7.4.0-1ubuntu1~18.04.1_amd64.deb" :
+ "a355512c0c6ce266e5ac978e0c3fba697678f2f977efc312dbccd5b0dbc862e8",
+ "linux-libc-dev_4.15.0-66.75_amd64.deb" :
+ "8e8e3cb778c40e25a3a107a2ffc595527616e3be8487588a5de0ae5c14777d38",
+ "mime-support_3.60ubuntu1_all.deb" :
+ "98e05aa03538c5f182ed14cbb59cfe64b30592d77e602abd2442a9f1c72532b3",
+ "python-minimal_2.7.15~rc1-1_amd64.deb" :
+ "960ba1bf3601f763f2d9b26773ce91840facb16f141197ef462a98a5e86bbd07",
+ "python2.7-minimal_2.7.15-4ubuntu4~18.04.2_amd64.deb" :
+ "027817d061f1597c6132dd707b07287bd7dec200296f692db52e8f16008d60b5",
+ "python2.7_2.7.15-4ubuntu4~18.04.2_amd64.deb" :
+ "4ffd42068182cc06fafce537b5bc5a1d7f21c705692968350655a4db43c88473",
+ "python_2.7.15~rc1-1_amd64.deb" :
+ "9be87952c519f94d24129911e03a24035ce47358cb528492f4a53b2e31efc6d4",
+ "readline-common_7.0-3_all.deb" :
+ "84cb3642c82114496d2fc17011db13655bd661cf4641098c03c168ddde367908",
}
+
diff --git a/debian/ni-libraries-2019.BUILD b/debian/ni-libraries-2019.BUILD
index 09522cd..4b363b5 100644
--- a/debian/ni-libraries-2019.BUILD
+++ b/debian/ni-libraries-2019.BUILD
@@ -1,13 +1,14 @@
cc_library(
name = "ni-libraries",
srcs = [
- "src/lib/chipobject/libNiFpga.so.18.0.0",
- "src/lib/chipobject/libNiFpgaLv.so.18.0.0",
- "src/lib/chipobject/libNiRioSrv.so.18.0.0",
- "src/lib/chipobject/libRoboRIO_FRC_ChipObject.so.19.0.0",
- "src/lib/chipobject/libniriodevenum.so.18.0.0",
- "src/lib/chipobject/libniriosession.so.18.0.0",
- "src/lib/netcomm/libFRC_NetworkCommunication.so.19.0.0",
+ "src/lib/chipobject/libNiFpga.so.19.0.0",
+ "src/lib/runtime/libNiFpgaLv.so.19.0.0",
+ "src/lib/runtime/libNiRioSrv.so.19.0.0",
+ "src/lib/chipobject/libRoboRIO_FRC_ChipObject.so.20.0.0",
+ "src/lib/runtime/libniriodevenum.so.19.0.0",
+ "src/lib/runtime/libniriosession.so.18.0.0",
+ "src/lib/runtime/libnirio_emb_can.so.16.0.0",
+ "src/lib/netcomm/libFRC_NetworkCommunication.so.20.0.0",
],
hdrs = glob(["src/include/**"]),
includes = [
diff --git a/debian/packages.bzl b/debian/packages.bzl
index 845b660..59f993e 100644
--- a/debian/packages.bzl
+++ b/debian/packages.bzl
@@ -7,7 +7,7 @@
# packages you care about and exclude the ones you don't care about.
# Invoke "bazel build" on the "download_packages" target you just created.
# Save the "_files" dictionary it prints into a .bzl file in the //debian
-# folder.
+# folder. You will need to have the apt-rdepends package installed.
# 2. The "download_packages" steps prints the location of the deb packages
# after it prints the "_files" dictionary. Take the deb packages from there
# and upload them to http://www.frc971.org/Build-Dependencies/.
@@ -63,7 +63,7 @@
target = target.replace('+', 'x')
return "deb_%s_repo" % target
-def generate_repositories_for_debs(files):
+def generate_repositories_for_debs(files, base_url = 'http://www.frc971.org/Build-Dependencies'):
"""A WORKSPACE helper to add all the deb packages in the dictionary as a repo.
The files dictionary must be one generated with the "download_packages"
@@ -74,7 +74,7 @@
if name not in native.existing_rules():
http_file(
name = name,
- urls = ['http://www.frc971.org/Build-Dependencies/%s' % f],
+ urls = [base_url + '/' + f],
sha256 = files[f],
downloaded_file_path = f,
)
diff --git a/frc971/control_loops/drivetrain/libspline.cc b/frc971/control_loops/drivetrain/libspline.cc
index 1d7aa0b..5f5b02e 100644
--- a/frc971/control_loops/drivetrain/libspline.cc
+++ b/frc971/control_loops/drivetrain/libspline.cc
@@ -25,27 +25,27 @@
void deleteSpline(NSpline<6> *spline) { delete spline; }
void SplinePoint(NSpline<6> *spline, double alpha, double *res) {
- double *val = spline->Point(alpha).data();
- res[0] = val[0];
- res[1] = val[1];
+ const Eigen::Vector2d xy = spline->Point(alpha);
+ res[0] = xy.x();
+ res[1] = xy.y();
}
void SplineDPoint(NSpline<6> *spline, double alpha, double *res) {
- double *val = spline->DPoint(alpha).data();
- res[0] = val[0];
- res[1] = val[1];
+ const Eigen::Vector2d dxy = spline->DPoint(alpha);
+ res[0] = dxy.x();
+ res[1] = dxy.y();
}
void SplineDDPoint(NSpline<6> *spline, double alpha, double *res) {
- double *val = spline->DDPoint(alpha).data();
- res[0] = val[0];
- res[1] = val[1];
+ const Eigen::Vector2d ddxy = spline->DDPoint(alpha);
+ res[0] = ddxy.x();
+ res[1] = ddxy.y();
}
void SplineDDDPoint(NSpline<6> *spline, double alpha, double *res) {
- double *val = spline->DDDPoint(alpha).data();
- res[0] = val[0];
- res[1] = val[1];
+ const Eigen::Vector2d dddxy = spline->DDDPoint(alpha);
+ res[0] = dddxy.x();
+ res[1] = dddxy.y();
}
double SplineTheta(NSpline<6> *spline, double alpha) {
@@ -81,22 +81,22 @@
void deleteDistanceSpline(DistanceSpline *spline) { delete spline; }
void DistanceSplineXY(DistanceSpline *spline, double distance, double *res) {
- double *val = spline->XY(distance).data();
- res[0] = val[0];
- res[1] = val[1];
+ const Eigen::Vector2d xy = spline->XY(distance);
+ res[0] = xy.x();
+ res[1] = xy.y();
}
void DistanceSplineDXY(DistanceSpline *spline, double distance, double *res) {
- double *val = spline->DXY(distance).data();
- res[0] = val[0];
- res[1] = val[1];
+ const Eigen::Vector2d dxy = spline->DXY(distance);
+ res[0] = dxy.x();
+ res[1] = dxy.y();
}
void DistanceSplineDDXY(DistanceSpline *spline, double distance,
double *res) {
- double *val = spline->DDXY(distance).data();
- res[0] = val[0];
- res[1] = val[1];
+ const Eigen::Vector2d ddxy = spline->DDXY(distance);
+ res[0] = ddxy.x();
+ res[1] = ddxy.y();
}
double DistanceSplineTheta(DistanceSpline *spline, double distance) {
@@ -150,9 +150,9 @@
void TrajectoryPlan(Trajectory *t) { t->Plan(); }
void TrajectoryVoltage(Trajectory *t, double distance, double* res) {
- double *val = t->FFVoltage(distance).data();
- res[0] = val[0];
- res[1] = val[1];
+ const Eigen::Vector2d ff_voltage = t->FFVoltage(distance);
+ res[0] = ff_voltage.x();
+ res[1] = ff_voltage.y();
}
double TrajectoryLength(Trajectory *t) { return t->length(); }
diff --git a/frc971/control_loops/drivetrain/line_follow_drivetrain.cc b/frc971/control_loops/drivetrain/line_follow_drivetrain.cc
index 7fe5cad..7c92f8b 100644
--- a/frc971/control_loops/drivetrain/line_follow_drivetrain.cc
+++ b/frc971/control_loops/drivetrain/line_follow_drivetrain.cc
@@ -126,8 +126,10 @@
freeze_delay = chrono::milliseconds(2000);
}
}
+ freeze_target_ = true;
+ } else {
+ freeze_target_ = now <= freeze_delay + last_enable_;
}
- freeze_target_ = now <= freeze_delay + last_enable_;
// Set an adjustment that lets the driver tweak the offset for where we place
// the target left/right.
side_adjust_ = -goal->wheel() * 0.1;
diff --git a/frc971/wpilib/loop_output_handler.h b/frc971/wpilib/loop_output_handler.h
index a697339..46e78fc 100644
--- a/frc971/wpilib/loop_output_handler.h
+++ b/frc971/wpilib/loop_output_handler.h
@@ -37,7 +37,7 @@
// TODO(austin): Set name.
timer_handler_ = event_loop_->AddTimer([this]() { Stop(); });
- event_loop_->OnRun([this, timeout]() {
+ event_loop_->OnRun([this]() {
timer_handler_->Setup(event_loop_->monotonic_now() + timeout_);
});
}
diff --git a/third_party/allwpilib_2019/BUILD b/third_party/allwpilib_2019/BUILD
index e35687d..cfae703 100644
--- a/third_party/allwpilib_2019/BUILD
+++ b/third_party/allwpilib_2019/BUILD
@@ -64,6 +64,7 @@
include = [
"hal/src/main/native/athena/*.cpp",
"hal/src/main/native/cpp/cpp/*.cpp",
+ "hal/src/main/native/cpp/*.cpp",
"hal/src/main/native/athena/ctre/*.cpp",
"hal/src/main/native/shared/handles/*.cpp",
"hal/src/main/native/cpp/handles/*.cpp",
diff --git a/third_party/allwpilib_2019/wpiutil/BUILD b/third_party/allwpilib_2019/wpiutil/BUILD
index e579466..98ed173 100644
--- a/third_party/allwpilib_2019/wpiutil/BUILD
+++ b/third_party/allwpilib_2019/wpiutil/BUILD
@@ -2,17 +2,21 @@
cc_library(
name = "wpiutil",
- srcs = glob([
- "src/main/native/cpp/llvm/*.cpp",
- ]) + [
+ srcs = glob(
+ [
+ "src/main/native/cpp/llvm/*.cpp",
+ ],
+ ) + [
"src/main/native/cpp/llvm/Unix/Path.inc",
"src/main/native/cpp/timestamp.cpp",
"src/main/native/cpp/SafeThread.cpp",
- "src/main/native/cpp/memory.cpp",
],
- hdrs = glob([
- "src/main/native/include/**",
- ]),
+ hdrs = glob(
+ [
+ "src/main/native/include/**",
+ ],
+ exclude = ["STLExtras.h"],
+ ),
copts = [
"-Wno-unused-parameter",
],
diff --git a/third_party/cddlib/BUILD b/third_party/cddlib/BUILD
index ad99b15..fa2f50a 100644
--- a/third_party/cddlib/BUILD
+++ b/third_party/cddlib/BUILD
@@ -1,41 +1,43 @@
-licenses(['notice'])
+licenses(["notice"])
-load('//tools/build_rules:select.bzl', 'compiler_select')
+load("//tools/build_rules:select.bzl", "compiler_select")
cc_library(
- name = 'cddlib',
- visibility = ['//visibility:public'],
- srcs = [
- 'lib-src/cddcore.c',
- 'lib-src/cddlp.c',
- 'lib-src/cddmp.c',
- 'lib-src/cddio.c',
- 'lib-src/cddlib.c',
- 'lib-src/cddproj.c',
- 'lib-src/setoper.c',
- 'lib-src/cddmp.h',
- 'lib-src/cddtypes.h',
- 'lib-src/setoper.h',
- ],
- hdrs = [
- 'lib-src/cdd.h',
- ],
- copts = [
- '-Wno-sometimes-uninitialized',
- '-Wno-unused-parameter',
- '-Wno-switch-enum',
- '-Wno-empty-body',
- '-Wno-sign-compare',
- '-Wno-unused-result',
- ] + compiler_select({
- 'gcc': ['-Wno-unused-but-set-variable'],
- 'clang': []
- }),
+ name = "cddlib",
+ srcs = [
+ "lib-src/cddcore.c",
+ "lib-src/cddio.c",
+ "lib-src/cddlib.c",
+ "lib-src/cddlp.c",
+ "lib-src/cddmp.c",
+ "lib-src/cddmp.h",
+ "lib-src/cddproj.c",
+ "lib-src/cddtypes.h",
+ "lib-src/setoper.c",
+ "lib-src/setoper.h",
+ ],
+ hdrs = [
+ "lib-src/cdd.h",
+ ],
+ copts = [
+ "-Wno-sometimes-uninitialized",
+ "-Wno-unused-parameter",
+ "-Wno-switch-enum",
+ "-Wno-empty-body",
+ "-Wno-sign-compare",
+ "-Wno-implicit-fallthrough",
+ "-Wno-unused-result",
+ ] + compiler_select({
+ "gcc": ["-Wno-unused-but-set-variable"],
+ "clang": [],
+ }),
+ visibility = ["//visibility:public"],
)
+
cc_binary(
- name = '_cddlib.so',
- deps = [':cddlib'],
- linkshared = True,
- visibility = ['//visibility:public'],
- linkstatic = False,
+ name = "_cddlib.so",
+ linkshared = True,
+ linkstatic = False,
+ visibility = ["//visibility:public"],
+ deps = [":cddlib"],
)
diff --git a/third_party/ceres/BUILD b/third_party/ceres/BUILD
index 2a4028a..53e7c93 100644
--- a/third_party/ceres/BUILD
+++ b/third_party/ceres/BUILD
@@ -36,6 +36,10 @@
ceres_library(
name = "ceres",
+ extra_copts = cpu_select({
+ "roborio": ["-Wno-maybe-uninitialized"],
+ "else": [],
+ }),
restrict_schur_specializations = False,
)
diff --git a/third_party/ceres/bazel/ceres.bzl b/third_party/ceres/bazel/ceres.bzl
index d99046a..b33aeb3 100644
--- a/third_party/ceres/bazel/ceres.bzl
+++ b/third_party/ceres/bazel/ceres.bzl
@@ -138,6 +138,7 @@
# See https://github.com/ceres-solver/ceres-solver/issues/335.
def ceres_library(name,
restrict_schur_specializations=False,
+ extra_copts=[],
gflags_namespace="gflags"):
# The path to internal/ depends on whether Ceres is the main workspace or
# an external repository.
@@ -186,7 +187,7 @@
"-Wno-ignored-qualifiers",
"-Wno-unused-parameter",
"-Wno-format-nonliteral",
- ] + schur_eliminator_copts,
+ ] + schur_eliminator_copts + extra_copts,
# These include directories and defines are propagated to other targets
# depending on Ceres.
diff --git a/third_party/ct/ct_core/include/external/cppad/cg/cg.hpp b/third_party/ct/ct_core/include/external/cppad/cg/cg.hpp
index fd77d2d..6cb2c68 100644
--- a/third_party/ct/ct_core/include/external/cppad/cg/cg.hpp
+++ b/third_party/ct/ct_core/include/external/cppad/cg/cg.hpp
@@ -15,6 +15,8 @@
* Author: Joao Leal
*/
+#include <functional>
+
namespace CppAD {
namespace cg {
diff --git a/third_party/eigen/Eigen/src/LU/arch/Inverse_SSE.h b/third_party/eigen/Eigen/src/LU/arch/Inverse_SSE.h
index ebb64a6..4f35344 100644
--- a/third_party/eigen/Eigen/src/LU/arch/Inverse_SSE.h
+++ b/third_party/eigen/Eigen/src/LU/arch/Inverse_SSE.h
@@ -139,7 +139,7 @@
iC = _mm_sub_ps(iC, _mm_mul_ps(_mm_shuffle_ps(A,A,0xB1), _mm_shuffle_ps(DC,DC,0x66)));
rd = _mm_shuffle_ps(rd,rd,0);
- rd = _mm_xor_ps(rd, _mm_load_ps((float*)_Sign_PNNP));
+ rd = _mm_xor_ps(rd, _mm_load_ps((const float*)_Sign_PNNP));
// iB = C*|B| - D*B#*A
iB = _mm_sub_ps(_mm_mul_ps(C,_mm_shuffle_ps(dB,dB,0)), iB);
diff --git a/third_party/gflags/src/gflags_completions.cc b/third_party/gflags/src/gflags_completions.cc
index c53a128..4f33b38 100644
--- a/third_party/gflags/src/gflags_completions.cc
+++ b/third_party/gflags/src/gflags_completions.cc
@@ -327,9 +327,14 @@
}
switch (found_question_marks) { // all fallthroughs
- case 3: options->flag_description_substring_search = true;
- case 2: options->flag_location_substring_search = true;
- case 1: options->flag_name_substring_search = true;
+ case 3:
+ options->flag_description_substring_search = true;
+ [[fallthrough]];
+ case 2:
+ options->flag_location_substring_search = true;
+ [[fallthrough]];
+ case 1:
+ options->flag_name_substring_search = true;
};
options->return_all_matching_flags = (found_plusses > 0);
diff --git a/third_party/googletest/googlemock/test/BUILD.bazel b/third_party/googletest/googlemock/test/BUILD.bazel
index 541ef8e..517f8d6 100644
--- a/third_party/googletest/googlemock/test/BUILD.bazel
+++ b/third_party/googletest/googlemock/test/BUILD.bazel
@@ -47,6 +47,7 @@
copts = [
"-Wno-unused-parameter",
"-Wno-unused-function",
+ "-Wno-unused-private-field",
],
deps = ["//third_party/googletest:gtest"],
)
diff --git a/third_party/googletest/googletest/test/BUILD.bazel b/third_party/googletest/googletest/test/BUILD.bazel
index 293969f..0a66ce9 100644
--- a/third_party/googletest/googletest/test/BUILD.bazel
+++ b/third_party/googletest/googletest/test/BUILD.bazel
@@ -98,6 +98,7 @@
"//conditions:default": [
"-DGTEST_USE_OWN_TR1_TUPLE=1",
"-Wno-empty-body",
+ "-Wno-dangling-else",
],
}),
includes = [
@@ -121,7 +122,10 @@
name = "googletest-death-test-test",
size = "medium",
srcs = ["googletest-death-test-test.cc"],
- copts = ["-Wno-empty-body"],
+ copts = [
+ "-Wno-empty-body",
+ "-Wno-dangling-else",
+ ],
deps = ["//third_party/googletest:gtest_main"],
)
@@ -159,6 +163,9 @@
"googletest-param-test-test.h",
"googletest-param-test2-test.cc",
],
+ copts = [
+ "-Wno-unused-private-field",
+ ],
deps = ["//third_party/googletest:gtest"],
)
@@ -167,7 +174,10 @@
size = "small",
srcs = ["gtest_unittest.cc"],
args = ["--heap_check=strict"],
- copts = ["-Wno-empty-body"],
+ copts = [
+ "-Wno-empty-body",
+ "-Wno-dangling-else",
+ ],
shard_count = 2,
deps = ["//third_party/googletest:gtest_main"],
)
diff --git a/third_party/gperftools/src/libc_override_gcc_and_weak.h b/third_party/gperftools/src/libc_override_gcc_and_weak.h
index 818e43d..c2c2403 100644
--- a/third_party/gperftools/src/libc_override_gcc_and_weak.h
+++ b/third_party/gperftools/src/libc_override_gcc_and_weak.h
@@ -54,11 +54,11 @@
#define ALIAS(tc_fn) __attribute__ ((alias (#tc_fn)))
-void* operator new(size_t size) throw (std::bad_alloc)
+void* operator new(size_t size) _GLIBCXX_THROW (std::bad_alloc)
ALIAS(tc_new);
void operator delete(void* p) __THROW
ALIAS(tc_delete);
-void* operator new[](size_t size) throw (std::bad_alloc)
+void* operator new[](size_t size) _GLIBCXX_THROW (std::bad_alloc)
ALIAS(tc_newarray);
void operator delete[](void* p) __THROW
ALIAS(tc_deletearray);
diff --git a/third_party/gperftools/src/tests/tcmalloc_unittest.cc b/third_party/gperftools/src/tests/tcmalloc_unittest.cc
index 1831168..5205e0c 100644
--- a/third_party/gperftools/src/tests/tcmalloc_unittest.cc
+++ b/third_party/gperftools/src/tests/tcmalloc_unittest.cc
@@ -626,7 +626,7 @@
#endif
}
-static void TestNewHandler() throw (std::bad_alloc) {
+static void TestNewHandler() _GLIBCXX_THROW (std::bad_alloc) {
++news_handled;
throw std::bad_alloc();
}
diff --git a/third_party/libevent/evdns.c b/third_party/libevent/evdns.c
index 3ae5d8b..09fee5f 100644
--- a/third_party/libevent/evdns.c
+++ b/third_party/libevent/evdns.c
@@ -2247,6 +2247,10 @@
retcode = 1;
/* fall through: we'll set a timeout, which will time out,
* and make us retransmit the request anyway. */
+#ifdef __cplusplus
+ [[fallthrough]];
+#endif // __cplusplus
+ /* FALLTHRU */
default:
/* all ok */
log(EVDNS_LOG_DEBUG,
diff --git a/third_party/libjpeg/BUILD b/third_party/libjpeg/BUILD
index 2f3a812..f5b2d12 100644
--- a/third_party/libjpeg/BUILD
+++ b/third_party/libjpeg/BUILD
@@ -65,6 +65,7 @@
"-Wno-switch-enum",
"-Wno-format-nonliteral",
"-Wno-unused-parameter",
+ "-Wno-implicit-fallthrough",
] + select({
"//tools:cpu_roborio": [
# This is sketchy under the standard, but it's a known issue with
diff --git a/third_party/optional/.appveyor.yml b/third_party/optional/.appveyor.yml
deleted file mode 100644
index 2bc97fd..0000000
--- a/third_party/optional/.appveyor.yml
+++ /dev/null
@@ -1,10 +0,0 @@
-os:
-- Visual Studio 2015
-- Visual Studio 2017
-
-build_script:
- - mkdir build
- - cd build
- - cmake ..
- - cmake --build .
- - C:\projects\optional\build\Debug\tests.exe
diff --git a/third_party/optional/.clang-format b/third_party/optional/.clang-format
deleted file mode 100644
index 9b3aa8b..0000000
--- a/third_party/optional/.clang-format
+++ /dev/null
@@ -1 +0,0 @@
-BasedOnStyle: LLVM
diff --git a/third_party/optional/.gitignore b/third_party/optional/.gitignore
deleted file mode 100644
index 7029959..0000000
--- a/third_party/optional/.gitignore
+++ /dev/null
@@ -1,2 +0,0 @@
-\#*
-.\#*
diff --git a/third_party/optional/.travis.yml b/third_party/optional/.travis.yml
deleted file mode 100644
index 46eccb1..0000000
--- a/third_party/optional/.travis.yml
+++ /dev/null
@@ -1,257 +0,0 @@
-language: cpp
-
-
-dist: trusty
-sudo: false
-
-matrix:
- include:
- - compiler: gcc
- addons:
- apt:
- sources:
- - ubuntu-toolchain-r-test
- packages:
- - g++-5
- env: COMPILER=g++-5 CXXSTD=11
- - compiler: gcc
- addons:
- apt:
- sources:
- - ubuntu-toolchain-r-test
- packages:
- - g++-6
- env: COMPILER=g++-6 CXXSTD=11
- - compiler: gcc
- addons:
- apt:
- sources:
- - ubuntu-toolchain-r-test
- packages:
- - g++-7
- env: COMPILER=g++-7 CXXSTD=11
- - compiler: gcc
- addons:
- apt:
- sources:
- - ubuntu-toolchain-r-test
- packages:
- - g++-8
- env: COMPILER=g++-8 CXXSTD=11
- - compiler: gcc
- addons:
- apt:
- sources:
- - ubuntu-toolchain-r-test
- packages:
- - g++-4.9
- env: COMPILER=g++-4.9 CXXSTD=11
- - compiler: gcc
- addons:
- apt:
- sources:
- - ubuntu-toolchain-r-test
- packages:
- - g++-4.8
- env: COMPILER=g++-4.8 CXXSTD=11
- - compiler: clang
- addons:
- apt:
- sources:
- - llvm-toolchain-precise-3.5
- - ubuntu-toolchain-r-test
- packages:
- - clang++-3.5
- - libc++-dev
- env: COMPILER=clang++-3.5 CXXSTD=11
- - compiler: clang
- addons:
- apt:
- sources:
- - llvm-toolchain-precise-3.6
- - ubuntu-toolchain-r-test
- packages:
- - clang++-3.6
- - libc++-dev
- env: COMPILER=clang++-3.6 CXXSTD=11
- - compiler: clang
- addons:
- apt:
- sources:
- - llvm-toolchain-precise-3.7
- - ubuntu-toolchain-r-test
- packages:
- - clang++-3.7
- - libc++-dev
- env: COMPILER=clang++-3.7 CXXSTD=11
- - compiler: clang
- addons:
- apt:
- sources:
- - llvm-toolchain-precise-3.8
- - ubuntu-toolchain-r-test
- packages:
- - clang++-3.8
- - libc++-dev
- env: COMPILER=clang++-3.8 CXXSTD=11
- - compiler: clang
- addons:
- apt:
- sources:
- - sourceline: "deb http://apt.llvm.org/trusty/ llvm-toolchain-trusty-3.9 main"
- key_url: "http://apt.llvm.org/llvm-snapshot.gpg.key"
- - ubuntu-toolchain-r-test
- packages:
- - clang++-3.9
- - libc++-dev
- env: COMPILER=clang++-3.9 CXXSTD=11
- - compiler: clang
- addons:
- apt:
- sources:
- - llvm-toolchain-trusty-4.0
- - ubuntu-toolchain-r-test
- packages:
- - clang++-4.0
- - libc++-dev
- env: COMPILER=clang++-4.0 CXXSTD=11
- - compiler: clang
- addons:
- apt:
- sources:
- - llvm-toolchain-trusty-5.0
- - ubuntu-toolchain-r-test
- packages:
- - clang++-5.0
- - libc++-dev
- env: COMPILER=clang++-5.0 CXXSTD=11
- - compiler: clang
- addons:
- apt:
- sources:
- - llvm-toolchain-trusty-6.0
- - ubuntu-toolchain-r-test
- packages:
- - clang++-6.0
- - libc++-dev
- env: COMPILER=clang++-6.0 CXXSTD=11
-
- - compiler: gcc
- addons:
- apt:
- sources:
- - ubuntu-toolchain-r-test
- packages:
- - g++-5
- env: COMPILER=g++-5 CXXSTD=14
- - compiler: gcc
- addons:
- apt:
- sources:
- - ubuntu-toolchain-r-test
- packages:
- - g++-6
- env: COMPILER=g++-6 CXXSTD=14
- - compiler: gcc
- addons:
- apt:
- sources:
- - ubuntu-toolchain-r-test
- packages:
- - g++-7
- env: COMPILER=g++-7 CXXSTD=14
- - compiler: gcc
- addons:
- apt:
- sources:
- - ubuntu-toolchain-r-test
- packages:
- - g++-8
- env: COMPILER=g++-8 CXXSTD=14
- - compiler: clang
- addons:
- apt:
- sources:
- - llvm-toolchain-precise-3.5
- - ubuntu-toolchain-r-test
- packages:
- - clang++-3.5
- - libc++-dev
- env: COMPILER=clang++-3.5 CXXSTD=14
- - compiler: clang
- addons:
- apt:
- sources:
- - llvm-toolchain-precise-3.6
- - ubuntu-toolchain-r-test
- packages:
- - clang++-3.6
- - libc++-dev
- env: COMPILER=clang++-3.6 CXXSTD=14
- - compiler: clang
- addons:
- apt:
- sources:
- - llvm-toolchain-precise-3.7
- - ubuntu-toolchain-r-test
- packages:
- - clang++-3.7
- - libc++-dev
- env: COMPILER=clang++-3.7 CXXSTD=14
- - compiler: clang
- addons:
- apt:
- sources:
- - llvm-toolchain-precise-3.8
- - ubuntu-toolchain-r-test
- packages:
- - clang++-3.8
- - libc++-dev
- env: COMPILER=clang++-3.8 CXXSTD=14
- - compiler: clang
- addons:
- apt:
- sources:
- - sourceline: "deb http://apt.llvm.org/trusty/ llvm-toolchain-trusty-3.9 main"
- key_url: "http://apt.llvm.org/llvm-snapshot.gpg.key"
- - ubuntu-toolchain-r-test
- packages:
- - clang++-3.9
- - libc++-dev
- env: COMPILER=clang++-3.9 CXXSTD=14
- - compiler: clang
- addons:
- apt:
- sources:
- - llvm-toolchain-trusty-4.0
- - ubuntu-toolchain-r-test
- packages:
- - clang++-4.0
- - libc++-dev
- env: COMPILER=clang++-4.0 CXXSTD=14
- - compiler: clang
- addons:
- apt:
- sources:
- - llvm-toolchain-trusty-5.0
- - ubuntu-toolchain-r-test
- packages:
- - clang++-5.0
- - libc++-dev
- env: COMPILER=clang++-5.0 CXXSTD=14
- - compiler: clang
- addons:
- apt:
- sources:
- - llvm-toolchain-trusty-6.0
- - ubuntu-toolchain-r-test
- packages:
- - clang++-6.0
- - libc++-dev
- env: COMPILER=clang++-6.0 CXXSTD=14
-
-install:
- - if [ "$CXX" = "clang++" ]; then export CXX="$COMPILER -stdlib=libc++"; fi
- - if [ "$CXX" = "g++" ]; then export CXX="$COMPILER"; fi
-
-script: mkdir build && cd build && cmake -DCXXSTD=$CXXSTD .. && make && ./tests
diff --git a/third_party/optional/BUILD b/third_party/optional/BUILD
deleted file mode 100644
index 3599d61..0000000
--- a/third_party/optional/BUILD
+++ /dev/null
@@ -1,47 +0,0 @@
-licenses(["notice"])
-
-load("//tools:environments.bzl", "mcu_cpus")
-
-cc_library(
- name = "optional",
- hdrs = [
- "tl/optional.hpp",
- ],
- compatible_with = mcu_cpus,
- includes = ["."],
- visibility = ["//visibility:public"],
-)
-
-cc_library(
- name = "catch",
- hdrs = [
- "tests/catch.hpp",
- ],
-)
-
-# Create a small wrapper because the tests want to #include "optional.hpp"
-# directly.
-cc_library(
- name = "optional_test_wrapper",
- includes = [
- "./tl/",
- ],
- deps = [
- ":optional",
- ],
-)
-
-cc_test(
- name = "optional_test",
- srcs = glob([
- "tests/*.cpp",
- ]),
- copts = [
- "-fexceptions",
- "-Wno-unused-parameter",
- ],
- deps = [
- ":catch",
- ":optional_test_wrapper",
- ],
-)
diff --git a/third_party/optional/CMakeLists.txt b/third_party/optional/CMakeLists.txt
deleted file mode 100644
index 63720f6..0000000
--- a/third_party/optional/CMakeLists.txt
+++ /dev/null
@@ -1,52 +0,0 @@
-cmake_minimum_required(VERSION 3.0)
-
-project(optional)
-
-option(OPTIONAL_ENABLE_TESTS "Enable tests." ON)
-option(OPTIONAL_ENABLE_DOCS "Enable documentation." ON)
-
-add_library(optional INTERFACE)
-target_sources(optional INTERFACE ${CMAKE_CURRENT_SOURCE_DIR}/tl/optional.hpp)
-target_include_directories(optional INTERFACE ${CMAKE_CURRENT_SOURCE_DIR}/tl)
-
-if(OPTIONAL_ENABLE_TESTS)
- # Prepare "Catch" library for other executables
- set(CATCH_INCLUDE_DIR ${CMAKE_CURRENT_SOURCE_DIR}/test)
- add_library(Catch INTERFACE)
- target_include_directories(Catch INTERFACE ${CATCH_INCLUDE_DIR})
-
- # Make test executable
- set(TEST_SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/tests/main.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/tests/noexcept.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/tests/make_optional.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/tests/in_place.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/tests/relops.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/tests/observers.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/tests/extensions.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/tests/emplace.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/tests/constexpr.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/tests/constructors.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/tests/assignment.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/tests/issues.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/tests/bases.cpp
- ${CMAKE_CURRENT_SOURCE_DIR}/tests/nullopt.cpp)
-
- add_executable(tests ${TEST_SOURCES})
-
- target_link_libraries(tests Catch optional)
-
- set(CXXSTD 14 CACHE STRING "C++ standard to use, default C++14")
- set_property(TARGET tests PROPERTY CXX_STANDARD ${CXXSTD})
-endif()
-
-if(OPTIONAL_ENABLE_DOCS)
- find_package(standardese) # find standardese after installation
-
- # generates a custom target that will run standardese to generate the documentation
- if(standardese_FOUND)
- standardese_generate(optional
- INCLUDE_DIRECTORY tl
- CONFIG ${CMAKE_CURRENT_SOURCE_DIR}/standardese.config
- INPUT tl/optional.hpp)
- endif()
-endif()
diff --git a/third_party/optional/COPYING b/third_party/optional/COPYING
deleted file mode 100644
index 0e259d4..0000000
--- a/third_party/optional/COPYING
+++ /dev/null
@@ -1,121 +0,0 @@
-Creative Commons Legal Code
-
-CC0 1.0 Universal
-
- CREATIVE COMMONS CORPORATION IS NOT A LAW FIRM AND DOES NOT PROVIDE
- LEGAL SERVICES. DISTRIBUTION OF THIS DOCUMENT DOES NOT CREATE AN
- ATTORNEY-CLIENT RELATIONSHIP. CREATIVE COMMONS PROVIDES THIS
- INFORMATION ON AN "AS-IS" BASIS. CREATIVE COMMONS MAKES NO WARRANTIES
- REGARDING THE USE OF THIS DOCUMENT OR THE INFORMATION OR WORKS
- PROVIDED HEREUNDER, AND DISCLAIMS LIABILITY FOR DAMAGES RESULTING FROM
- THE USE OF THIS DOCUMENT OR THE INFORMATION OR WORKS PROVIDED
- HEREUNDER.
-
-Statement of Purpose
-
-The laws of most jurisdictions throughout the world automatically confer
-exclusive Copyright and Related Rights (defined below) upon the creator
-and subsequent owner(s) (each and all, an "owner") of an original work of
-authorship and/or a database (each, a "Work").
-
-Certain owners wish to permanently relinquish those rights to a Work for
-the purpose of contributing to a commons of creative, cultural and
-scientific works ("Commons") that the public can reliably and without fear
-of later claims of infringement build upon, modify, incorporate in other
-works, reuse and redistribute as freely as possible in any form whatsoever
-and for any purposes, including without limitation commercial purposes.
-These owners may contribute to the Commons to promote the ideal of a free
-culture and the further production of creative, cultural and scientific
-works, or to gain reputation or greater distribution for their Work in
-part through the use and efforts of others.
-
-For these and/or other purposes and motivations, and without any
-expectation of additional consideration or compensation, the person
-associating CC0 with a Work (the "Affirmer"), to the extent that he or she
-is an owner of Copyright and Related Rights in the Work, voluntarily
-elects to apply CC0 to the Work and publicly distribute the Work under its
-terms, with knowledge of his or her Copyright and Related Rights in the
-Work and the meaning and intended legal effect of CC0 on those rights.
-
-1. Copyright and Related Rights. A Work made available under CC0 may be
-protected by copyright and related or neighboring rights ("Copyright and
-Related Rights"). Copyright and Related Rights include, but are not
-limited to, the following:
-
- i. the right to reproduce, adapt, distribute, perform, display,
- communicate, and translate a Work;
- ii. moral rights retained by the original author(s) and/or performer(s);
-iii. publicity and privacy rights pertaining to a person's image or
- likeness depicted in a Work;
- iv. rights protecting against unfair competition in regards to a Work,
- subject to the limitations in paragraph 4(a), below;
- v. rights protecting the extraction, dissemination, use and reuse of data
- in a Work;
- vi. database rights (such as those arising under Directive 96/9/EC of the
- European Parliament and of the Council of 11 March 1996 on the legal
- protection of databases, and under any national implementation
- thereof, including any amended or successor version of such
- directive); and
-vii. other similar, equivalent or corresponding rights throughout the
- world based on applicable law or treaty, and any national
- implementations thereof.
-
-2. Waiver. To the greatest extent permitted by, but not in contravention
-of, applicable law, Affirmer hereby overtly, fully, permanently,
-irrevocably and unconditionally waives, abandons, and surrenders all of
-Affirmer's Copyright and Related Rights and associated claims and causes
-of action, whether now known or unknown (including existing as well as
-future claims and causes of action), in the Work (i) in all territories
-worldwide, (ii) for the maximum duration provided by applicable law or
-treaty (including future time extensions), (iii) in any current or future
-medium and for any number of copies, and (iv) for any purpose whatsoever,
-including without limitation commercial, advertising or promotional
-purposes (the "Waiver"). Affirmer makes the Waiver for the benefit of each
-member of the public at large and to the detriment of Affirmer's heirs and
-successors, fully intending that such Waiver shall not be subject to
-revocation, rescission, cancellation, termination, or any other legal or
-equitable action to disrupt the quiet enjoyment of the Work by the public
-as contemplated by Affirmer's express Statement of Purpose.
-
-3. Public License Fallback. Should any part of the Waiver for any reason
-be judged legally invalid or ineffective under applicable law, then the
-Waiver shall be preserved to the maximum extent permitted taking into
-account Affirmer's express Statement of Purpose. In addition, to the
-extent the Waiver is so judged Affirmer hereby grants to each affected
-person a royalty-free, non transferable, non sublicensable, non exclusive,
-irrevocable and unconditional license to exercise Affirmer's Copyright and
-Related Rights in the Work (i) in all territories worldwide, (ii) for the
-maximum duration provided by applicable law or treaty (including future
-time extensions), (iii) in any current or future medium and for any number
-of copies, and (iv) for any purpose whatsoever, including without
-limitation commercial, advertising or promotional purposes (the
-"License"). The License shall be deemed effective as of the date CC0 was
-applied by Affirmer to the Work. Should any part of the License for any
-reason be judged legally invalid or ineffective under applicable law, such
-partial invalidity or ineffectiveness shall not invalidate the remainder
-of the License, and in such case Affirmer hereby affirms that he or she
-will not (i) exercise any of his or her remaining Copyright and Related
-Rights in the Work or (ii) assert any associated claims and causes of
-action with respect to the Work, in either case contrary to Affirmer's
-express Statement of Purpose.
-
-4. Limitations and Disclaimers.
-
- a. No trademark or patent rights held by Affirmer are waived, abandoned,
- surrendered, licensed or otherwise affected by this document.
- b. Affirmer offers the Work as-is and makes no representations or
- warranties of any kind concerning the Work, express, implied,
- statutory or otherwise, including without limitation warranties of
- title, merchantability, fitness for a particular purpose, non
- infringement, or the absence of latent or other defects, accuracy, or
- the present or absence of errors, whether or not discoverable, all to
- the greatest extent permissible under applicable law.
- c. Affirmer disclaims responsibility for clearing rights of other persons
- that may apply to the Work or any use thereof, including without
- limitation any person's Copyright and Related Rights in the Work.
- Further, Affirmer disclaims responsibility for obtaining any necessary
- consents, permissions or other rights required for any use of the
- Work.
- d. Affirmer understands and acknowledges that Creative Commons is not a
- party to this document and has no duty or obligation with respect to
- this CC0 or use of the Work.
diff --git a/third_party/optional/README.md b/third_party/optional/README.md
deleted file mode 100644
index 90d3000..0000000
--- a/third_party/optional/README.md
+++ /dev/null
@@ -1,127 +0,0 @@
-# optional
-Single header implementation of `std::optional` with functional-style extensions and support for references.
-
-Clang + GCC: [](https://travis-ci.org/TartanLlama/optional)
-MSVC: [](https://ci.appveyor.com/project/TartanLlama/optional)
-
-`std::optional` is the preferred way to represent an object which may or may not have a value. Unfortunately, chaining together many computations which may or may not produce a value can be verbose, as empty-checking code will be mixed in with the actual programming logic. This implementation provides a number of utilities to make coding with `optional` cleaner.
-
-For example, instead of writing this code:
-
-```c++
-std::optional<image> get_cute_cat (const image& img) {
- auto cropped = crop_to_cat(img);
- if (!cropped) {
- return std::nullopt;
- }
-
- auto with_tie = add_bow_tie(*cropped);
- if (!with_tie) {
- return std::nullopt;
- }
-
- auto with_sparkles = make_eyes_sparkle(*with_tie);
- if (!with_sparkles) {
- return std::nullopt;
- }
-
- return add_rainbow(make_smaller(*with_sparkles));
-}
-```
-
-You can do this:
-
-```c++
-tl::optional<image> get_cute_cat (const image& img) {
- return crop_to_cat(img)
- .and_then(add_bow_tie)
- .and_then(make_eyes_sparkle)
- .map(make_smaller)
- .map(add_rainbow);
-}
-```
-
-Full documentation available at [optional.tartanllama.xyz](https://optional.tartanllama.xyz)
-
-The interface is the same as `std::optional`, but the following member functions are also defined. Explicit types are for clarity.
-
-- `map`: carries out some operation on the stored object if there is one.
- * `tl::optional<std::size_t> s = opt_string.map(&std::string::size);`
-- `and_then`: like `map`, but for operations which return a `tl::optional`.
- * `tl::optional<int> stoi (const std::string& s);`
- * `tl::optional<int> i = opt_string.and_then(stoi);`
-- `or_else`: calls some function if there is no value stored.
- * `opt.or_else([] { throw std::runtime_error{"oh no"}; });`
-- `map_or`: carries out a `map` if there is a value, otherwise returns a default value.
- * `tl::optional<std::size_t> s = opt_string.map_or(&std::string::size, 0);`
-- `map_or_else`: carries out a `map` if there is a value, otherwise returns the result of a given default function.
- * `std::size_t get_default();`
- * `tl::optional<std::size_t> s = opt_string.map_or(&std::string::size, get_default);`
-- `conjunction`: returns the argument if a value is stored in the optional, otherwise an empty optional.
- * `tl::make_optional(42).conjunction(13); //13`
- * `tl::optional<int>){}.conjunction(13); //empty`
-- `disjunction`: returns the argument if the optional is empty, otherwise the current value.
- * `tl::make_optional(42).disjunction(13); //42`
- * `tl::optional<int>{}.disjunction(13); //13`
-- `take`: returns the current value, leaving the optional empty.
- * `opt_string.take().map(&std::string::size); //opt_string now empty;`
-
-In addition to those member functions, optional references are also supported:
-
-```c++
-int i = 42;
-tl::optional<int&> o = i;
-*o == 42; //true
-i = 12;
-*o = 12; //true
-&*o == &i; //true
-```
-
-Assignment has rebind semantics rather than assign-through semantics:
-
-```c++
-int j = 8;
-o = j;
-
-&*o == &j; //true
-```
-
-### Compiler support
-
-Tested on:
-
-
-- Linux
- * clang 6.0.1
- * clang 5.0.2
- * clang 4.0.1
- * clang 3.9
- * clang 3.8
- * clang 3.7
- * clang 3.6
- * clang 3.5
- * g++ 8.0.1
- * g++ 7.3
- * g++ 6.4
- * g++ 5.5
- * g++ 4.9
- * g++ 4.8
-- Windows
- * MSVC 2015
- * MSVC 2017
-
-### Dependencies
-
-Requires [Standardese](https://github.com/foonathan/standardese) for generating documentation.
-
-Requires [Catch](https://github.com/philsquared/Catch) for testing. This is bundled in the test directory.
-
-### Standards Proposal
-
-This library also serves as an implementation of WG21 standards paper [P0798R0: Monadic operations for std::optional](https://wg21.tartanllama.xyz/monadic-optional). This paper proposes adding `map`, `and_then`, and `or_else` to `std::optional`.
-
-----------
-
-[]("http://creativecommons.org/publicdomain/zero/1.0/")
-
-To the extent possible under law, [Simon Brand](https://twitter.com/TartanLlama) has waived all copyright and related or neighboring rights to the `optional` library. This work is published from: United Kingdom.
diff --git a/third_party/optional/docs/CNAME b/third_party/optional/docs/CNAME
deleted file mode 100644
index d680696..0000000
--- a/third_party/optional/docs/CNAME
+++ /dev/null
@@ -1 +0,0 @@
-optional.tartanllama.xyz
\ No newline at end of file
diff --git a/third_party/optional/docs/index.md b/third_party/optional/docs/index.md
deleted file mode 100644
index 0db9b0f..0000000
--- a/third_party/optional/docs/index.md
+++ /dev/null
@@ -1,1076 +0,0 @@
-# Header file `optional.hpp`<a id="optional.hpp"></a>
-
-<pre><code class="language-cpp">#define <a href='doc_optional.html#optional.hpp'>TL_OPTIONAL_HPP</a>
-
-#define <a href='doc_optional.html#optional.hpp'>TL_OPTIONAL_VERSION_MAJOR</a>
-
-#define <a href='doc_optional.html#optional.hpp'>TL_OPTIONAL_VERSION_MINOR</a>
-
-#define <a href='doc_optional.html#optional.hpp'>IS_TRIVIALLY_COPY_CONSTRUCTIBLE</a>(T)
-
-#define <a href='doc_optional.html#optional.hpp'>IS_TRIVIALLY_COPY_ASSIGNABLE</a>(T)
-
-#define <a href='doc_optional.html#optional.hpp'>IS_TRIVIALLY_DESTRUCTIBLE</a>(T)
-
-#define <a href='doc_optional.html#optional.hpp'>TL_OPTIONAL_CXX14</a>
-
-#define <a href='doc_optional.html#optional.hpp'>TL_MONOSTATE_INPLACE_MUTEX</a>
-
-#define <a href='doc_optional.html#optional.hpp'>TL_TRAITS_MUTEX</a>
-
-namespace <a href='doc_optional.html#optional.hpp'>tl</a>
-{
- class <a href='doc_optional.html#tl::monostate'>monostate</a>;
-
- struct <a href='doc_optional.html#tl::in_place_t'>in_place_t</a>;
-
- constexpr <a href='doc_optional.html#tl::in_place_t'>in_place_t{}</a> <a href='doc_optional.html#tl::in_place'>in_place</a>;
-
- struct <a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>;
-
- static constexpr nullopt_t nullopt;
-
- class <a href='doc_optional.html#optional.hpp'>bad_optional_access</a>;
-
- template <class T>
- class <a href='doc_optional.html#tl::optional-T-'>optional</a>;
-
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constoptional-U-&)'>operator==</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<U></a>& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constoptional-U-&)'>operator!=</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<U></a>& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constoptional-U-&)'>operator<</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<U></a>& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constoptional-U-&)'>operator></a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<U></a>& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constoptional-U-&)'>operator<=</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<U></a>& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constoptional-U-&)'>operator>=</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<U></a>& rhs);
-
- template <class T>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,tl::nullopt_t)'>operator==</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, <a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
- template <class T>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,tl::nullopt_t)'>operator==</a>(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs) noexcept;
- template <class T>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,tl::nullopt_t)'>operator!=</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, <a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
- template <class T>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,tl::nullopt_t)'>operator!=</a>(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs) noexcept;
- template <class T>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,tl::nullopt_t)'>operator<</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>&, <a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
- template <class T>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,tl::nullopt_t)'>operator<</a>(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs) noexcept;
- template <class T>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,tl::nullopt_t)'>operator<=</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, <a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
- template <class T>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,tl::nullopt_t)'>operator<=</a>(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>&) noexcept;
- template <class T>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,tl::nullopt_t)'>operator></a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, <a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
- template <class T>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,tl::nullopt_t)'>operator></a>(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>&) noexcept;
- template <class T>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,tl::nullopt_t)'>operator>=</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>&, <a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
- template <class T>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,tl::nullopt_t)'>operator>=</a>(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs) noexcept;
-
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constU&)'>operator==</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const U& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constU&)'>operator==</a>(const U& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constU&)'>operator!=</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const U& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constU&)'>operator!=</a>(const U& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constU&)'>operator<</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const U& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constU&)'>operator<</a>(const U& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constU&)'>operator<=</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const U& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constU&)'>operator<=</a>(const U& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constU&)'>operator></a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const U& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constU&)'>operator></a>(const U& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constU&)'>operator>=</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const U& rhs);
- template <class T, class U>
- constexpr bool <a href='doc_optional.html#tl::operator==(constoptional-T-&,constU&)'>operator>=</a>(const U& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs);
-
- template <class T>
- void swap(optional<T> &lhs, optional<T> &rhs);
-
- namespace <a href='doc_optional.html#optional.hpp'>detail</a>
- {
- struct <a href='doc_optional.html#optional.hpp'>i_am_secret</a>;
- }
-
- template <class T = detail::i_am_secret, class U, class Ret = detail::conditional_t<std::is_same<T, detail::i_am_secret>::value, detail::decay_t<U>, T>>
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional<Ret></a> <a href='doc_optional.html#optional.hpp'>make_optional</a>(U&& v);
-
- template <class T, class ... Args>
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional<T></a> <a href='doc_optional.html#optional.hpp'>make_optional</a>(Args&&... args);
-
- template <class T, class U, class ... Args>
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional<T></a> <a href='doc_optional.html#optional.hpp'>make_optional</a>(<a href='http://en.cppreference.com/mwiki/index.php?title=Special%3ASearch&search=std::initializer_list%3cU%3e'>std::initializer_list<U></a> il, Args&&... args);
-
- template <class T>
- class <a href='doc_optional.html#tl::optional-T&-'>optional<T&></a>;
-}
-
-namespace <a href='doc_optional.html#optional.hpp'>std</a>
-{
-}</code></pre>
-
-## Class `tl::monostate`<a id="tl::monostate"></a>
-
-<pre><code class="language-cpp">class monostate
-{
-};</code></pre>
-
-Used to represent an optional with no data; essentially a bool
-
-## Struct `tl::in_place_t`<a id="tl::in_place_t"></a>
-
-<pre><code class="language-cpp">struct in_place_t
-{
- <a href='doc_optional.html#tl::in_place_t'>in_place_t</a>() = default;
-};</code></pre>
-
-A tag type to tell optional to construct its value in-place
-
-## Variable `tl::in_place`<a id="tl::in_place"></a>
-
-<pre><code class="language-cpp">constexpr <a href='doc_optional.html#tl::in_place_t'>in_place_t{}</a> in_place;</code></pre>
-
-A tag to tell optional to construct its value in-place
-
-## Struct `tl::nullopt_t`<a id="tl::nullopt_t"></a>
-
-<pre><code class="language-cpp">struct nullopt_t
-{
- struct <a href='doc_optional.html#tl::nullopt_t'>do_not_use</a>;
-
- constexpr <a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>(<a href='doc_optional.html#tl::nullopt_t'>do_not_use</a>, <a href='doc_optional.html#tl::nullopt_t'>do_not_use</a>) noexcept;
-};</code></pre>
-
-A tag type to represent an empty optional
-
-## Variable `tl::nullopt`<a id="tl::nullopt"></a>
-
-<pre><code class="language-cpp">static constexpr nullopt_t nullopt;</code></pre>
-
-Represents an empty optional
-
-*Examples*:
-
- tl::optional<int> a = tl::nullopt;
- void foo (tl::optional<int>);
- foo(tl::nullopt); //pass an empty optional
-
-## Class template `tl::optional`<a id="tl::optional-T-"></a>
-
-<pre><code class="language-cpp">template <class T>
-class optional
-{
-public:
- template <class F>
- constexpr auto and_then(F &&f) &;
- template <class F>
- constexpr auto and_then(F &&f) &&;
- template <class F>
- constexpr auto and_then(F &&f) const &;
- template <class F>
- constexpr auto and_then(F &&f) const &&;
-
- template <class F> constexpr auto map(F &&f) &;
- template <class F> constexpr auto map(F &&f) &&;
- template <class F> constexpr auto map(F &&f) const&;
- template <class F> constexpr auto map(F &&f) const&&;
-
- template <class F> optional<T> or_else (F &&f) &;
- template <class F> optional<T> or_else (F &&f) &&;
- template <class F> optional<T> or_else (F &&f) const &;
-
- template <class F, class U>
- U <a href='doc_optional.html#tl::optional-T-::map_or(F&&,U&&)&'>map_or</a>(F&& f, U&& u) &;
- template <class F, class U>
- U <a href='doc_optional.html#tl::optional-T-::map_or(F&&,U&&)&'>map_or</a>(F&& f, U&& u) &&;
- template <class F, class U>
- U <a href='doc_optional.html#tl::optional-T-::map_or(F&&,U&&)&'>map_or</a>(F&& f, U&& u) const &;
- template <class F, class U>
- U <a href='doc_optional.html#tl::optional-T-::map_or(F&&,U&&)&'>map_or</a>(F&& f, U&& u) const &&;
-
- template <class F, class U>
- auto map_or_else(F &&f, U &&u) &;
- template <class F, class U>
- auto map_or_else(F &&f, U &&u)
- template <class F, class U>
- auto map_or_else(F &&f, U &&u)
- template <class F, class U>
- auto map_or_else(F &&f, U &&u)
-
- template <class U>
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional<typename std::decay<U>::type></a> <a href='doc_optional.html#tl::optional-T-::conjunction(U&&)const'>conjunction</a>(U&& u) const;
-
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T-::disjunction(constoptional-T-&)&'>disjunction</a>(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) &;
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T-::disjunction(constoptional-T-&)&'>disjunction</a>(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) const &;
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T-::disjunction(constoptional-T-&)&'>disjunction</a>(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) &&;
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T-::disjunction(constoptional-T-&)&'>disjunction</a>(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) const &&;
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T-::disjunction(constoptional-T-&)&'>disjunction</a>(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) &;
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T-::disjunction(constoptional-T-&)&'>disjunction</a>(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) const &;
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T-::disjunction(constoptional-T-&)&'>disjunction</a>(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) &&;
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T-::disjunction(constoptional-T-&)&'>disjunction</a>(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) const &&;
-
- <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T-::take()&'>take</a>() &;
- <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T-::take()&'>take</a>() const &;
- <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T-::take()&'>take</a>() &&;
- <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T-::take()&'>take</a>() const &&;
-
- using <a href='doc_optional.html#tl::optional-T-'>value_type</a> = T;
-
- constexpr <a href='doc_optional.html#tl::optional-T-::optional()'>optional</a>() noexcept = default;
- constexpr <a href='doc_optional.html#tl::optional-T-::optional()'>optional</a>(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
-
- constexpr <a href='doc_optional.html#tl::optional-T-::optional(constoptional-T-&)'>optional</a>(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) = default;
-
- constexpr <a href='doc_optional.html#tl::optional-T-::optional(optional-T-&&)'>optional</a>(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) = default;
-
- template <class... Args> constexpr explicit optional(in_place_t, Args&&... args);
- template <class U, class... Args>
- constexpr explicit optional(in_place_t, std::initializer_list<U>&, Args&&... args);
-
- template <class U=T> constexpr optional(U &&u);
-
- template <class U> optional(const optional<U> &rhs);
-
- template <class U> optional(optional<U> &&rhs);
-
- <a href='doc_optional.html#tl::optional-T-::~optional()'>~optional</a>() = default;
-
- <a href='doc_optional.html#tl::optional-T-'>optional</a>& <a href='doc_optional.html#tl::optional-T-::operator=(tl::nullopt_t)'>operator=</a>(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
-
- <a href='doc_optional.html#tl::optional-T-'>optional</a>& <a href='doc_optional.html#tl::optional-T-::operator=(constoptional-T-&)'>operator=</a>(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) = default;
-
- <a href='doc_optional.html#tl::optional-T-'>optional</a>& <a href='doc_optional.html#tl::optional-T-::operator=(optional-T-&&)'>operator=</a>(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) = default;
-
- optional &operator=(U &&u);
-
- optional &operator=(const optional<U> & rhs);
-
- optional &operator=(optional<U> && rhs);
-
- template <class ... Args>
- T& <a href='doc_optional.html#tl::optional-T-::emplace(Args&&...)'>emplace</a>(Args&&... args);
- template <class U, class... Args>
- T& emplace(std::initializer_list<U> il, Args &&... args);
-
- void <a href='doc_optional.html#tl::optional-T-::swap(optional-T-&)'>swap</a>(<a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) noexcept(std::is_nothrow_move_constructible<T>::value&&detail::is_nothrow_swappable<T>::value);
-
- constexpr const T *operator->() const;
- constexpr T *operator->();
-
- constexpr T &operator*();
- constexpr const T &operator*() const;
-
- constexpr bool <a href='doc_optional.html#tl::optional-T-::has_value()const'>has_value</a>() const noexcept;
- constexpr <a href='doc_optional.html#tl::optional-T-::has_value()const'>operator bool</a>() const noexcept;
-
- constexpr T &value();
- constexpr const T &value() const;
-
- template <class U>
- constexpr T <a href='doc_optional.html#tl::optional-T-::value_or(U&&)const&'>value_or</a>(U&& u) const &;
- template <class U>
- constexpr T <a href='doc_optional.html#tl::optional-T-::value_or(U&&)const&'>value_or</a>(U&& u) &&;
-
- void <a href='doc_optional.html#tl::optional-T-::reset()'>reset</a>() noexcept;
-};</code></pre>
-
-An optional object is an object that contains the storage for another object and manages the lifetime of this contained object, if any. The contained object may be initialized after the optional object has been initialized, and may be destroyed before the optional object has been destroyed. The initialization state of the contained object is tracked by the optional object.
-
-### Function template `tl::optional::and_then`<a id="tl::optional-T-::and_then(F&&)&"></a>
-
-<pre><code class="language-cpp">(1) template <class F>
- constexpr auto and_then(F &&f) &;
-
-(2) template <class F>
- constexpr auto and_then(F &&f) &&;
-
-(3) template <class F>
- constexpr auto and_then(F &&f) const &;
-
-(4) template <class F>
- constexpr auto and_then(F &&f) const &&;</code></pre>
-
-Carries out some operation which returns an optional on the stored object if there is one. \\requires `std::invoke(std::forward<F>(f), value())` returns a `std::optional<U>` for some `U`. \\returns Let `U` be the result of `std::invoke(std::forward<F>(f), value())`. Returns a `std::optional<U>`. The return value is empty if `*this` is empty, otherwise the return value of `std::invoke(std::forward<F>(f), value())` is returned.
-
-### Function template `tl::optional::map`<a id="tl::optional-T-::map(F&&)&"></a>
-
-<pre><code class="language-cpp">(1) template <class F> constexpr auto map(F &&f) &;
-
-(2) template <class F> constexpr auto map(F &&f) &&;
-
-(3) template <class F> constexpr auto map(F &&f) const&;
-
-(4) template <class F> constexpr auto map(F &&f) const&&;</code></pre>
-
-Carries out some operation on the stored object if there is one.
-
-*Returns*: Let `U` be the result of `std::invoke(std::forward<F>(f), value())`. Returns a `std::optional<U>`. The return value is empty if `*this` is empty, otherwise an `optional<U>` is constructed from the return value of `std::invoke(std::forward<F>(f), value())` and is returned.
-
-### Function template `tl::optional::or_else`<a id="tl::optional-T-::or_else(F&&)&"></a>
-
-<pre><code class="language-cpp">(1) template <class F> optional<T> or_else (F &&f) &;
-
-(2) template <class F> optional<T> or_else (F &&f) &&;
-
-(3) template <class F> optional<T> or_else (F &&f) const &;</code></pre>
-
-Calls `f` if the optional is empty
-
-*Requires*: `std::invoke_result_t<F>` must be void or convertible to `optional<T>`.
-
-*Effects*: If `*this` has a value, returns `*this`. Otherwise, if `f` returns `void`, calls `std::forward<F>(f)` and returns `std::nullopt`. Otherwise, returns `std::forward<F>(f)()`.
-
-### Function template `tl::optional::map_or`<a id="tl::optional-T-::map_or(F&&,U&&)&"></a>
-
-<pre><code class="language-cpp">(1) template <class F, class U>
- U map_or(F&& f, U&& u) &;
-
-(2) template <class F, class U>
- U map_or(F&& f, U&& u) &&;
-
-(3) template <class F, class U>
- U map_or(F&& f, U&& u) const &;
-
-(4) template <class F, class U>
- U map_or(F&& f, U&& u) const &&;</code></pre>
-
-Maps the stored value with `f` if there is one, otherwise returns `u`.
-
-If there is a value stored, then `f` is called with `**this` and the value is returned. Otherwise `u` is returned.
-
-### Function template `tl::optional::map_or_else`<a id="tl::optional-T-::map_or_else(F&&,U&&)&"></a>
-
-<pre><code class="language-cpp">(1) template <class F, class U>
- auto map_or_else(F &&f, U &&u) &;
-
-(2) template <class F, class U>
- auto map_or_else(F &&f, U &&u)
-
-(3) template <class F, class U>
- auto map_or_else(F &&f, U &&u)
-
-(4) template <class F, class U>
- auto map_or_else(F &&f, U &&u)</code></pre>
-
-Maps the stored value with `f` if there is one, otherwise calls `u` and returns the result.
-
-If there is a value stored, then `f` is called with `**this` and the value is returned. Otherwise `std::forward<U>(u)()` is returned.
-
-### Function template `tl::optional::conjunction`<a id="tl::optional-T-::conjunction(U&&)const"></a>
-
-<pre><code class="language-cpp">template <class U>
-constexpr <a href='doc_optional.html#tl::optional-T-'>optional<typename std::decay<U>::type></a> conjunction(U&& u) const;</code></pre>
-
-*Returns*: `u` if `*this` has a value, otherwise an empty optional.
-
-### Function `tl::optional::disjunction`<a id="tl::optional-T-::disjunction(constoptional-T-&)&"></a>
-
-<pre><code class="language-cpp">(1) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) &;
-
-(2) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) const &;
-
-(3) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) &&;
-
-(4) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) const &&;
-
-(5) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) &;
-
-(6) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) const &;
-
-(7) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) &&;
-
-(8) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) const &&;</code></pre>
-
-*Returns*: `rhs` if `*this` is empty, otherwise the current value.
-
-### Function `tl::optional::take`<a id="tl::optional-T-::take()&"></a>
-
-<pre><code class="language-cpp">(1) <a href='doc_optional.html#tl::optional-T-'>optional</a> take() &;
-
-(2) <a href='doc_optional.html#tl::optional-T-'>optional</a> take() const &;
-
-(3) <a href='doc_optional.html#tl::optional-T-'>optional</a> take() &&;
-
-(4) <a href='doc_optional.html#tl::optional-T-'>optional</a> take() const &&;</code></pre>
-
-Takes the value out of the optional, leaving it empty
-
-### Default constructor `tl::optional::optional`<a id="tl::optional-T-::optional()"></a>
-
-<pre><code class="language-cpp">(1) constexpr optional() noexcept = default;
-
-(2) constexpr optional(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;</code></pre>
-
-Constructs an optional that does not contain a value.
-
-### Copy constructor `tl::optional::optional`<a id="tl::optional-T-::optional(constoptional-T-&)"></a>
-
-<pre><code class="language-cpp">constexpr optional(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) = default;</code></pre>
-
-Copy constructor
-
-If `rhs` contains a value, the stored value is direct-initialized with it. Otherwise, the constructed optional is empty.
-
-### Move constructor `tl::optional::optional`<a id="tl::optional-T-::optional(optional-T-&&)"></a>
-
-<pre><code class="language-cpp">constexpr optional(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) = default;</code></pre>
-
-Move constructor
-
-If `rhs` contains a value, the stored value is direct-initialized with it. Otherwise, the constructed optional is empty.
-
-### Function template `tl::optional::optional`<a id="tl::optional-T-::optional(detail::enable_if_t-std::is_constructible-T,Args...-::value,in_place_t-,Args&&...)"></a>
-
-<pre><code class="language-cpp">(1) template <class... Args> constexpr explicit optional(in_place_t, Args&&... args);
-
-(2) template <class U, class... Args>
- constexpr explicit optional(in_place_t, std::initializer_list<U>&, Args&&... args);</code></pre>
-
-Constructs the stored value in-place using the given arguments.
-
-### Function template `tl::optional::optional`<a id="tl::optional-T-::optional(U&&)"></a>
-
-<pre><code class="language-cpp">template <class U=T> constexpr optional(U &&u);</code></pre>
-
-Constructs the stored value with `u`.
-
-### Function template `tl::optional::optional`<a id="tl::optional-T-::optional(constoptional-U-&)"></a>
-
-<pre><code class="language-cpp">template <class U> optional(const optional<U> &rhs);</code></pre>
-
-Converting copy constructor.
-
-### Function template `tl::optional::optional`<a id="tl::optional-T-::optional(optional-U-&&)"></a>
-
-<pre><code class="language-cpp">template <class U> optional(optional<U> &&rhs);</code></pre>
-
-Converting move constructor.
-
-### Destructor `tl::optional::~optional`<a id="tl::optional-T-::~optional()"></a>
-
-<pre><code class="language-cpp">~optional() = default;</code></pre>
-
-Destroys the stored value if there is one.
-
-### Assignment operator `tl::optional::operator=`<a id="tl::optional-T-::operator=(tl::nullopt_t)"></a>
-
-<pre><code class="language-cpp"><a href='doc_optional.html#tl::optional-T-'>optional</a>& operator=(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;</code></pre>
-
-Assignment to empty.
-
-Destroys the current value if there is one.
-
-### Assignment operator `tl::optional::operator=`<a id="tl::optional-T-::operator=(constoptional-T-&)"></a>
-
-<pre><code class="language-cpp"><a href='doc_optional.html#tl::optional-T-'>optional</a>& operator=(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) = default;</code></pre>
-
-Copy assignment.
-
-Copies the value from `rhs` if there is one. Otherwise resets the stored value in `*this`.
-
-### Assignment operator `tl::optional::operator=`<a id="tl::optional-T-::operator=(optional-T-&&)"></a>
-
-<pre><code class="language-cpp"><a href='doc_optional.html#tl::optional-T-'>optional</a>& operator=(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) = default;</code></pre>
-
-Move assignment.
-
-Moves the value from `rhs` if there is one. Otherwise resets the stored value in `*this`.
-
-### Assignment operator `tl::optional::operator=`<a id="tl::optional-T-::operator=(U&&)"></a>
-
-<pre><code class="language-cpp">optional &operator=(U &&u);</code></pre>
-
-Assigns the stored value from `u`, destroying the old value if there was one.
-
-### Assignment operator `tl::optional::operator=`<a id="tl::optional-T-::operator=(constoptional-U-&)"></a>
-
-<pre><code class="language-cpp">optional &operator=(const optional<U> & rhs);</code></pre>
-
-Converting copy assignment operator.
-
-Copies the value from `rhs` if there is one. Otherwise resets the stored value in `*this`.
-
-### Assignment operator `tl::optional::operator=`<a id="tl::optional-T-::operator=(optional-U-&&)"></a>
-
-<pre><code class="language-cpp">optional &operator=(optional<U> && rhs);</code></pre>
-
-Converting move assignment operator.
-
-Moves the value from `rhs` if there is one. Otherwise resets the stored value in `*this`.
-
-### Function template `tl::optional::emplace`<a id="tl::optional-T-::emplace(Args&&...)"></a>
-
-<pre><code class="language-cpp">(1) template <class ... Args>
- T& emplace(Args&&... args);
-
-(2) template <class U, class... Args>
- T& emplace(std::initializer_list<U> il, Args &&... args);</code></pre>
-
-Constructs the value in-place, destroying the current one if there is one.
-
-### Function `tl::optional::swap`<a id="tl::optional-T-::swap(optional-T-&)"></a>
-
-<pre><code class="language-cpp">void swap(<a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) noexcept(std::is_nothrow_move_constructible<T>::value&&detail::is_nothrow_swappable<T>::value);</code></pre>
-
-Swaps this optional with the other.
-
-If neither optionals have a value, nothing happens. If both have a value, the values are swapped. If one has a value, it is moved to the other and the movee is left valueless.
-
-### Operator `tl::optional::operator->`<a id="tl::optional-T-::operator--()const"></a>
-
-<pre><code class="language-cpp">(1) constexpr const T *operator->() const;
-
-(2) constexpr T *operator->();</code></pre>
-
-*Returns*: a pointer to the stored value
-
-*Requires*: a value is stored
-
-### Operator `tl::optional::operator*`<a id="tl::optional-T-::operator*()&"></a>
-
-<pre><code class="language-cpp">(1) constexpr T &operator*();
-
-(2) constexpr const T &operator*() const;</code></pre>
-
-*Returns*: the stored value
-
-*Requires*: a value is stored
-
-### Function `tl::optional::has_value`<a id="tl::optional-T-::has_value()const"></a>
-
-<pre><code class="language-cpp">(1) constexpr bool has_value() const noexcept;
-
-(2) constexpr operator bool() const noexcept;</code></pre>
-
-*Returns*: whether or not the optional has a value
-
-### Function `tl::optional::value`<a id="tl::optional-T-::value()&"></a>
-
-<pre><code class="language-cpp">(1) constexpr T &value();
-
-(2) constexpr const T &value() const;</code></pre>
-
-*Returns*: the contained value if there is one, otherwise throws \[bad\_optional\_access\]
-
-### Function template `tl::optional::value_or`<a id="tl::optional-T-::value_or(U&&)const&"></a>
-
-<pre><code class="language-cpp">(1) template <class U>
- constexpr T value_or(U&& u) const &;
-
-(2) template <class U>
- constexpr T value_or(U&& u) &&;</code></pre>
-
-*Returns*: the stored value if there is one, otherwise returns `u`
-
-### Function `tl::optional::reset`<a id="tl::optional-T-::reset()"></a>
-
-<pre><code class="language-cpp">void reset() noexcept;</code></pre>
-
-Destroys the stored value if one exists, making the optional empty
-
------
-
-## Comparison operator `tl::operator==`<a id="tl::operator==(constoptional-T-&,constoptional-U-&)"></a>
-
-<pre><code class="language-cpp">(1) template <class T, class U>
- constexpr bool operator==(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<U></a>& rhs);
-
-(2) template <class T, class U>
- constexpr bool operator!=(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<U></a>& rhs);
-
-(3) template <class T, class U>
- constexpr bool operator<(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<U></a>& rhs);
-
-(4) template <class T, class U>
- constexpr bool operator>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<U></a>& rhs);
-
-(5) template <class T, class U>
- constexpr bool operator<=(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<U></a>& rhs);
-
-(6) template <class T, class U>
- constexpr bool operator>=(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<U></a>& rhs);</code></pre>
-
-Compares two optional objects
-
-If both optionals contain a value, they are compared with `T`s relational operators. Otherwise `lhs` and `rhs` are equal only if they are both empty, and `lhs` is less than `rhs` only if `rhs` is empty and `lhs` is not.
-
-## Comparison operator `tl::operator==`<a id="tl::operator==(constoptional-T-&,tl::nullopt_t)"></a>
-
-<pre><code class="language-cpp">(1) template <class T>
- constexpr bool operator==(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, <a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
-
-(2) template <class T>
- constexpr bool operator==(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs) noexcept;
-
-(3) template <class T>
- constexpr bool operator!=(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, <a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
-
-(4) template <class T>
- constexpr bool operator!=(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs) noexcept;
-
-(5) template <class T>
- constexpr bool operator<(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>&, <a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
-
-(6) template <class T>
- constexpr bool operator<(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs) noexcept;
-
-(7) template <class T>
- constexpr bool operator<=(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, <a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
-
-(8) template <class T>
- constexpr bool operator<=(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>&) noexcept;
-
-(9) template <class T>
- constexpr bool operator>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, <a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
-
-(10) template <class T>
- constexpr bool operator>(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>&) noexcept;
-
-(11) template <class T>
- constexpr bool operator>=(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>&, <a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
-
-(12) template <class T>
- constexpr bool operator>=(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs) noexcept;</code></pre>
-
-Compares an optional to a `nullopt`
-
-Equivalent to comparing the optional to an empty optional
-
-## Comparison operator `tl::operator==`<a id="tl::operator==(constoptional-T-&,constU&)"></a>
-
-<pre><code class="language-cpp">(1) template <class T, class U>
- constexpr bool operator==(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const U& rhs);
-
-(2) template <class T, class U>
- constexpr bool operator==(const U& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs);
-
-(3) template <class T, class U>
- constexpr bool operator!=(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const U& rhs);
-
-(4) template <class T, class U>
- constexpr bool operator!=(const U& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs);
-
-(5) template <class T, class U>
- constexpr bool operator<(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const U& rhs);
-
-(6) template <class T, class U>
- constexpr bool operator<(const U& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs);
-
-(7) template <class T, class U>
- constexpr bool operator<=(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const U& rhs);
-
-(8) template <class T, class U>
- constexpr bool operator<=(const U& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs);
-
-(9) template <class T, class U>
- constexpr bool operator>(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const U& rhs);
-
-(10) template <class T, class U>
- constexpr bool operator>(const U& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs);
-
-(11) template <class T, class U>
- constexpr bool operator>=(const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& lhs, const U& rhs);
-
-(12) template <class T, class U>
- constexpr bool operator>=(const U& lhs, const <a href='doc_optional.html#tl::optional-T-'>optional<T></a>& rhs);</code></pre>
-
-Compares the optional with a value.
-
-If the optional has a value, it is compared with the other value using `T`s relational operators. Otherwise, the optional is considered less than the value.
-
-## Class template `tl::optional<T&>`<a id="tl::optional-T&-"></a>
-
-<pre><code class="language-cpp">template <class T>
-class optional<T&>
-{
-public:
- template <class F>
- constexpr auto and_then(F &&f) &;
- template <class F>
- constexpr auto and_then(F &&f) &&;
- template <class F>
- constexpr auto and_then(F &&f) const &;
- template <class F>
- constexpr auto and_then(F &&f) const &&;
-
- template <class F> constexpr auto map(F &&f) &;
- template <class F> constexpr auto map(F &&f) &&;
- template <class F> constexpr auto map(F &&f) const&;
- template <class F> constexpr auto map(F &&f) const&&;
-
- template <class F> optional<T> or_else (F &&f) &;
- template <class F> optional<T> or_else (F &&f) &&;
- template <class F> optional<T> or_else (F &&f) const &;
-
- template <class F, class U>
- U <a href='doc_optional.html#tl::optional-T&-::map_or(F&&,U&&)&'>map_or</a>(F&& f, U&& u) &;
- template <class F, class U>
- U <a href='doc_optional.html#tl::optional-T&-::map_or(F&&,U&&)&'>map_or</a>(F&& f, U&& u) &&;
- template <class F, class U>
- U <a href='doc_optional.html#tl::optional-T&-::map_or(F&&,U&&)&'>map_or</a>(F&& f, U&& u) const &;
- template <class F, class U>
- U <a href='doc_optional.html#tl::optional-T&-::map_or(F&&,U&&)&'>map_or</a>(F&& f, U&& u) const &&;
-
- template <class F, class U>
- auto map_or_else(F &&f, U &&u) &;
- template <class F, class U>
- auto map_or_else(F &&f, U &&u)
- template <class F, class U>
- auto map_or_else(F &&f, U &&u)
- template <class F, class U>
- auto map_or_else(F &&f, U &&u)
-
- template <class U>
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional<typename std::decay<U>::type></a> <a href='doc_optional.html#tl::optional-T&-::conjunction(U&&)const'>conjunction</a>(U&& u) const;
-
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T&-::disjunction(constoptional&)&'>disjunction</a>(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) &;
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T&-::disjunction(constoptional&)&'>disjunction</a>(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) const &;
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T&-::disjunction(constoptional&)&'>disjunction</a>(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) &&;
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T&-::disjunction(constoptional&)&'>disjunction</a>(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) const &&;
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T&-::disjunction(constoptional&)&'>disjunction</a>(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) &;
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T&-::disjunction(constoptional&)&'>disjunction</a>(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) const &;
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T&-::disjunction(constoptional&)&'>disjunction</a>(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) &&;
- constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T&-::disjunction(constoptional&)&'>disjunction</a>(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) const &&;
-
- <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T&-::take()&'>take</a>() &;
- <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T&-::take()&'>take</a>() const &;
- <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T&-::take()&'>take</a>() &&;
- <a href='doc_optional.html#tl::optional-T-'>optional</a> <a href='doc_optional.html#tl::optional-T&-::take()&'>take</a>() const &&;
-
- using <a href='doc_optional.html#tl::optional-T&-'>value_type</a> = T&;
-
- constexpr <a href='doc_optional.html#tl::optional-T&-::optional()'>optional</a>() noexcept;
- constexpr <a href='doc_optional.html#tl::optional-T&-::optional()'>optional</a>(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
-
- constexpr <a href='doc_optional.html#tl::optional-T&-::optional(constoptional&)'>optional</a>(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) noexcept = default;
-
- constexpr <a href='doc_optional.html#tl::optional-T&-::optional(optional&&)'>optional</a>(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) = default;
-
- template <class U=T> constexpr optional(U &&u);
-
- <a href='doc_optional.html#tl::optional-T&-::~optional()'>~optional</a>() = default;
-
- <a href='doc_optional.html#tl::optional-T-'>optional</a>& <a href='doc_optional.html#tl::optional-T&-::operator=(tl::nullopt_t)'>operator=</a>(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;
-
- <a href='doc_optional.html#tl::optional-T-'>optional</a>& <a href='doc_optional.html#tl::optional-T&-::operator=(constoptional&)'>operator=</a>(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) = default;
-
- optional &operator=(U &&u);
-
- template <class U>
- <a href='doc_optional.html#tl::optional-T-'>optional</a>& <a href='doc_optional.html#tl::optional-T&-::operator=(constoptional-U-&)'>operator=</a>(const <a href='doc_optional.html#tl::optional-T-'>optional<U></a>& rhs);
-
- template <class ... Args>
- T& <a href='doc_optional.html#tl::optional-T&-::emplace(Args&&...)'>emplace</a>(Args&&... args) noexcept;
-
- void <a href='doc_optional.html#tl::optional-T&-::swap(optional&)'>swap</a>(<a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) noexcept;
-
- constexpr const T *operator->() const;
- constexpr T *operator->();
-
- constexpr T &operator*();
- constexpr const T &operator*() const;
-
- constexpr bool <a href='doc_optional.html#tl::optional-T&-::has_value()const'>has_value</a>() const noexcept;
- constexpr <a href='doc_optional.html#tl::optional-T&-::has_value()const'>operator bool</a>() const noexcept;
-
- constexpr T& <a href='doc_optional.html#tl::optional-T&-::value()&'>value</a>() &;
- constexpr const T &value() const;
-
- template <class U>
- constexpr T <a href='doc_optional.html#tl::optional-T&-::value_or(U&&)const&'>value_or</a>(U&& u) const &;
- template <class U>
- constexpr T <a href='doc_optional.html#tl::optional-T&-::value_or(U&&)const&'>value_or</a>(U&& u) &&;
-
- void <a href='doc_optional.html#tl::optional-T&-::reset()'>reset</a>() noexcept;
-};</code></pre>
-
-Specialization for when `T` is a reference. `optional<T&>` acts similarly to a `T*`, but provides more operations and shows intent more clearly.
-
-*Examples*:
-
- int i = 42;
- tl::optional<int&> o = i;
- *o == 42; //true
- i = 12;
- *o = 12; //true
- &*o == &i; //true
-
-Assignment has rebind semantics rather than assign-through semantics:
-
- int j = 8;
- o = j;
-
- &*o == &j; //true
-
-### Function template `tl::optional<T&>::and_then`<a id="tl::optional-T&-::and_then(F&&)&"></a>
-
-<pre><code class="language-cpp">(1) template <class F>
- constexpr auto and_then(F &&f) &;
-
-(2) template <class F>
- constexpr auto and_then(F &&f) &&;
-
-(3) template <class F>
- constexpr auto and_then(F &&f) const &;
-
-(4) template <class F>
- constexpr auto and_then(F &&f) const &&;</code></pre>
-
-Carries out some operation which returns an optional on the stored object if there is one. \\requires `std::invoke(std::forward<F>(f), value())` returns a `std::optional<U>` for some `U`. \\returns Let `U` be the result of `std::invoke(std::forward<F>(f), value())`. Returns a `std::optional<U>`. The return value is empty if `*this` is empty, otherwise the return value of `std::invoke(std::forward<F>(f), value())` is returned.
-
-### Function template `tl::optional<T&>::map`<a id="tl::optional-T&-::map(F&&)&"></a>
-
-<pre><code class="language-cpp">(1) template <class F> constexpr auto map(F &&f) &;
-
-(2) template <class F> constexpr auto map(F &&f) &&;
-
-(3) template <class F> constexpr auto map(F &&f) const&;
-
-(4) template <class F> constexpr auto map(F &&f) const&&;</code></pre>
-
-Carries out some operation on the stored object if there is one.
-
-*Returns*: Let `U` be the result of `std::invoke(std::forward<F>(f), value())`. Returns a `std::optional<U>`. The return value is empty if `*this` is empty, otherwise an `optional<U>` is constructed from the return value of `std::invoke(std::forward<F>(f), value())` and is returned.
-
-### Function template `tl::optional<T&>::or_else`<a id="tl::optional-T&-::or_else(F&&)&"></a>
-
-<pre><code class="language-cpp">(1) template <class F> optional<T> or_else (F &&f) &;
-
-(2) template <class F> optional<T> or_else (F &&f) &&;
-
-(3) template <class F> optional<T> or_else (F &&f) const &;</code></pre>
-
-Calls `f` if the optional is empty
-
-*Requires*: `std::invoke_result_t<F>` must be void or convertible to `optional<T>`. \\effects If `*this` has a value, returns `*this`. Otherwise, if `f` returns `void`, calls `std::forward<F>(f)` and returns `std::nullopt`. Otherwise, returns `std::forward<F>(f)()`.
-
-### Function template `tl::optional<T&>::map_or`<a id="tl::optional-T&-::map_or(F&&,U&&)&"></a>
-
-<pre><code class="language-cpp">(1) template <class F, class U>
- U map_or(F&& f, U&& u) &;
-
-(2) template <class F, class U>
- U map_or(F&& f, U&& u) &&;
-
-(3) template <class F, class U>
- U map_or(F&& f, U&& u) const &;
-
-(4) template <class F, class U>
- U map_or(F&& f, U&& u) const &&;</code></pre>
-
-Maps the stored value with `f` if there is one, otherwise returns `u`.
-
-If there is a value stored, then `f` is called with `**this` and the value is returned. Otherwise `u` is returned.
-
-### Function template `tl::optional<T&>::map_or_else`<a id="tl::optional-T&-::map_or_else(F&&,U&&)&"></a>
-
-<pre><code class="language-cpp">(1) template <class F, class U>
- auto map_or_else(F &&f, U &&u) &;
-
-(2) template <class F, class U>
- auto map_or_else(F &&f, U &&u)
-
-(3) template <class F, class U>
- auto map_or_else(F &&f, U &&u)
-
-(4) template <class F, class U>
- auto map_or_else(F &&f, U &&u)</code></pre>
-
-Maps the stored value with `f` if there is one, otherwise calls `u` and returns the result.
-
-If there is a value stored, then `f` is called with `**this` and the value is returned. Otherwise `std::forward<U>(u)()` is returned.
-
-### Function template `tl::optional<T&>::conjunction`<a id="tl::optional-T&-::conjunction(U&&)const"></a>
-
-<pre><code class="language-cpp">template <class U>
-constexpr <a href='doc_optional.html#tl::optional-T-'>optional<typename std::decay<U>::type></a> conjunction(U&& u) const;</code></pre>
-
-*Returns*: `u` if `*this` has a value, otherwise an empty optional.
-
-### Function `tl::optional<T&>::disjunction`<a id="tl::optional-T&-::disjunction(constoptional&)&"></a>
-
-<pre><code class="language-cpp">(1) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) &;
-
-(2) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) const &;
-
-(3) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) &&;
-
-(4) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) const &&;
-
-(5) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) &;
-
-(6) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) const &;
-
-(7) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) &&;
-
-(8) constexpr <a href='doc_optional.html#tl::optional-T-'>optional</a> disjunction(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) const &&;</code></pre>
-
-*Returns*: `rhs` if `*this` is empty, otherwise the current value.
-
-### Function `tl::optional<T&>::take`<a id="tl::optional-T&-::take()&"></a>
-
-<pre><code class="language-cpp">(1) <a href='doc_optional.html#tl::optional-T-'>optional</a> take() &;
-
-(2) <a href='doc_optional.html#tl::optional-T-'>optional</a> take() const &;
-
-(3) <a href='doc_optional.html#tl::optional-T-'>optional</a> take() &&;
-
-(4) <a href='doc_optional.html#tl::optional-T-'>optional</a> take() const &&;</code></pre>
-
-Takes the value out of the optional, leaving it empty
-
-### Default constructor `tl::optional<T&>::optional`<a id="tl::optional-T&-::optional()"></a>
-
-<pre><code class="language-cpp">(1) constexpr optional() noexcept;
-
-(2) constexpr optional(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;</code></pre>
-
-Constructs an optional that does not contain a value.
-
-### Copy constructor `tl::optional<T&>::optional`<a id="tl::optional-T&-::optional(constoptional&)"></a>
-
-<pre><code class="language-cpp">constexpr optional(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) noexcept = default;</code></pre>
-
-Copy constructor
-
-If `rhs` contains a value, the stored value is direct-initialized with it. Otherwise, the constructed optional is empty.
-
-### Move constructor `tl::optional<T&>::optional`<a id="tl::optional-T&-::optional(optional&&)"></a>
-
-<pre><code class="language-cpp">constexpr optional(<a href='doc_optional.html#tl::optional-T-'>optional</a>&& rhs) = default;</code></pre>
-
-Move constructor
-
-If `rhs` contains a value, the stored value is direct-initialized with it. Otherwise, the constructed optional is empty.
-
-### Function template `tl::optional<T&>::optional`<a id="tl::optional-T&-::optional(U&&)"></a>
-
-<pre><code class="language-cpp">template <class U=T> constexpr optional(U &&u);</code></pre>
-
-Constructs the stored value with `u`.
-
-### Destructor `tl::optional<T&>::~optional`<a id="tl::optional-T&-::~optional()"></a>
-
-<pre><code class="language-cpp">~optional() = default;</code></pre>
-
-No-op
-
-### Assignment operator `tl::optional<T&>::operator=`<a id="tl::optional-T&-::operator=(tl::nullopt_t)"></a>
-
-<pre><code class="language-cpp"><a href='doc_optional.html#tl::optional-T-'>optional</a>& operator=(<a href='doc_optional.html#tl::nullopt_t'>nullopt_t</a>) noexcept;</code></pre>
-
-Assignment to empty.
-
-Destroys the current value if there is one.
-
-### Copy assignment operator `tl::optional<T&>::operator=`<a id="tl::optional-T&-::operator=(constoptional&)"></a>
-
-<pre><code class="language-cpp"><a href='doc_optional.html#tl::optional-T-'>optional</a>& operator=(const <a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) = default;</code></pre>
-
-Copy assignment.
-
-Rebinds this optional to the referee of `rhs` if there is one. Otherwise resets the stored value in `*this`.
-
-### Assignment operator `tl::optional<T&>::operator=`<a id="tl::optional-T&-::operator=(U&&)"></a>
-
-<pre><code class="language-cpp">optional &operator=(U &&u);</code></pre>
-
-Rebinds this optional to `u`.
-
-*Requires*: `U` must be an lvalue reference.
-
-### Assignment operator `tl::optional<T&>::operator=`<a id="tl::optional-T&-::operator=(constoptional-U-&)"></a>
-
-<pre><code class="language-cpp">template <class U>
-<a href='doc_optional.html#tl::optional-T-'>optional</a>& operator=(const <a href='doc_optional.html#tl::optional-T-'>optional<U></a>& rhs);</code></pre>
-
-Converting copy assignment operator.
-
-Rebinds this optional to the referee of `rhs` if there is one. Otherwise resets the stored value in `*this`.
-
-### Function template `tl::optional<T&>::emplace`<a id="tl::optional-T&-::emplace(Args&&...)"></a>
-
-<pre><code class="language-cpp">(1) template <class ... Args>
- T& emplace(Args&&... args) noexcept;</code></pre>
-
-Constructs the value in-place, destroying the current one if there is one.
-
-### Function `tl::optional<T&>::swap`<a id="tl::optional-T&-::swap(optional&)"></a>
-
-<pre><code class="language-cpp">void swap(<a href='doc_optional.html#tl::optional-T-'>optional</a>& rhs) noexcept;</code></pre>
-
-Swaps this optional with the other.
-
-If neither optionals have a value, nothing happens. If both have a value, the values are swapped. If one has a value, it is moved to the other and the movee is left valueless.
-
-### Operator `tl::optional<T&>::operator->`<a id="tl::optional-T&-::operator--()const"></a>
-
-<pre><code class="language-cpp">(1) constexpr const T *operator->() const;
-
-(2) constexpr T *operator->();</code></pre>
-
-*Returns*: a pointer to the stored value
-
-*Requires*: a value is stored
-
-### Operator `tl::optional<T&>::operator*`<a id="tl::optional-T&-::operator*()&"></a>
-
-<pre><code class="language-cpp">(1) constexpr T &operator*();
-
-(2) constexpr const T &operator*() const;</code></pre>
-
-*Returns*: the stored value
-
-*Requires*: a value is stored
-
-### Function `tl::optional<T&>::has_value`<a id="tl::optional-T&-::has_value()const"></a>
-
-<pre><code class="language-cpp">(1) constexpr bool has_value() const noexcept;
-
-(2) constexpr operator bool() const noexcept;</code></pre>
-
-*Returns*: whether or not the optional has a value
-
-### Function `tl::optional<T&>::value`<a id="tl::optional-T&-::value()&"></a>
-
-<pre><code class="language-cpp">(1) constexpr T& value() &;
-
-(2) constexpr const T &value() const;</code></pre>
-
-*Returns*: the contained value if there is one, otherwise throws \[bad\_optional\_access\]
-
-synopsis constexpr T \&value();
-
-### Function template `tl::optional<T&>::value_or`<a id="tl::optional-T&-::value_or(U&&)const&"></a>
-
-<pre><code class="language-cpp">(1) template <class U>
- constexpr T value_or(U&& u) const &;
-
-(2) template <class U>
- constexpr T value_or(U&& u) &&;</code></pre>
-
-*Returns*: the stored value if there is one, otherwise returns `u`
-
-### Function `tl::optional<T&>::reset`<a id="tl::optional-T&-::reset()"></a>
-
-<pre><code class="language-cpp">void reset() noexcept;</code></pre>
-
-Destroys the stored value if one exists, making the optional empty
-
------
-
------
diff --git a/third_party/optional/standardese.config b/third_party/optional/standardese.config
deleted file mode 100644
index 643fd3b..0000000
--- a/third_party/optional/standardese.config
+++ /dev/null
@@ -1,3 +0,0 @@
-[output]
-format=commonmark
-link_extension=html
diff --git a/third_party/optional/tests/assignment.cpp b/third_party/optional/tests/assignment.cpp
deleted file mode 100644
index 205ed7b..0000000
--- a/third_party/optional/tests/assignment.cpp
+++ /dev/null
@@ -1,71 +0,0 @@
-#include "catch.hpp"
-#include "optional.hpp"
-
-TEST_CASE("Assignment value", "[assignment.value]") {
- tl::optional<int> o1 = 42;
- tl::optional<int> o2 = 12;
- tl::optional<int> o3;
-
- o1 = o1;
- REQUIRE(*o1 == 42);
-
- o1 = o2;
- REQUIRE(*o1 == 12);
-
- o1 = o3;
- REQUIRE(!o1);
-
- o1 = 42;
- REQUIRE(*o1 == 42);
-
- o1 = tl::nullopt;
- REQUIRE(!o1);
-
- o1 = std::move(o2);
- REQUIRE(*o1 == 12);
-
- tl::optional<short> o4 = 42;
-
- o1 = o4;
- REQUIRE(*o1 == 42);
-
- o1 = std::move(o4);
- REQUIRE(*o1 == 42);
-}
-
-
-TEST_CASE("Assignment reference", "[assignment.ref]") {
- auto i = 42;
- auto j = 12;
-
- tl::optional<int&> o1 = i;
- tl::optional<int&> o2 = j;
- tl::optional<int&> o3;
-
- o1 = o1;
- REQUIRE(*o1 == 42);
- REQUIRE(&*o1 == &i);
-
- o1 = o2;
- REQUIRE(*o1 == 12);
-
- o1 = o3;
- REQUIRE(!o1);
-
- auto k = 42;
- o1 = k;
- REQUIRE(*o1 == 42);
- REQUIRE(*o1 == i);
- REQUIRE(*o1 == k);
- REQUIRE(&*o1 != &i);
- REQUIRE(&*o1 == &k);
-
- k = 12;
- REQUIRE(*o1 == 12);
-
- o1 = tl::nullopt;
- REQUIRE(!o1);
-
- o1 = std::move(o2);
- REQUIRE(*o1 == 12);
-}
diff --git a/third_party/optional/tests/bases.cpp b/third_party/optional/tests/bases.cpp
deleted file mode 100644
index 09623ea..0000000
--- a/third_party/optional/tests/bases.cpp
+++ /dev/null
@@ -1,106 +0,0 @@
-#include "catch.hpp"
-#include "optional.hpp"
-
-// Old versions of GCC don't have the correct trait names. Could fix them up if needs be.
-#ifdef TL_OPTIONAL_GCC49
-// nothing for now
-#else
-TEST_CASE("Triviality", "[bases.triviality]") {
- REQUIRE(std::is_trivially_copy_constructible<tl::optional<int>>::value);
- REQUIRE(std::is_trivially_copy_assignable<tl::optional<int>>::value);
- REQUIRE(std::is_trivially_move_constructible<tl::optional<int>>::value);
- REQUIRE(std::is_trivially_move_assignable<tl::optional<int>>::value);
- REQUIRE(std::is_trivially_destructible<tl::optional<int>>::value);
-
- {
- struct T {
- T(const T&) = default;
- T(T&&) = default;
- T& operator=(const T&) = default;
- T& operator=(T&&) = default;
- ~T() = default;
- };
- REQUIRE(std::is_trivially_copy_constructible<tl::optional<T>>::value);
- REQUIRE(std::is_trivially_copy_assignable<tl::optional<T>>::value);
- REQUIRE(std::is_trivially_move_constructible<tl::optional<T>>::value);
- REQUIRE(std::is_trivially_move_assignable<tl::optional<T>>::value);
- REQUIRE(std::is_trivially_destructible<tl::optional<T>>::value);
- }
-
- {
- struct T {
- T(const T&){}
- T(T&&) {};
- T& operator=(const T&) { return *this; }
- T& operator=(T&&) { return *this; };
- ~T(){}
- };
- REQUIRE(!std::is_trivially_copy_constructible<tl::optional<T>>::value);
- REQUIRE(!std::is_trivially_copy_assignable<tl::optional<T>>::value);
- REQUIRE(!std::is_trivially_move_constructible<tl::optional<T>>::value);
- REQUIRE(!std::is_trivially_move_assignable<tl::optional<T>>::value);
- REQUIRE(!std::is_trivially_destructible<tl::optional<T>>::value);
- }
-
-}
-
-TEST_CASE("Deletion", "[bases.deletion]") {
- REQUIRE(std::is_copy_constructible<tl::optional<int>>::value);
- REQUIRE(std::is_copy_assignable<tl::optional<int>>::value);
- REQUIRE(std::is_move_constructible<tl::optional<int>>::value);
- REQUIRE(std::is_move_assignable<tl::optional<int>>::value);
- REQUIRE(std::is_destructible<tl::optional<int>>::value);
-
- {
- struct T {
- T(const T&) = default;
- T(T&&) = default;
- T& operator=(const T&) = default;
- T& operator=(T&&) = default;
- ~T() = default;
- };
- REQUIRE(std::is_copy_constructible<tl::optional<T>>::value);
- REQUIRE(std::is_copy_assignable<tl::optional<T>>::value);
- REQUIRE(std::is_move_constructible<tl::optional<T>>::value);
- REQUIRE(std::is_move_assignable<tl::optional<T>>::value);
- REQUIRE(std::is_destructible<tl::optional<T>>::value);
- }
-
- {
- struct T {
- T(const T&)=delete;
- T(T&&)=delete;
- T& operator=(const T&)=delete;
- T& operator=(T&&)=delete;
- };
- REQUIRE(!std::is_copy_constructible<tl::optional<T>>::value);
- REQUIRE(!std::is_copy_assignable<tl::optional<T>>::value);
- REQUIRE(!std::is_move_constructible<tl::optional<T>>::value);
- REQUIRE(!std::is_move_assignable<tl::optional<T>>::value);
- }
-
- {
- struct T {
- T(const T&)=delete;
- T(T&&)=default;
- T& operator=(const T&)=delete;
- T& operator=(T&&)=default;
- };
- REQUIRE(!std::is_copy_constructible<tl::optional<T>>::value);
- REQUIRE(!std::is_copy_assignable<tl::optional<T>>::value);
- REQUIRE(std::is_move_constructible<tl::optional<T>>::value);
- REQUIRE(std::is_move_assignable<tl::optional<T>>::value);
- }
-
- {
- struct T {
- T(const T&)=default;
- T(T&&)=delete;
- T& operator=(const T&)=default;
- T& operator=(T&&)=delete;
- };
- REQUIRE(std::is_copy_constructible<tl::optional<T>>::value);
- REQUIRE(std::is_copy_assignable<tl::optional<T>>::value);
- }
-}
-#endif
diff --git a/third_party/optional/tests/catch.hpp b/third_party/optional/tests/catch.hpp
deleted file mode 100644
index 362f869..0000000
--- a/third_party/optional/tests/catch.hpp
+++ /dev/null
@@ -1,12012 +0,0 @@
-/*
- * Catch v2.0.1
- * Generated: 2017-11-03 11:53:39.642003
- * ----------------------------------------------------------
- * This file has been merged from multiple headers. Please don't edit it directly
- * Copyright (c) 2017 Two Blue Cubes Ltd. All rights reserved.
- *
- * Distributed under the Boost Software License, Version 1.0. (See accompanying
- * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt)
- */
-#ifndef TWOBLUECUBES_SINGLE_INCLUDE_CATCH_HPP_INCLUDED
-#define TWOBLUECUBES_SINGLE_INCLUDE_CATCH_HPP_INCLUDED
-// start catch.hpp
-
-
-#ifdef __clang__
-# pragma clang system_header
-#elif defined __GNUC__
-# pragma GCC system_header
-#endif
-
-// start catch_suppress_warnings.h
-
-#ifdef __clang__
-# ifdef __ICC // icpc defines the __clang__ macro
-# pragma warning(push)
-# pragma warning(disable: 161 1682)
-# else // __ICC
-# pragma clang diagnostic ignored "-Wglobal-constructors"
-# pragma clang diagnostic ignored "-Wvariadic-macros"
-# pragma clang diagnostic ignored "-Wc99-extensions"
-# pragma clang diagnostic ignored "-Wunused-variable"
-# pragma clang diagnostic push
-# pragma clang diagnostic ignored "-Wpadded"
-# pragma clang diagnostic ignored "-Wswitch-enum"
-# pragma clang diagnostic ignored "-Wcovered-switch-default"
-# endif
-#elif defined __GNUC__
-# pragma GCC diagnostic ignored "-Wvariadic-macros"
-# pragma GCC diagnostic ignored "-Wunused-variable"
-# pragma GCC diagnostic ignored "-Wparentheses"
-
-# pragma GCC diagnostic push
-# pragma GCC diagnostic ignored "-Wpadded"
-#endif
-// end catch_suppress_warnings.h
-#if defined(CATCH_CONFIG_MAIN) || defined(CATCH_CONFIG_RUNNER)
-# define CATCH_IMPL
-# define CATCH_CONFIG_EXTERNAL_INTERFACES
-# if defined(CATCH_CONFIG_DISABLE_MATCHERS)
-# undef CATCH_CONFIG_DISABLE_MATCHERS
-# endif
-#endif
-
-// start catch_platform.h
-
-#ifdef __APPLE__
-# include <TargetConditionals.h>
-# if TARGET_OS_MAC == 1
-# define CATCH_PLATFORM_MAC
-# elif TARGET_OS_IPHONE == 1
-# define CATCH_PLATFORM_IPHONE
-# endif
-
-#elif defined(linux) || defined(__linux) || defined(__linux__)
-# define CATCH_PLATFORM_LINUX
-
-#elif defined(WIN32) || defined(__WIN32__) || defined(_WIN32) || defined(_MSC_VER)
-# define CATCH_PLATFORM_WINDOWS
-#endif
-
-// end catch_platform.h
-#ifdef CATCH_IMPL
-# ifndef CLARA_CONFIG_MAIN
-# define CLARA_CONFIG_MAIN_NOT_DEFINED
-# define CLARA_CONFIG_MAIN
-# endif
-#endif
-
-// start catch_tag_alias_autoregistrar.h
-
-// start catch_common.h
-
-// start catch_compiler_capabilities.h
-
-// Detect a number of compiler features - by compiler
-// The following features are defined:
-//
-// CATCH_CONFIG_COUNTER : is the __COUNTER__ macro supported?
-// CATCH_CONFIG_WINDOWS_SEH : is Windows SEH supported?
-// CATCH_CONFIG_POSIX_SIGNALS : are POSIX signals supported?
-// ****************
-// Note to maintainers: if new toggles are added please document them
-// in configuration.md, too
-// ****************
-
-// In general each macro has a _NO_<feature name> form
-// (e.g. CATCH_CONFIG_NO_POSIX_SIGNALS) which disables the feature.
-// Many features, at point of detection, define an _INTERNAL_ macro, so they
-// can be combined, en-mass, with the _NO_ forms later.
-
-#ifdef __cplusplus
-
-# if __cplusplus >= 201402L
-# define CATCH_CPP14_OR_GREATER
-# endif
-
-#endif
-
-#ifdef __clang__
-
-# define CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- _Pragma( "clang diagnostic push" ) \
- _Pragma( "clang diagnostic ignored \"-Wexit-time-destructors\"" ) \
- _Pragma( "clang diagnostic ignored \"-Wglobal-constructors\"")
-# define CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS \
- _Pragma( "clang diagnostic pop" )
-
-# define CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS \
- _Pragma( "clang diagnostic push" ) \
- _Pragma( "clang diagnostic ignored \"-Wparentheses\"" )
-# define CATCH_INTERNAL_UNSUPPRESS_PARENTHESES_WARNINGS \
- _Pragma( "clang diagnostic pop" )
-
-#endif // __clang__
-
-////////////////////////////////////////////////////////////////////////////////
-// We know some environments not to support full POSIX signals
-#if defined(__CYGWIN__) || defined(__QNX__)
-
-# if !defined(CATCH_CONFIG_POSIX_SIGNALS)
-# define CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS
-# endif
-
-#endif
-
-#ifdef __OS400__
-# define CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS
-# define CATCH_CONFIG_COLOUR_NONE
-#endif
-
-////////////////////////////////////////////////////////////////////////////////
-// Cygwin
-#ifdef __CYGWIN__
-
-// Required for some versions of Cygwin to declare gettimeofday
-// see: http://stackoverflow.com/questions/36901803/gettimeofday-not-declared-in-this-scope-cygwin
-# define _BSD_SOURCE
-
-#endif // __CYGWIN__
-
-////////////////////////////////////////////////////////////////////////////////
-// Visual C++
-#ifdef _MSC_VER
-
-// Universal Windows platform does not support SEH
-// Or console colours (or console at all...)
-# if defined(WINAPI_FAMILY) && (WINAPI_FAMILY == WINAPI_FAMILY_APP)
-# define CATCH_CONFIG_COLOUR_NONE
-# else
-# define CATCH_INTERNAL_CONFIG_WINDOWS_SEH
-# endif
-
-#endif // _MSC_VER
-
-////////////////////////////////////////////////////////////////////////////////
-
-// Use of __COUNTER__ is suppressed during code analysis in
-// CLion/AppCode 2017.2.x and former, because __COUNTER__ is not properly
-// handled by it.
-// Otherwise all supported compilers support COUNTER macro,
-// but user still might want to turn it off
-#if ( !defined(__JETBRAINS_IDE__) || __JETBRAINS_IDE__ >= 20170300L )
- #define CATCH_INTERNAL_CONFIG_COUNTER
-#endif
-
-#if defined(CATCH_INTERNAL_CONFIG_COUNTER) && !defined(CATCH_CONFIG_NO_COUNTER) && !defined(CATCH_CONFIG_COUNTER)
-# define CATCH_CONFIG_COUNTER
-#endif
-#if defined(CATCH_INTERNAL_CONFIG_WINDOWS_SEH) && !defined(CATCH_CONFIG_NO_WINDOWS_SEH) && !defined(CATCH_CONFIG_WINDOWS_SEH)
-# define CATCH_CONFIG_WINDOWS_SEH
-#endif
-// This is set by default, because we assume that unix compilers are posix-signal-compatible by default.
-#if !defined(CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS) && !defined(CATCH_CONFIG_NO_POSIX_SIGNALS) && !defined(CATCH_CONFIG_POSIX_SIGNALS)
-# define CATCH_CONFIG_POSIX_SIGNALS
-#endif
-
-#if !defined(CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS)
-# define CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS
-# define CATCH_INTERNAL_UNSUPPRESS_PARENTHESES_WARNINGS
-#endif
-#if !defined(CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS)
-# define CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS
-# define CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS
-#endif
-
-// end catch_compiler_capabilities.h
-#define INTERNAL_CATCH_UNIQUE_NAME_LINE2( name, line ) name##line
-#define INTERNAL_CATCH_UNIQUE_NAME_LINE( name, line ) INTERNAL_CATCH_UNIQUE_NAME_LINE2( name, line )
-#ifdef CATCH_CONFIG_COUNTER
-# define INTERNAL_CATCH_UNIQUE_NAME( name ) INTERNAL_CATCH_UNIQUE_NAME_LINE( name, __COUNTER__ )
-#else
-# define INTERNAL_CATCH_UNIQUE_NAME( name ) INTERNAL_CATCH_UNIQUE_NAME_LINE( name, __LINE__ )
-#endif
-
-#include <iosfwd>
-#include <string>
-#include <cstdint>
-
-namespace Catch {
-
- struct CaseSensitive { enum Choice {
- Yes,
- No
- }; };
-
- class NonCopyable {
- NonCopyable( NonCopyable const& ) = delete;
- NonCopyable( NonCopyable && ) = delete;
- NonCopyable& operator = ( NonCopyable const& ) = delete;
- NonCopyable& operator = ( NonCopyable && ) = delete;
-
- protected:
- NonCopyable();
- virtual ~NonCopyable();
- };
-
- struct SourceLineInfo {
-
- SourceLineInfo() = delete;
- SourceLineInfo( char const* _file, std::size_t _line ) noexcept;
-
- SourceLineInfo( SourceLineInfo const& other ) = default;
- SourceLineInfo( SourceLineInfo && ) = default;
- SourceLineInfo& operator = ( SourceLineInfo const& ) = default;
- SourceLineInfo& operator = ( SourceLineInfo && ) = default;
-
- bool empty() const noexcept;
- bool operator == ( SourceLineInfo const& other ) const noexcept;
- bool operator < ( SourceLineInfo const& other ) const noexcept;
-
- char const* file;
- std::size_t line;
- };
-
- std::ostream& operator << ( std::ostream& os, SourceLineInfo const& info );
-
- // This is just here to avoid compiler warnings with macro constants and boolean literals
- bool isTrue( bool value );
- bool alwaysTrue();
- bool alwaysFalse();
-
- // Use this in variadic streaming macros to allow
- // >> +StreamEndStop
- // as well as
- // >> stuff +StreamEndStop
- struct StreamEndStop {
- std::string operator+() const;
- };
- template<typename T>
- T const& operator + ( T const& value, StreamEndStop ) {
- return value;
- }
-}
-
-#define CATCH_INTERNAL_LINEINFO \
- ::Catch::SourceLineInfo( __FILE__, static_cast<std::size_t>( __LINE__ ) )
-
-// end catch_common.h
-namespace Catch {
-
- struct RegistrarForTagAliases {
- RegistrarForTagAliases( char const* alias, char const* tag, SourceLineInfo const& lineInfo );
- };
-
-} // end namespace Catch
-
-#define CATCH_REGISTER_TAG_ALIAS( alias, spec ) namespace{ Catch::RegistrarForTagAliases INTERNAL_CATCH_UNIQUE_NAME( AutoRegisterTagAlias )( alias, spec, CATCH_INTERNAL_LINEINFO ); }
-
-// end catch_tag_alias_autoregistrar.h
-// start catch_test_registry.h
-
-// start catch_interfaces_testcase.h
-
-#include <vector>
-#include <memory>
-
-namespace Catch {
-
- class TestSpec;
-
- struct ITestInvoker {
- virtual void invoke () const = 0;
- virtual ~ITestInvoker();
- };
-
- using ITestCasePtr = std::shared_ptr<ITestInvoker>;
-
- class TestCase;
- struct IConfig;
-
- struct ITestCaseRegistry {
- virtual ~ITestCaseRegistry();
- virtual std::vector<TestCase> const& getAllTests() const = 0;
- virtual std::vector<TestCase> const& getAllTestsSorted( IConfig const& config ) const = 0;
- };
-
- bool matchTest( TestCase const& testCase, TestSpec const& testSpec, IConfig const& config );
- std::vector<TestCase> filterTests( std::vector<TestCase> const& testCases, TestSpec const& testSpec, IConfig const& config );
- std::vector<TestCase> const& getAllTestCasesSorted( IConfig const& config );
-
-}
-
-// end catch_interfaces_testcase.h
-// start catch_stringref.h
-
-#include <cstddef>
-#include <string>
-#include <iosfwd>
-
-namespace Catch {
-
- class StringData;
-
- /// A non-owning string class (similar to the forthcoming std::string_view)
- /// Note that, because a StringRef may be a substring of another string,
- /// it may not be null terminated. c_str() must return a null terminated
- /// string, however, and so the StringRef will internally take ownership
- /// (taking a copy), if necessary. In theory this ownership is not externally
- /// visible - but it does mean (substring) StringRefs should not be shared between
- /// threads.
- class StringRef {
- friend struct StringRefTestAccess;
-
- using size_type = std::size_t;
-
- char const* m_start;
- size_type m_size;
-
- char* m_data = nullptr;
-
- void takeOwnership();
-
- public: // construction/ assignment
- StringRef() noexcept;
- StringRef( StringRef const& other ) noexcept;
- StringRef( StringRef&& other ) noexcept;
- StringRef( char const* rawChars ) noexcept;
- StringRef( char const* rawChars, size_type size ) noexcept;
- StringRef( std::string const& stdString ) noexcept;
- ~StringRef() noexcept;
-
- auto operator = ( StringRef other ) noexcept -> StringRef&;
- operator std::string() const;
-
- void swap( StringRef& other ) noexcept;
-
- public: // operators
- auto operator == ( StringRef const& other ) const noexcept -> bool;
- auto operator != ( StringRef const& other ) const noexcept -> bool;
-
- auto operator[] ( size_type index ) const noexcept -> char;
-
- public: // named queries
- auto empty() const noexcept -> bool;
- auto size() const noexcept -> size_type;
- auto numberOfCharacters() const noexcept -> size_type;
- auto c_str() const -> char const*;
-
- public: // substrings and searches
- auto substr( size_type start, size_type size ) const noexcept -> StringRef;
-
- private: // ownership queries - may not be consistent between calls
- auto isOwned() const noexcept -> bool;
- auto isSubstring() const noexcept -> bool;
- auto data() const noexcept -> char const*;
- };
-
- auto operator + ( StringRef const& lhs, StringRef const& rhs ) -> std::string;
- auto operator + ( StringRef const& lhs, char const* rhs ) -> std::string;
- auto operator + ( char const* lhs, StringRef const& rhs ) -> std::string;
-
- auto operator << ( std::ostream& os, StringRef const& sr ) -> std::ostream&;
-
-} // namespace Catch
-
-// end catch_stringref.h
-namespace Catch {
-
-template<typename C>
-class TestInvokerAsMethod : public ITestInvoker {
- void (C::*m_testAsMethod)();
-public:
- TestInvokerAsMethod( void (C::*testAsMethod)() ) noexcept : m_testAsMethod( testAsMethod ) {}
-
- void invoke() const override {
- C obj;
- (obj.*m_testAsMethod)();
- }
-};
-
-auto makeTestInvoker( void(*testAsFunction)() ) noexcept -> ITestInvoker*;
-
-template<typename C>
-auto makeTestInvoker( void (C::*testAsMethod)() ) noexcept -> ITestInvoker* {
- return new(std::nothrow) TestInvokerAsMethod<C>( testAsMethod );
-}
-
-struct NameAndTags {
- NameAndTags( StringRef name_ = "", StringRef tags_ = "" ) noexcept;
- StringRef name;
- StringRef tags;
-};
-
-struct AutoReg : NonCopyable {
- AutoReg( ITestInvoker* invoker, SourceLineInfo const& lineInfo, StringRef classOrMethod, NameAndTags const& nameAndTags ) noexcept;
- ~AutoReg();
-};
-
-} // end namespace Catch
-
-#if defined(CATCH_CONFIG_DISABLE)
- #define INTERNAL_CATCH_TESTCASE_NO_REGISTRATION( TestName, ... ) \
- static void TestName()
- #define INTERNAL_CATCH_TESTCASE_METHOD_NO_REGISTRATION( TestName, ClassName, ... ) \
- namespace{ \
- struct TestName : ClassName { \
- void test(); \
- }; \
- } \
- void TestName::test()
-
-#endif
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_TESTCASE2( TestName, ... ) \
- static void TestName(); \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- namespace{ Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar )( Catch::makeTestInvoker( &TestName ), CATCH_INTERNAL_LINEINFO, "", Catch::NameAndTags{ __VA_ARGS__ } ); } /* NOLINT */ \
- CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS \
- static void TestName()
- #define INTERNAL_CATCH_TESTCASE( ... ) \
- INTERNAL_CATCH_TESTCASE2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), __VA_ARGS__ )
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_METHOD_AS_TEST_CASE( QualifiedMethod, ... ) \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- namespace{ Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar )( Catch::makeTestInvoker( &QualifiedMethod ), CATCH_INTERNAL_LINEINFO, "&" #QualifiedMethod, Catch::NameAndTags{ __VA_ARGS__ } ); } /* NOLINT */ \
- CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_TEST_CASE_METHOD2( TestName, ClassName, ... )\
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- namespace{ \
- struct TestName : ClassName{ \
- void test(); \
- }; \
- Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar ) ( Catch::makeTestInvoker( &TestName::test ), CATCH_INTERNAL_LINEINFO, #ClassName, Catch::NameAndTags{ __VA_ARGS__ } ); /* NOLINT */ \
- } \
- CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS \
- void TestName::test()
- #define INTERNAL_CATCH_TEST_CASE_METHOD( ClassName, ... ) \
- INTERNAL_CATCH_TEST_CASE_METHOD2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), ClassName, __VA_ARGS__ )
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_REGISTER_TESTCASE( Function, ... ) \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar )( Catch::makeTestInvoker( Function ), CATCH_INTERNAL_LINEINFO, "", Catch::NameAndTags{ __VA_ARGS__ } ); /* NOLINT */ \
- CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS
-
-// end catch_test_registry.h
-// start catch_capture.hpp
-
-// start catch_assertionhandler.h
-
-// start catch_decomposer.h
-
-// start catch_tostring.h
-
-#include <sstream>
-#include <vector>
-#include <cstddef>
-#include <type_traits>
-#include <string>
-
-#ifdef __OBJC__
-// start catch_objc_arc.hpp
-
-#import <Foundation/Foundation.h>
-
-#ifdef __has_feature
-#define CATCH_ARC_ENABLED __has_feature(objc_arc)
-#else
-#define CATCH_ARC_ENABLED 0
-#endif
-
-void arcSafeRelease( NSObject* obj );
-id performOptionalSelector( id obj, SEL sel );
-
-#if !CATCH_ARC_ENABLED
-inline void arcSafeRelease( NSObject* obj ) {
- [obj release];
-}
-inline id performOptionalSelector( id obj, SEL sel ) {
- if( [obj respondsToSelector: sel] )
- return [obj performSelector: sel];
- return nil;
-}
-#define CATCH_UNSAFE_UNRETAINED
-#define CATCH_ARC_STRONG
-#else
-inline void arcSafeRelease( NSObject* ){}
-inline id performOptionalSelector( id obj, SEL sel ) {
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Warc-performSelector-leaks"
-#endif
- if( [obj respondsToSelector: sel] )
- return [obj performSelector: sel];
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
- return nil;
-}
-#define CATCH_UNSAFE_UNRETAINED __unsafe_unretained
-#define CATCH_ARC_STRONG __strong
-#endif
-
-// end catch_objc_arc.hpp
-#endif
-
-#ifdef _MSC_VER
-#pragma warning(push)
-#pragma warning(disable:4180) // We attempt to stream a function (address) by const&, which MSVC complains about but is harmless
-#endif
-
-// We need a dummy global operator<< so we can bring it into Catch namespace later
-struct Catch_global_namespace_dummy;
-std::ostream& operator<<(std::ostream&, Catch_global_namespace_dummy);
-
-namespace Catch {
- // Bring in operator<< from global namespace into Catch namespace
- using ::operator<<;
-
- namespace Detail {
-
- extern const std::string unprintableString;
-
- std::string rawMemoryToString( const void *object, std::size_t size );
-
- template<typename T>
- std::string rawMemoryToString( const T& object ) {
- return rawMemoryToString( &object, sizeof(object) );
- }
-
- template<typename T>
- class IsStreamInsertable {
- template<typename SS, typename TT>
- static auto test(int)
- -> decltype(std::declval<SS&>() << std::declval<TT>(), std::true_type());
-
- template<typename, typename>
- static auto test(...)->std::false_type;
-
- public:
- static const bool value = decltype(test<std::ostream, const T&>(0))::value;
- };
-
- } // namespace Detail
-
- // If we decide for C++14, change these to enable_if_ts
- template <typename T>
- struct StringMaker {
- template <typename Fake = T>
- static
- typename std::enable_if<::Catch::Detail::IsStreamInsertable<Fake>::value, std::string>::type
- convert(const Fake& t) {
- std::ostringstream sstr;
- sstr << t;
- return sstr.str();
- }
-
- template <typename Fake = T>
- static
- typename std::enable_if<!::Catch::Detail::IsStreamInsertable<Fake>::value, std::string>::type
- convert(const Fake&) {
- return Detail::unprintableString;
- }
- };
-
- namespace Detail {
-
- // This function dispatches all stringification requests inside of Catch.
- // Should be preferably called fully qualified, like ::Catch::Detail::stringify
- template <typename T>
- std::string stringify(const T& e) {
- return ::Catch::StringMaker<typename std::remove_cv<typename std::remove_reference<T>::type>::type>::convert(e);
- }
-
- } // namespace Detail
-
- // Some predefined specializations
-
- template<>
- struct StringMaker<std::string> {
- static std::string convert(const std::string& str);
- };
- template<>
- struct StringMaker<std::wstring> {
- static std::string convert(const std::wstring& wstr);
- };
-
- template<>
- struct StringMaker<char const *> {
- static std::string convert(char const * str);
- };
- template<>
- struct StringMaker<char *> {
- static std::string convert(char * str);
- };
- template<>
- struct StringMaker<wchar_t const *> {
- static std::string convert(wchar_t const * str);
- };
- template<>
- struct StringMaker<wchar_t *> {
- static std::string convert(wchar_t * str);
- };
-
- template<int SZ>
- struct StringMaker<char[SZ]> {
- static std::string convert(const char* str) {
- return ::Catch::Detail::stringify(std::string{ str });
- }
- };
- template<int SZ>
- struct StringMaker<signed char[SZ]> {
- static std::string convert(const char* str) {
- return ::Catch::Detail::stringify(std::string{ str });
- }
- };
- template<int SZ>
- struct StringMaker<unsigned char[SZ]> {
- static std::string convert(const char* str) {
- return ::Catch::Detail::stringify(std::string{ str });
- }
- };
-
- template<>
- struct StringMaker<int> {
- static std::string convert(int value);
- };
- template<>
- struct StringMaker<long> {
- static std::string convert(long value);
- };
- template<>
- struct StringMaker<long long> {
- static std::string convert(long long value);
- };
- template<>
- struct StringMaker<unsigned int> {
- static std::string convert(unsigned int value);
- };
- template<>
- struct StringMaker<unsigned long> {
- static std::string convert(unsigned long value);
- };
- template<>
- struct StringMaker<unsigned long long> {
- static std::string convert(unsigned long long value);
- };
-
- template<>
- struct StringMaker<bool> {
- static std::string convert(bool b);
- };
-
- template<>
- struct StringMaker<char> {
- static std::string convert(char c);
- };
- template<>
- struct StringMaker<signed char> {
- static std::string convert(signed char c);
- };
- template<>
- struct StringMaker<unsigned char> {
- static std::string convert(unsigned char c);
- };
-
- template<>
- struct StringMaker<std::nullptr_t> {
- static std::string convert(std::nullptr_t);
- };
-
- template<>
- struct StringMaker<float> {
- static std::string convert(float value);
- };
- template<>
- struct StringMaker<double> {
- static std::string convert(double value);
- };
-
- template <typename T>
- struct StringMaker<T*> {
- template <typename U>
- static std::string convert(U* p) {
- if (p) {
- return ::Catch::Detail::rawMemoryToString(p);
- } else {
- return "nullptr";
- }
- }
- };
-
- template <typename R, typename C>
- struct StringMaker<R C::*> {
- static std::string convert(R C::* p) {
- if (p) {
- return ::Catch::Detail::rawMemoryToString(p);
- } else {
- return "nullptr";
- }
- }
- };
-
- namespace Detail {
- template<typename InputIterator>
- std::string rangeToString(InputIterator first, InputIterator last) {
- std::ostringstream oss;
- oss << "{ ";
- if (first != last) {
- oss << ::Catch::Detail::stringify(*first);
- for (++first; first != last; ++first)
- oss << ", " << ::Catch::Detail::stringify(*first);
- }
- oss << " }";
- return oss.str();
- }
- }
-
- template<typename T, typename Allocator>
- struct StringMaker<std::vector<T, Allocator> > {
- static std::string convert( std::vector<T,Allocator> const& v ) {
- return ::Catch::Detail::rangeToString( v.begin(), v.end() );
- }
- };
-
- template<typename T>
- struct EnumStringMaker {
- static std::string convert(const T& t) {
- return ::Catch::Detail::stringify(static_cast<typename std::underlying_type<T>::type>(t));
- }
- };
-
-#ifdef __OBJC__
- template<>
- struct StringMaker<NSString*> {
- static std::string convert(NSString * nsstring) {
- if (!nsstring)
- return "nil";
- return std::string("@") + [nsstring UTF8String];
- }
- };
- template<>
- struct StringMaker<NSObject*> {
- static std::string convert(NSObject* nsObject) {
- return ::Catch::Detail::stringify([nsObject description]);
- }
-
- };
- namespace Detail {
- inline std::string stringify( NSString* nsstring ) {
- return StringMaker<NSString*>::convert( nsstring );
- }
-
- } // namespace Detail
-#endif // __OBJC__
-
-} // namespace Catch
-
-//////////////////////////////////////////////////////
-// Separate std-lib types stringification, so it can be selectively enabled
-// This means that we do not bring in
-
-#if defined(CATCH_CONFIG_ENABLE_ALL_STRINGMAKERS)
-# define CATCH_CONFIG_ENABLE_PAIR_STRINGMAKER
-# define CATCH_CONFIG_ENABLE_TUPLE_STRINGMAKER
-# define CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER
-#endif
-
-// Separate std::pair specialization
-#if defined(CATCH_CONFIG_ENABLE_PAIR_STRINGMAKER)
-#include <utility>
-namespace Catch {
- template<typename T1, typename T2>
- struct StringMaker<std::pair<T1, T2> > {
- static std::string convert(const std::pair<T1, T2>& pair) {
- std::ostringstream oss;
- oss << "{ "
- << ::Catch::Detail::stringify(pair.first)
- << ", "
- << ::Catch::Detail::stringify(pair.second)
- << " }";
- return oss.str();
- }
- };
-}
-#endif // CATCH_CONFIG_ENABLE_PAIR_STRINGMAKER
-
-// Separate std::tuple specialization
-#if defined(CATCH_CONFIG_ENABLE_TUPLE_STRINGMAKER)
-#include <tuple>
-namespace Catch {
- namespace Detail {
- template<
- typename Tuple,
- std::size_t N = 0,
- bool = (N < std::tuple_size<Tuple>::value)
- >
- struct TupleElementPrinter {
- static void print(const Tuple& tuple, std::ostream& os) {
- os << (N ? ", " : " ")
- << ::Catch::Detail::stringify(std::get<N>(tuple));
- TupleElementPrinter<Tuple, N + 1>::print(tuple, os);
- }
- };
-
- template<
- typename Tuple,
- std::size_t N
- >
- struct TupleElementPrinter<Tuple, N, false> {
- static void print(const Tuple&, std::ostream&) {}
- };
-
- }
-
- template<typename ...Types>
- struct StringMaker<std::tuple<Types...>> {
- static std::string convert(const std::tuple<Types...>& tuple) {
- std::ostringstream os;
- os << '{';
- Detail::TupleElementPrinter<std::tuple<Types...>>::print(tuple, os);
- os << " }";
- return os.str();
- }
- };
-}
-#endif // CATCH_CONFIG_ENABLE_TUPLE_STRINGMAKER
-
-// Separate std::chrono::duration specialization
-#if defined(CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER)
-#include <ctime>
-#include <ratio>
-#include <chrono>
-
-template <class Ratio>
-struct ratio_string {
- static std::string symbol();
-};
-
-template <class Ratio>
-std::string ratio_string<Ratio>::symbol() {
- std::ostringstream oss;
- oss << '[' << Ratio::num << '/'
- << Ratio::den << ']';
- return oss.str();
-}
-template <>
-struct ratio_string<std::atto> {
- static std::string symbol() { return "a"; }
-};
-template <>
-struct ratio_string<std::femto> {
- static std::string symbol() { return "f"; }
-};
-template <>
-struct ratio_string<std::pico> {
- static std::string symbol() { return "p"; }
-};
-template <>
-struct ratio_string<std::nano> {
- static std::string symbol() { return "n"; }
-};
-template <>
-struct ratio_string<std::micro> {
- static std::string symbol() { return "u"; }
-};
-template <>
-struct ratio_string<std::milli> {
- static std::string symbol() { return "m"; }
-};
-
-namespace Catch {
- ////////////
- // std::chrono::duration specializations
- template<typename Value, typename Ratio>
- struct StringMaker<std::chrono::duration<Value, Ratio>> {
- static std::string convert(std::chrono::duration<Value, Ratio> const& duration) {
- std::ostringstream oss;
- oss << duration.count() << ' ' << ratio_string<Ratio>::symbol() << 's';
- return oss.str();
- }
- };
- template<typename Value>
- struct StringMaker<std::chrono::duration<Value, std::ratio<1>>> {
- static std::string convert(std::chrono::duration<Value, std::ratio<1>> const& duration) {
- std::ostringstream oss;
- oss << duration.count() << " s";
- return oss.str();
- }
- };
- template<typename Value>
- struct StringMaker<std::chrono::duration<Value, std::ratio<60>>> {
- static std::string convert(std::chrono::duration<Value, std::ratio<60>> const& duration) {
- std::ostringstream oss;
- oss << duration.count() << " m";
- return oss.str();
- }
- };
- template<typename Value>
- struct StringMaker<std::chrono::duration<Value, std::ratio<3600>>> {
- static std::string convert(std::chrono::duration<Value, std::ratio<3600>> const& duration) {
- std::ostringstream oss;
- oss << duration.count() << " h";
- return oss.str();
- }
- };
-
- ////////////
- // std::chrono::time_point specialization
- // Generic time_point cannot be specialized, only std::chrono::time_point<system_clock>
- template<typename Clock, typename Duration>
- struct StringMaker<std::chrono::time_point<Clock, Duration>> {
- static std::string convert(std::chrono::time_point<Clock, Duration> const& time_point) {
- return ::Catch::Detail::stringify(time_point.time_since_epoch()) + " since epoch";
- }
- };
- // std::chrono::time_point<system_clock> specialization
- template<typename Duration>
- struct StringMaker<std::chrono::time_point<std::chrono::system_clock, Duration>> {
- static std::string convert(std::chrono::time_point<std::chrono::system_clock, Duration> const& time_point) {
- auto converted = std::chrono::system_clock::to_time_t(time_point);
-
-#ifdef _MSC_VER
- std::tm timeInfo = {};
- gmtime_s(&timeInfo, &converted);
-#else
- std::tm* timeInfo = std::gmtime(&converted);
-#endif
-
- auto const timeStampSize = sizeof("2017-01-16T17:06:45Z");
- char timeStamp[timeStampSize];
- const char * const fmt = "%Y-%m-%dT%H:%M:%SZ";
-
-#ifdef _MSC_VER
- std::strftime(timeStamp, timeStampSize, fmt, &timeInfo);
-#else
- std::strftime(timeStamp, timeStampSize, fmt, timeInfo);
-#endif
- return std::string(timeStamp);
- }
- };
-}
-#endif // CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER
-
-#ifdef _MSC_VER
-#pragma warning(pop)
-#endif
-
-// end catch_tostring.h
-#include <ostream>
-
-#ifdef _MSC_VER
-#pragma warning(push)
-#pragma warning(disable:4389) // '==' : signed/unsigned mismatch
-#pragma warning(disable:4018) // more "signed/unsigned mismatch"
-#pragma warning(disable:4312) // Converting int to T* using reinterpret_cast (issue on x64 platform)
-#pragma warning(disable:4180) // qualifier applied to function type has no meaning
-#endif
-
-namespace Catch {
-
- struct ITransientExpression {
- virtual auto isBinaryExpression() const -> bool = 0;
- virtual auto getResult() const -> bool = 0;
- virtual void streamReconstructedExpression( std::ostream &os ) const = 0;
-
- // We don't actually need a virtual destructore, but many static analysers
- // complain if it's not here :-(
- virtual ~ITransientExpression();
- };
-
- void formatReconstructedExpression( std::ostream &os, std::string const& lhs, StringRef op, std::string const& rhs );
-
- template<typename LhsT, typename RhsT>
- class BinaryExpr : public ITransientExpression {
- bool m_result;
- LhsT m_lhs;
- StringRef m_op;
- RhsT m_rhs;
-
- auto isBinaryExpression() const -> bool override { return true; }
- auto getResult() const -> bool override { return m_result; }
-
- void streamReconstructedExpression( std::ostream &os ) const override {
- formatReconstructedExpression
- ( os, Catch::Detail::stringify( m_lhs ), m_op, Catch::Detail::stringify( m_rhs ) );
- }
-
- public:
- BinaryExpr( bool comparisonResult, LhsT lhs, StringRef op, RhsT rhs )
- : m_result( comparisonResult ),
- m_lhs( lhs ),
- m_op( op ),
- m_rhs( rhs )
- {}
- };
-
- template<typename LhsT>
- class UnaryExpr : public ITransientExpression {
- LhsT m_lhs;
-
- auto isBinaryExpression() const -> bool override { return false; }
- auto getResult() const -> bool override { return m_lhs ? true : false; }
-
- void streamReconstructedExpression( std::ostream &os ) const override {
- os << Catch::Detail::stringify( m_lhs );
- }
-
- public:
- UnaryExpr( LhsT lhs ) : m_lhs( lhs ) {}
- };
-
- // Specialised comparison functions to handle equality comparisons between ints and pointers (NULL deduces as an int)
- template<typename LhsT, typename RhsT>
- auto compareEqual( LhsT const& lhs, RhsT const& rhs ) -> bool { return lhs == rhs; };
- template<typename T>
- auto compareEqual( T* const& lhs, int rhs ) -> bool { return lhs == reinterpret_cast<void const*>( rhs ); }
- template<typename T>
- auto compareEqual( T* const& lhs, long rhs ) -> bool { return lhs == reinterpret_cast<void const*>( rhs ); }
- template<typename T>
- auto compareEqual( int lhs, T* const& rhs ) -> bool { return reinterpret_cast<void const*>( lhs ) == rhs; }
- template<typename T>
- auto compareEqual( long lhs, T* const& rhs ) -> bool { return reinterpret_cast<void const*>( lhs ) == rhs; }
-
- template<typename LhsT, typename RhsT>
- auto compareNotEqual( LhsT const& lhs, RhsT&& rhs ) -> bool { return lhs != rhs; };
- template<typename T>
- auto compareNotEqual( T* const& lhs, int rhs ) -> bool { return lhs != reinterpret_cast<void const*>( rhs ); }
- template<typename T>
- auto compareNotEqual( T* const& lhs, long rhs ) -> bool { return lhs != reinterpret_cast<void const*>( rhs ); }
- template<typename T>
- auto compareNotEqual( int lhs, T* const& rhs ) -> bool { return reinterpret_cast<void const*>( lhs ) != rhs; }
- template<typename T>
- auto compareNotEqual( long lhs, T* const& rhs ) -> bool { return reinterpret_cast<void const*>( lhs ) != rhs; }
-
- template<typename LhsT>
- class ExprLhs {
- LhsT m_lhs;
- public:
- ExprLhs( LhsT lhs ) : m_lhs( lhs ) {}
-
- template<typename RhsT>
- auto operator == ( RhsT const& rhs ) -> BinaryExpr<LhsT, RhsT const&> const {
- return BinaryExpr<LhsT, RhsT const&>( compareEqual( m_lhs, rhs ), m_lhs, "==", rhs );
- }
- auto operator == ( bool rhs ) -> BinaryExpr<LhsT, bool> const {
- return BinaryExpr<LhsT, bool>( m_lhs == rhs, m_lhs, "==", rhs );
- }
-
- template<typename RhsT>
- auto operator != ( RhsT const& rhs ) -> BinaryExpr<LhsT, RhsT const&> const {
- return BinaryExpr<LhsT, RhsT const&>( compareNotEqual( m_lhs, rhs ), m_lhs, "!=", rhs );
- }
- auto operator != ( bool rhs ) -> BinaryExpr<LhsT, bool> const {
- return BinaryExpr<LhsT, bool>( m_lhs != rhs, m_lhs, "!=", rhs );
- }
-
- template<typename RhsT>
- auto operator > ( RhsT const& rhs ) -> BinaryExpr<LhsT, RhsT const&> const {
- return BinaryExpr<LhsT, RhsT const&>( m_lhs > rhs, m_lhs, ">", rhs );
- }
- template<typename RhsT>
- auto operator < ( RhsT const& rhs ) -> BinaryExpr<LhsT, RhsT const&> const {
- return BinaryExpr<LhsT, RhsT const&>( m_lhs < rhs, m_lhs, "<", rhs );
- }
- template<typename RhsT>
- auto operator >= ( RhsT const& rhs ) -> BinaryExpr<LhsT, RhsT const&> const {
- return BinaryExpr<LhsT, RhsT const&>( m_lhs >= rhs, m_lhs, ">=", rhs );
- }
- template<typename RhsT>
- auto operator <= ( RhsT const& rhs ) -> BinaryExpr<LhsT, RhsT const&> const {
- return BinaryExpr<LhsT, RhsT const&>( m_lhs <= rhs, m_lhs, "<=", rhs );
- }
-
- auto makeUnaryExpr() const -> UnaryExpr<LhsT> {
- return UnaryExpr<LhsT>( m_lhs );
- }
- };
-
- void handleExpression( ITransientExpression const& expr );
-
- template<typename T>
- void handleExpression( ExprLhs<T> const& expr ) {
- handleExpression( expr.makeUnaryExpr() );
- }
-
- struct Decomposer {
- template<typename T>
- auto operator <= ( T const& lhs ) -> ExprLhs<T const&> {
- return ExprLhs<T const&>( lhs );
- }
- auto operator <=( bool value ) -> ExprLhs<bool> {
- return ExprLhs<bool>( value );
- }
- };
-
-} // end namespace Catch
-
-#ifdef _MSC_VER
-#pragma warning(pop)
-#endif
-
-// end catch_decomposer.h
-// start catch_assertioninfo.h
-
-// start catch_result_type.h
-
-namespace Catch {
-
- // ResultWas::OfType enum
- struct ResultWas { enum OfType {
- Unknown = -1,
- Ok = 0,
- Info = 1,
- Warning = 2,
-
- FailureBit = 0x10,
-
- ExpressionFailed = FailureBit | 1,
- ExplicitFailure = FailureBit | 2,
-
- Exception = 0x100 | FailureBit,
-
- ThrewException = Exception | 1,
- DidntThrowException = Exception | 2,
-
- FatalErrorCondition = 0x200 | FailureBit
-
- }; };
-
- bool isOk( ResultWas::OfType resultType );
- bool isJustInfo( int flags );
-
- // ResultDisposition::Flags enum
- struct ResultDisposition { enum Flags {
- Normal = 0x01,
-
- ContinueOnFailure = 0x02, // Failures fail test, but execution continues
- FalseTest = 0x04, // Prefix expression with !
- SuppressFail = 0x08 // Failures are reported but do not fail the test
- }; };
-
- ResultDisposition::Flags operator | ( ResultDisposition::Flags lhs, ResultDisposition::Flags rhs );
-
- bool shouldContinueOnFailure( int flags );
- bool isFalseTest( int flags );
- bool shouldSuppressFailure( int flags );
-
-} // end namespace Catch
-
-// end catch_result_type.h
-namespace Catch {
-
- struct AssertionInfo
- {
- StringRef macroName;
- SourceLineInfo lineInfo;
- StringRef capturedExpression;
- ResultDisposition::Flags resultDisposition;
-
- // We want to delete this constructor but a compiler bug in 4.8 means
- // the struct is then treated as non-aggregate
- //AssertionInfo() = delete;
- };
-
-} // end namespace Catch
-
-// end catch_assertioninfo.h
-namespace Catch {
-
- struct TestFailureException{};
- struct AssertionResultData;
-
- class LazyExpression {
- friend class AssertionHandler;
- friend struct AssertionStats;
-
- ITransientExpression const* m_transientExpression = nullptr;
- bool m_isNegated;
- public:
- LazyExpression( bool isNegated );
- LazyExpression( LazyExpression const& other );
- LazyExpression& operator = ( LazyExpression const& ) = delete;
-
- explicit operator bool() const;
-
- friend auto operator << ( std::ostream& os, LazyExpression const& lazyExpr ) -> std::ostream&;
- };
-
- class AssertionHandler {
- AssertionInfo m_assertionInfo;
- bool m_shouldDebugBreak = false;
- bool m_shouldThrow = false;
- bool m_inExceptionGuard = false;
-
- public:
- AssertionHandler
- ( StringRef macroName,
- SourceLineInfo const& lineInfo,
- StringRef capturedExpression,
- ResultDisposition::Flags resultDisposition );
- ~AssertionHandler();
-
- void handle( ITransientExpression const& expr );
-
- template<typename T>
- void handle( ExprLhs<T> const& expr ) {
- handle( expr.makeUnaryExpr() );
- }
- void handle( ResultWas::OfType resultType );
- void handle( ResultWas::OfType resultType, StringRef const& message );
- void handle( ResultWas::OfType resultType, ITransientExpression const* expr, bool negated );
- void handle( AssertionResultData const& resultData, ITransientExpression const* expr );
-
- auto shouldDebugBreak() const -> bool;
- auto allowThrows() const -> bool;
- void reactWithDebugBreak() const;
- void reactWithoutDebugBreak() const;
- void useActiveException();
- void setExceptionGuard();
- void unsetExceptionGuard();
- };
-
- void handleExceptionMatchExpr( AssertionHandler& handler, std::string const& str, StringRef matcherString );
-
-} // namespace Catch
-
-// end catch_assertionhandler.h
-// start catch_message.h
-
-#include <string>
-#include <sstream>
-
-namespace Catch {
-
- struct MessageInfo {
- MessageInfo( std::string const& _macroName,
- SourceLineInfo const& _lineInfo,
- ResultWas::OfType _type );
-
- std::string macroName;
- std::string message;
- SourceLineInfo lineInfo;
- ResultWas::OfType type;
- unsigned int sequence;
-
- bool operator == ( MessageInfo const& other ) const;
- bool operator < ( MessageInfo const& other ) const;
- private:
- static unsigned int globalCount;
- };
-
- struct MessageStream {
-
- template<typename T>
- MessageStream& operator << ( T const& value ) {
- m_stream << value;
- return *this;
- }
-
- // !TBD reuse a global/ thread-local stream
- std::ostringstream m_stream;
- };
-
- struct MessageBuilder : MessageStream {
- MessageBuilder( std::string const& macroName,
- SourceLineInfo const& lineInfo,
- ResultWas::OfType type );
-
- template<typename T>
- MessageBuilder& operator << ( T const& value ) {
- m_stream << value;
- return *this;
- }
-
- MessageInfo m_info;
- };
-
- class ScopedMessage {
- public:
- ScopedMessage( MessageBuilder const& builder );
- ~ScopedMessage();
-
- MessageInfo m_info;
- };
-
-} // end namespace Catch
-
-// end catch_message.h
-// start catch_interfaces_capture.h
-
-#include <string>
-
-namespace Catch {
-
- class AssertionResult;
- struct AssertionInfo;
- struct SectionInfo;
- struct SectionEndInfo;
- struct MessageInfo;
- struct Counts;
- struct BenchmarkInfo;
- struct BenchmarkStats;
-
- struct IResultCapture {
-
- virtual ~IResultCapture();
-
- virtual void assertionStarting( AssertionInfo const& info ) = 0;
- virtual void assertionEnded( AssertionResult const& result ) = 0;
- virtual bool sectionStarted( SectionInfo const& sectionInfo,
- Counts& assertions ) = 0;
- virtual void sectionEnded( SectionEndInfo const& endInfo ) = 0;
- virtual void sectionEndedEarly( SectionEndInfo const& endInfo ) = 0;
-
- virtual void benchmarkStarting( BenchmarkInfo const& info ) = 0;
- virtual void benchmarkEnded( BenchmarkStats const& stats ) = 0;
-
- virtual void pushScopedMessage( MessageInfo const& message ) = 0;
- virtual void popScopedMessage( MessageInfo const& message ) = 0;
-
- virtual std::string getCurrentTestName() const = 0;
- virtual const AssertionResult* getLastResult() const = 0;
-
- virtual void exceptionEarlyReported() = 0;
-
- virtual void handleFatalErrorCondition( StringRef message ) = 0;
-
- virtual bool lastAssertionPassed() = 0;
- virtual void assertionPassed() = 0;
- virtual void assertionRun() = 0;
- };
-
- IResultCapture& getResultCapture();
-}
-
-// end catch_interfaces_capture.h
-// start catch_debugger.h
-
-namespace Catch {
- bool isDebuggerActive();
-}
-
-#ifdef CATCH_PLATFORM_MAC
-
- #define CATCH_TRAP() __asm__("int $3\n" : : ) /* NOLINT */
-
-#elif defined(CATCH_PLATFORM_LINUX)
- // If we can use inline assembler, do it because this allows us to break
- // directly at the location of the failing check instead of breaking inside
- // raise() called from it, i.e. one stack frame below.
- #if defined(__GNUC__) && (defined(__i386) || defined(__x86_64))
- #define CATCH_TRAP() asm volatile ("int $3") /* NOLINT */
- #else // Fall back to the generic way.
- #include <signal.h>
-
- #define CATCH_TRAP() raise(SIGTRAP)
- #endif
-#elif defined(_MSC_VER)
- #define CATCH_TRAP() __debugbreak()
-#elif defined(__MINGW32__)
- extern "C" __declspec(dllimport) void __stdcall DebugBreak();
- #define CATCH_TRAP() DebugBreak()
-#endif
-
-#ifdef CATCH_TRAP
- #define CATCH_BREAK_INTO_DEBUGGER() if( Catch::isDebuggerActive() ) { CATCH_TRAP(); }
-#else
- #define CATCH_BREAK_INTO_DEBUGGER() Catch::alwaysTrue();
-#endif
-
-// end catch_debugger.h
-#if !defined(CATCH_CONFIG_DISABLE)
-
-#if !defined(CATCH_CONFIG_DISABLE_STRINGIFICATION)
- #define CATCH_INTERNAL_STRINGIFY(...) #__VA_ARGS__
-#else
- #define CATCH_INTERNAL_STRINGIFY(...) "Disabled by CATCH_CONFIG_DISABLE_STRINGIFICATION"
-#endif
-
-#if defined(CATCH_CONFIG_FAST_COMPILE)
-///////////////////////////////////////////////////////////////////////////////
-// We can speedup compilation significantly by breaking into debugger lower in
-// the callstack, because then we don't have to expand CATCH_BREAK_INTO_DEBUGGER
-// macro in each assertion
-#define INTERNAL_CATCH_REACT( handler ) \
- handler.reactWithDebugBreak();
-
-///////////////////////////////////////////////////////////////////////////////
-// Another way to speed-up compilation is to omit local try-catch for REQUIRE*
-// macros.
-// This can potentially cause false negative, if the test code catches
-// the exception before it propagates back up to the runner.
-#define INTERNAL_CATCH_TRY( capturer ) capturer.setExceptionGuard();
-#define INTERNAL_CATCH_CATCH( capturer ) capturer.unsetExceptionGuard();
-
-#else // CATCH_CONFIG_FAST_COMPILE
-
-///////////////////////////////////////////////////////////////////////////////
-// In the event of a failure works out if the debugger needs to be invoked
-// and/or an exception thrown and takes appropriate action.
-// This needs to be done as a macro so the debugger will stop in the user
-// source code rather than in Catch library code
-#define INTERNAL_CATCH_REACT( handler ) \
- if( handler.shouldDebugBreak() ) CATCH_BREAK_INTO_DEBUGGER(); \
- handler.reactWithoutDebugBreak();
-
-#define INTERNAL_CATCH_TRY( capturer ) try
-#define INTERNAL_CATCH_CATCH( capturer ) catch(...) { capturer.useActiveException(); }
-
-#endif
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_TEST( macroName, resultDisposition, ... ) \
- do { \
- Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(__VA_ARGS__), resultDisposition ); \
- INTERNAL_CATCH_TRY( catchAssertionHandler ) { \
- CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS \
- catchAssertionHandler.handle( Catch::Decomposer() <= __VA_ARGS__ ); \
- CATCH_INTERNAL_UNSUPPRESS_PARENTHESES_WARNINGS \
- } INTERNAL_CATCH_CATCH( catchAssertionHandler ) \
- INTERNAL_CATCH_REACT( catchAssertionHandler ) \
- } while( Catch::isTrue( false && static_cast<bool>( !!(__VA_ARGS__) ) ) ) // the expression here is never evaluated at runtime but it forces the compiler to give it a look
- // The double negation silences MSVC's C4800 warning, the static_cast forces short-circuit evaluation if the type has overloaded &&.
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_IF( macroName, resultDisposition, ... ) \
- INTERNAL_CATCH_TEST( macroName, resultDisposition, __VA_ARGS__ ); \
- if( Catch::getResultCapture().lastAssertionPassed() )
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_ELSE( macroName, resultDisposition, ... ) \
- INTERNAL_CATCH_TEST( macroName, resultDisposition, __VA_ARGS__ ); \
- if( !Catch::getResultCapture().lastAssertionPassed() )
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_NO_THROW( macroName, resultDisposition, ... ) \
- do { \
- Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(__VA_ARGS__), resultDisposition ); \
- try { \
- static_cast<void>(__VA_ARGS__); \
- catchAssertionHandler.handle( Catch::ResultWas::Ok ); \
- } \
- catch( ... ) { \
- catchAssertionHandler.useActiveException(); \
- } \
- INTERNAL_CATCH_REACT( catchAssertionHandler ) \
- } while( Catch::alwaysFalse() )
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_THROWS( macroName, resultDisposition, ... ) \
- do { \
- Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(__VA_ARGS__), resultDisposition); \
- if( catchAssertionHandler.allowThrows() ) \
- try { \
- static_cast<void>(__VA_ARGS__); \
- catchAssertionHandler.handle( Catch::ResultWas::DidntThrowException ); \
- } \
- catch( ... ) { \
- catchAssertionHandler.handle( Catch::ResultWas::Ok ); \
- } \
- else \
- catchAssertionHandler.handle( Catch::ResultWas::Ok ); \
- INTERNAL_CATCH_REACT( catchAssertionHandler ) \
- } while( Catch::alwaysFalse() )
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_THROWS_AS( macroName, exceptionType, resultDisposition, expr ) \
- do { \
- Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(expr) ", " CATCH_INTERNAL_STRINGIFY(exceptionType), resultDisposition ); \
- if( catchAssertionHandler.allowThrows() ) \
- try { \
- static_cast<void>(expr); \
- catchAssertionHandler.handle( Catch::ResultWas::DidntThrowException ); \
- } \
- catch( exceptionType const& ) { \
- catchAssertionHandler.handle( Catch::ResultWas::Ok ); \
- } \
- catch( ... ) { \
- catchAssertionHandler.useActiveException(); \
- } \
- else \
- catchAssertionHandler.handle( Catch::ResultWas::Ok ); \
- INTERNAL_CATCH_REACT( catchAssertionHandler ) \
- } while( Catch::alwaysFalse() )
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_MSG( macroName, messageType, resultDisposition, ... ) \
- do { \
- Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, "", resultDisposition ); \
- catchAssertionHandler.handle( messageType, ( Catch::MessageStream() << __VA_ARGS__ + ::Catch::StreamEndStop() ).m_stream.str() ); \
- INTERNAL_CATCH_REACT( catchAssertionHandler ) \
- } while( Catch::alwaysFalse() )
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_INFO( macroName, log ) \
- Catch::ScopedMessage INTERNAL_CATCH_UNIQUE_NAME( scopedMessage ) = Catch::MessageBuilder( macroName, CATCH_INTERNAL_LINEINFO, Catch::ResultWas::Info ) << log;
-
-///////////////////////////////////////////////////////////////////////////////
-// Although this is matcher-based, it can be used with just a string
-#define INTERNAL_CATCH_THROWS_STR_MATCHES( macroName, resultDisposition, matcher, ... ) \
- do { \
- Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(__VA_ARGS__) ", " CATCH_INTERNAL_STRINGIFY(matcher), resultDisposition ); \
- if( catchAssertionHandler.allowThrows() ) \
- try { \
- static_cast<void>(__VA_ARGS__); \
- catchAssertionHandler.handle( Catch::ResultWas::DidntThrowException ); \
- } \
- catch( ... ) { \
- handleExceptionMatchExpr( catchAssertionHandler, matcher, #matcher ); \
- } \
- else \
- catchAssertionHandler.handle( Catch::ResultWas::Ok ); \
- INTERNAL_CATCH_REACT( catchAssertionHandler ) \
- } while( Catch::alwaysFalse() )
-
-#endif // CATCH_CONFIG_DISABLE
-
-// end catch_capture.hpp
-// start catch_section.h
-
-// start catch_section_info.h
-
-// start catch_totals.h
-
-#include <cstddef>
-
-namespace Catch {
-
- struct Counts {
- Counts operator - ( Counts const& other ) const;
- Counts& operator += ( Counts const& other );
-
- std::size_t total() const;
- bool allPassed() const;
- bool allOk() const;
-
- std::size_t passed = 0;
- std::size_t failed = 0;
- std::size_t failedButOk = 0;
- };
-
- struct Totals {
-
- Totals operator - ( Totals const& other ) const;
- Totals& operator += ( Totals const& other );
-
- Totals delta( Totals const& prevTotals ) const;
-
- Counts assertions;
- Counts testCases;
- };
-}
-
-// end catch_totals.h
-#include <string>
-
-namespace Catch {
-
- struct SectionInfo {
- SectionInfo
- ( SourceLineInfo const& _lineInfo,
- std::string const& _name,
- std::string const& _description = std::string() );
-
- std::string name;
- std::string description;
- SourceLineInfo lineInfo;
- };
-
- struct SectionEndInfo {
- SectionEndInfo( SectionInfo const& _sectionInfo, Counts const& _prevAssertions, double _durationInSeconds );
-
- SectionInfo sectionInfo;
- Counts prevAssertions;
- double durationInSeconds;
- };
-
-} // end namespace Catch
-
-// end catch_section_info.h
-// start catch_timer.h
-
-#include <cstdint>
-
-namespace Catch {
-
- auto getCurrentNanosecondsSinceEpoch() -> uint64_t;
- auto getEstimatedClockResolution() -> uint64_t;
-
- class Timer {
- uint64_t m_nanoseconds = 0;
- public:
- void start();
- auto getElapsedNanoseconds() const -> unsigned int;
- auto getElapsedMicroseconds() const -> unsigned int;
- auto getElapsedMilliseconds() const -> unsigned int;
- auto getElapsedSeconds() const -> double;
- };
-
-} // namespace Catch
-
-// end catch_timer.h
-#include <string>
-
-namespace Catch {
-
- class Section : NonCopyable {
- public:
- Section( SectionInfo const& info );
- ~Section();
-
- // This indicates whether the section should be executed or not
- explicit operator bool() const;
-
- private:
- SectionInfo m_info;
-
- std::string m_name;
- Counts m_assertions;
- bool m_sectionIncluded;
- Timer m_timer;
- };
-
-} // end namespace Catch
-
- #define INTERNAL_CATCH_SECTION( ... ) \
- if( Catch::Section const& INTERNAL_CATCH_UNIQUE_NAME( catch_internal_Section ) = Catch::SectionInfo( CATCH_INTERNAL_LINEINFO, __VA_ARGS__ ) )
-
-// end catch_section.h
-// start catch_benchmark.h
-
-#include <cstdint>
-#include <string>
-
-namespace Catch {
-
- class BenchmarkLooper {
-
- std::string m_name;
- std::size_t m_count = 0;
- std::size_t m_iterationsToRun = 1;
- uint64_t m_resolution;
- Timer m_timer;
-
- static auto getResolution() -> uint64_t;
- public:
- // Keep most of this inline as it's on the code path that is being timed
- BenchmarkLooper( StringRef name )
- : m_name( name ),
- m_resolution( getResolution() )
- {
- reportStart();
- m_timer.start();
- }
-
- explicit operator bool() {
- if( m_count < m_iterationsToRun )
- return true;
- return needsMoreIterations();
- }
-
- void increment() {
- ++m_count;
- }
-
- void reportStart();
- auto needsMoreIterations() -> bool;
- };
-
-} // end namespace Catch
-
-#define BENCHMARK( name ) \
- for( Catch::BenchmarkLooper looper( name ); looper; looper.increment() )
-
-// end catch_benchmark.h
-// start catch_interfaces_exception.h
-
-// start catch_interfaces_registry_hub.h
-
-#include <string>
-#include <memory>
-
-namespace Catch {
-
- class TestCase;
- struct ITestCaseRegistry;
- struct IExceptionTranslatorRegistry;
- struct IExceptionTranslator;
- struct IReporterRegistry;
- struct IReporterFactory;
- struct ITagAliasRegistry;
- class StartupExceptionRegistry;
-
- using IReporterFactoryPtr = std::shared_ptr<IReporterFactory>;
-
- struct IRegistryHub {
- virtual ~IRegistryHub();
-
- virtual IReporterRegistry const& getReporterRegistry() const = 0;
- virtual ITestCaseRegistry const& getTestCaseRegistry() const = 0;
- virtual ITagAliasRegistry const& getTagAliasRegistry() const = 0;
-
- virtual IExceptionTranslatorRegistry& getExceptionTranslatorRegistry() = 0;
-
- virtual StartupExceptionRegistry const& getStartupExceptionRegistry() const = 0;
- };
-
- struct IMutableRegistryHub {
- virtual ~IMutableRegistryHub();
- virtual void registerReporter( std::string const& name, IReporterFactoryPtr const& factory ) = 0;
- virtual void registerListener( IReporterFactoryPtr const& factory ) = 0;
- virtual void registerTest( TestCase const& testInfo ) = 0;
- virtual void registerTranslator( const IExceptionTranslator* translator ) = 0;
- virtual void registerTagAlias( std::string const& alias, std::string const& tag, SourceLineInfo const& lineInfo ) = 0;
- virtual void registerStartupException() noexcept = 0;
- };
-
- IRegistryHub& getRegistryHub();
- IMutableRegistryHub& getMutableRegistryHub();
- void cleanUp();
- std::string translateActiveException();
-
-}
-
-// end catch_interfaces_registry_hub.h
-#if defined(CATCH_CONFIG_DISABLE)
- #define INTERNAL_CATCH_TRANSLATE_EXCEPTION_NO_REG( translatorName, signature) \
- static std::string translatorName( signature )
-#endif
-
-#include <exception>
-#include <string>
-#include <vector>
-
-namespace Catch {
- using exceptionTranslateFunction = std::string(*)();
-
- struct IExceptionTranslator;
- using ExceptionTranslators = std::vector<std::unique_ptr<IExceptionTranslator const>>;
-
- struct IExceptionTranslator {
- virtual ~IExceptionTranslator();
- virtual std::string translate( ExceptionTranslators::const_iterator it, ExceptionTranslators::const_iterator itEnd ) const = 0;
- };
-
- struct IExceptionTranslatorRegistry {
- virtual ~IExceptionTranslatorRegistry();
-
- virtual std::string translateActiveException() const = 0;
- };
-
- class ExceptionTranslatorRegistrar {
- template<typename T>
- class ExceptionTranslator : public IExceptionTranslator {
- public:
-
- ExceptionTranslator( std::string(*translateFunction)( T& ) )
- : m_translateFunction( translateFunction )
- {}
-
- std::string translate( ExceptionTranslators::const_iterator it, ExceptionTranslators::const_iterator itEnd ) const override {
- try {
- if( it == itEnd )
- std::rethrow_exception(std::current_exception());
- else
- return (*it)->translate( it+1, itEnd );
- }
- catch( T& ex ) {
- return m_translateFunction( ex );
- }
- }
-
- protected:
- std::string(*m_translateFunction)( T& );
- };
-
- public:
- template<typename T>
- ExceptionTranslatorRegistrar( std::string(*translateFunction)( T& ) ) {
- getMutableRegistryHub().registerTranslator
- ( new ExceptionTranslator<T>( translateFunction ) );
- }
- };
-}
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_TRANSLATE_EXCEPTION2( translatorName, signature ) \
- static std::string translatorName( signature ); \
- namespace{ Catch::ExceptionTranslatorRegistrar INTERNAL_CATCH_UNIQUE_NAME( catch_internal_ExceptionRegistrar )( &translatorName ); }\
- static std::string translatorName( signature )
-
-#define INTERNAL_CATCH_TRANSLATE_EXCEPTION( signature ) INTERNAL_CATCH_TRANSLATE_EXCEPTION2( INTERNAL_CATCH_UNIQUE_NAME( catch_internal_ExceptionTranslator ), signature )
-
-// end catch_interfaces_exception.h
-// start catch_approx.h
-
-// start catch_enforce.h
-
-#include <sstream>
-#include <stdexcept>
-
-#define CATCH_PREPARE_EXCEPTION( type, msg ) \
- type( static_cast<std::ostringstream&&>( std::ostringstream() << msg ).str() )
-#define CATCH_INTERNAL_ERROR( msg ) \
- throw CATCH_PREPARE_EXCEPTION( std::logic_error, CATCH_INTERNAL_LINEINFO << ": Internal Catch error: " << msg);
-#define CATCH_ERROR( msg ) \
- throw CATCH_PREPARE_EXCEPTION( std::domain_error, msg )
-#define CATCH_ENFORCE( condition, msg ) \
- do{ if( !(condition) ) CATCH_ERROR( msg ); } while(false)
-
-// end catch_enforce.h
-#include <type_traits>
-
-namespace Catch {
-namespace Detail {
-
- class Approx {
- private:
- bool equalityComparisonImpl(double other) const;
-
- public:
- explicit Approx ( double value );
-
- static Approx custom();
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- Approx operator()( T const& value ) {
- Approx approx( static_cast<double>(value) );
- approx.epsilon( m_epsilon );
- approx.margin( m_margin );
- approx.scale( m_scale );
- return approx;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- explicit Approx( T const& value ): Approx(static_cast<double>(value))
- {}
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator == ( const T& lhs, Approx const& rhs ) {
- auto lhs_v = static_cast<double>(lhs);
- return rhs.equalityComparisonImpl(lhs_v);
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator == ( Approx const& lhs, const T& rhs ) {
- return operator==( rhs, lhs );
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator != ( T const& lhs, Approx const& rhs ) {
- return !operator==( lhs, rhs );
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator != ( Approx const& lhs, T const& rhs ) {
- return !operator==( rhs, lhs );
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator <= ( T const& lhs, Approx const& rhs ) {
- return static_cast<double>(lhs) < rhs.m_value || lhs == rhs;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator <= ( Approx const& lhs, T const& rhs ) {
- return lhs.m_value < static_cast<double>(rhs) || lhs == rhs;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator >= ( T const& lhs, Approx const& rhs ) {
- return static_cast<double>(lhs) > rhs.m_value || lhs == rhs;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator >= ( Approx const& lhs, T const& rhs ) {
- return lhs.m_value > static_cast<double>(rhs) || lhs == rhs;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- Approx& epsilon( T const& newEpsilon ) {
- double epsilonAsDouble = static_cast<double>(newEpsilon);
- CATCH_ENFORCE(epsilonAsDouble >= 0 && epsilonAsDouble <= 1.0,
- "Invalid Approx::epsilon: " << epsilonAsDouble
- << ", Approx::epsilon has to be between 0 and 1");
- m_epsilon = epsilonAsDouble;
- return *this;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- Approx& margin( T const& newMargin ) {
- double marginAsDouble = static_cast<double>(newMargin);
- CATCH_ENFORCE(marginAsDouble >= 0,
- "Invalid Approx::margin: " << marginAsDouble
- << ", Approx::Margin has to be non-negative.");
- m_margin = marginAsDouble;
- return *this;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- Approx& scale( T const& newScale ) {
- m_scale = static_cast<double>(newScale);
- return *this;
- }
-
- std::string toString() const;
-
- private:
- double m_epsilon;
- double m_margin;
- double m_scale;
- double m_value;
- };
-}
-
-template<>
-struct StringMaker<Catch::Detail::Approx> {
- static std::string convert(Catch::Detail::Approx const& value);
-};
-
-} // end namespace Catch
-
-// end catch_approx.h
-// start catch_string_manip.h
-
-#include <string>
-#include <iosfwd>
-
-namespace Catch {
-
- bool startsWith( std::string const& s, std::string const& prefix );
- bool startsWith( std::string const& s, char prefix );
- bool endsWith( std::string const& s, std::string const& suffix );
- bool endsWith( std::string const& s, char suffix );
- bool contains( std::string const& s, std::string const& infix );
- void toLowerInPlace( std::string& s );
- std::string toLower( std::string const& s );
- std::string trim( std::string const& str );
- bool replaceInPlace( std::string& str, std::string const& replaceThis, std::string const& withThis );
-
- struct pluralise {
- pluralise( std::size_t count, std::string const& label );
-
- friend std::ostream& operator << ( std::ostream& os, pluralise const& pluraliser );
-
- std::size_t m_count;
- std::string m_label;
- };
-}
-
-// end catch_string_manip.h
-#ifndef CATCH_CONFIG_DISABLE_MATCHERS
-// start catch_capture_matchers.h
-
-// start catch_matchers.h
-
-#include <string>
-#include <vector>
-
-namespace Catch {
-namespace Matchers {
- namespace Impl {
-
- template<typename ArgT> struct MatchAllOf;
- template<typename ArgT> struct MatchAnyOf;
- template<typename ArgT> struct MatchNotOf;
-
- class MatcherUntypedBase {
- public:
- MatcherUntypedBase() = default;
- MatcherUntypedBase ( MatcherUntypedBase const& ) = default;
- MatcherUntypedBase& operator = ( MatcherUntypedBase const& ) = delete;
- std::string toString() const;
-
- protected:
- virtual ~MatcherUntypedBase();
- virtual std::string describe() const = 0;
- mutable std::string m_cachedToString;
- };
-
- template<typename ObjectT>
- struct MatcherMethod {
- virtual bool match( ObjectT const& arg ) const = 0;
- };
- template<typename PtrT>
- struct MatcherMethod<PtrT*> {
- virtual bool match( PtrT* arg ) const = 0;
- };
-
- template<typename ObjectT, typename ComparatorT = ObjectT>
- struct MatcherBase : MatcherUntypedBase, MatcherMethod<ObjectT> {
-
- MatchAllOf<ComparatorT> operator && ( MatcherBase const& other ) const;
- MatchAnyOf<ComparatorT> operator || ( MatcherBase const& other ) const;
- MatchNotOf<ComparatorT> operator ! () const;
- };
-
- template<typename ArgT>
- struct MatchAllOf : MatcherBase<ArgT> {
- bool match( ArgT const& arg ) const override {
- for( auto matcher : m_matchers ) {
- if (!matcher->match(arg))
- return false;
- }
- return true;
- }
- std::string describe() const override {
- std::string description;
- description.reserve( 4 + m_matchers.size()*32 );
- description += "( ";
- bool first = true;
- for( auto matcher : m_matchers ) {
- if( first )
- first = false;
- else
- description += " and ";
- description += matcher->toString();
- }
- description += " )";
- return description;
- }
-
- MatchAllOf<ArgT>& operator && ( MatcherBase<ArgT> const& other ) {
- m_matchers.push_back( &other );
- return *this;
- }
-
- std::vector<MatcherBase<ArgT> const*> m_matchers;
- };
- template<typename ArgT>
- struct MatchAnyOf : MatcherBase<ArgT> {
-
- bool match( ArgT const& arg ) const override {
- for( auto matcher : m_matchers ) {
- if (matcher->match(arg))
- return true;
- }
- return false;
- }
- std::string describe() const override {
- std::string description;
- description.reserve( 4 + m_matchers.size()*32 );
- description += "( ";
- bool first = true;
- for( auto matcher : m_matchers ) {
- if( first )
- first = false;
- else
- description += " or ";
- description += matcher->toString();
- }
- description += " )";
- return description;
- }
-
- MatchAnyOf<ArgT>& operator || ( MatcherBase<ArgT> const& other ) {
- m_matchers.push_back( &other );
- return *this;
- }
-
- std::vector<MatcherBase<ArgT> const*> m_matchers;
- };
-
- template<typename ArgT>
- struct MatchNotOf : MatcherBase<ArgT> {
-
- MatchNotOf( MatcherBase<ArgT> const& underlyingMatcher ) : m_underlyingMatcher( underlyingMatcher ) {}
-
- bool match( ArgT const& arg ) const override {
- return !m_underlyingMatcher.match( arg );
- }
-
- std::string describe() const override {
- return "not " + m_underlyingMatcher.toString();
- }
- MatcherBase<ArgT> const& m_underlyingMatcher;
- };
-
- template<typename ObjectT, typename ComparatorT>
- MatchAllOf<ComparatorT> MatcherBase<ObjectT, ComparatorT>::operator && ( MatcherBase const& other ) const {
- return MatchAllOf<ComparatorT>() && *this && other;
- }
- template<typename ObjectT, typename ComparatorT>
- MatchAnyOf<ComparatorT> MatcherBase<ObjectT, ComparatorT>::operator || ( MatcherBase const& other ) const {
- return MatchAnyOf<ComparatorT>() || *this || other;
- }
- template<typename ObjectT, typename ComparatorT>
- MatchNotOf<ComparatorT> MatcherBase<ObjectT, ComparatorT>::operator ! () const {
- return MatchNotOf<ComparatorT>( *this );
- }
-
- } // namespace Impl
-
-} // namespace Matchers
-
-using namespace Matchers;
-using Matchers::Impl::MatcherBase;
-
-} // namespace Catch
-
-// end catch_matchers.h
-// start catch_matchers_string.h
-
-#include <string>
-
-namespace Catch {
-namespace Matchers {
-
- namespace StdString {
-
- struct CasedString
- {
- CasedString( std::string const& str, CaseSensitive::Choice caseSensitivity );
- std::string adjustString( std::string const& str ) const;
- std::string caseSensitivitySuffix() const;
-
- CaseSensitive::Choice m_caseSensitivity;
- std::string m_str;
- };
-
- struct StringMatcherBase : MatcherBase<std::string> {
- StringMatcherBase( std::string const& operation, CasedString const& comparator );
- std::string describe() const override;
-
- CasedString m_comparator;
- std::string m_operation;
- };
-
- struct EqualsMatcher : StringMatcherBase {
- EqualsMatcher( CasedString const& comparator );
- bool match( std::string const& source ) const override;
- };
- struct ContainsMatcher : StringMatcherBase {
- ContainsMatcher( CasedString const& comparator );
- bool match( std::string const& source ) const override;
- };
- struct StartsWithMatcher : StringMatcherBase {
- StartsWithMatcher( CasedString const& comparator );
- bool match( std::string const& source ) const override;
- };
- struct EndsWithMatcher : StringMatcherBase {
- EndsWithMatcher( CasedString const& comparator );
- bool match( std::string const& source ) const override;
- };
-
- } // namespace StdString
-
- // The following functions create the actual matcher objects.
- // This allows the types to be inferred
-
- StdString::EqualsMatcher Equals( std::string const& str, CaseSensitive::Choice caseSensitivity = CaseSensitive::Yes );
- StdString::ContainsMatcher Contains( std::string const& str, CaseSensitive::Choice caseSensitivity = CaseSensitive::Yes );
- StdString::EndsWithMatcher EndsWith( std::string const& str, CaseSensitive::Choice caseSensitivity = CaseSensitive::Yes );
- StdString::StartsWithMatcher StartsWith( std::string const& str, CaseSensitive::Choice caseSensitivity = CaseSensitive::Yes );
-
-} // namespace Matchers
-} // namespace Catch
-
-// end catch_matchers_string.h
-// start catch_matchers_vector.h
-
-namespace Catch {
-namespace Matchers {
-
- namespace Vector {
-
- template<typename T>
- struct ContainsElementMatcher : MatcherBase<std::vector<T>, T> {
-
- ContainsElementMatcher(T const &comparator) : m_comparator( comparator) {}
-
- bool match(std::vector<T> const &v) const override {
- for (auto const& el : v) {
- if (el == m_comparator) {
- return true;
- }
- }
- return false;
- }
-
- std::string describe() const override {
- return "Contains: " + ::Catch::Detail::stringify( m_comparator );
- }
-
- T const& m_comparator;
- };
-
- template<typename T>
- struct ContainsMatcher : MatcherBase<std::vector<T>, std::vector<T> > {
-
- ContainsMatcher(std::vector<T> const &comparator) : m_comparator( comparator ) {}
-
- bool match(std::vector<T> const &v) const override {
- // !TBD: see note in EqualsMatcher
- if (m_comparator.size() > v.size())
- return false;
- for (auto const& comparator : m_comparator) {
- auto present = false;
- for (const auto& el : v) {
- if (el == comparator) {
- present = true;
- break;
- }
- }
- if (!present) {
- return false;
- }
- }
- return true;
- }
- std::string describe() const override {
- return "Contains: " + ::Catch::Detail::stringify( m_comparator );
- }
-
- std::vector<T> const& m_comparator;
- };
-
- template<typename T>
- struct EqualsMatcher : MatcherBase<std::vector<T>, std::vector<T> > {
-
- EqualsMatcher(std::vector<T> const &comparator) : m_comparator( comparator ) {}
-
- bool match(std::vector<T> const &v) const override {
- // !TBD: This currently works if all elements can be compared using !=
- // - a more general approach would be via a compare template that defaults
- // to using !=. but could be specialised for, e.g. std::vector<T> etc
- // - then just call that directly
- if (m_comparator.size() != v.size())
- return false;
- for (std::size_t i = 0; i < v.size(); ++i)
- if (m_comparator[i] != v[i])
- return false;
- return true;
- }
- std::string describe() const override {
- return "Equals: " + ::Catch::Detail::stringify( m_comparator );
- }
- std::vector<T> const& m_comparator;
- };
-
- } // namespace Vector
-
- // The following functions create the actual matcher objects.
- // This allows the types to be inferred
-
- template<typename T>
- Vector::ContainsMatcher<T> Contains( std::vector<T> const& comparator ) {
- return Vector::ContainsMatcher<T>( comparator );
- }
-
- template<typename T>
- Vector::ContainsElementMatcher<T> VectorContains( T const& comparator ) {
- return Vector::ContainsElementMatcher<T>( comparator );
- }
-
- template<typename T>
- Vector::EqualsMatcher<T> Equals( std::vector<T> const& comparator ) {
- return Vector::EqualsMatcher<T>( comparator );
- }
-
-} // namespace Matchers
-} // namespace Catch
-
-// end catch_matchers_vector.h
-namespace Catch {
-
- template<typename ArgT, typename MatcherT>
- class MatchExpr : public ITransientExpression {
- ArgT const& m_arg;
- MatcherT m_matcher;
- StringRef m_matcherString;
- bool m_result;
- public:
- MatchExpr( ArgT const& arg, MatcherT const& matcher, StringRef matcherString )
- : m_arg( arg ),
- m_matcher( matcher ),
- m_matcherString( matcherString ),
- m_result( matcher.match( arg ) )
- {}
-
- auto isBinaryExpression() const -> bool override { return true; }
- auto getResult() const -> bool override { return m_result; }
-
- void streamReconstructedExpression( std::ostream &os ) const override {
- auto matcherAsString = m_matcher.toString();
- os << Catch::Detail::stringify( m_arg ) << ' ';
- if( matcherAsString == Detail::unprintableString )
- os << m_matcherString;
- else
- os << matcherAsString;
- }
- };
-
- using StringMatcher = Matchers::Impl::MatcherBase<std::string>;
-
- void handleExceptionMatchExpr( AssertionHandler& handler, StringMatcher const& matcher, StringRef matcherString );
-
- template<typename ArgT, typename MatcherT>
- auto makeMatchExpr( ArgT const& arg, MatcherT const& matcher, StringRef matcherString ) -> MatchExpr<ArgT, MatcherT> {
- return MatchExpr<ArgT, MatcherT>( arg, matcher, matcherString );
- }
-
-} // namespace Catch
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CHECK_THAT( macroName, matcher, resultDisposition, arg ) \
- do { \
- Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(arg) ", " CATCH_INTERNAL_STRINGIFY(matcher), resultDisposition ); \
- INTERNAL_CATCH_TRY( catchAssertionHandler ) { \
- catchAssertionHandler.handle( Catch::makeMatchExpr( arg, matcher, #matcher ) ); \
- } INTERNAL_CATCH_CATCH( catchAssertionHandler ) \
- INTERNAL_CATCH_REACT( catchAssertionHandler ) \
- } while( Catch::alwaysFalse() )
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_THROWS_MATCHES( macroName, exceptionType, resultDisposition, matcher, ... ) \
- do { \
- Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(__VA_ARGS__) ", " CATCH_INTERNAL_STRINGIFY(exceptionType) ", " CATCH_INTERNAL_STRINGIFY(matcher), resultDisposition ); \
- if( catchAssertionHandler.allowThrows() ) \
- try { \
- static_cast<void>(__VA_ARGS__ ); \
- catchAssertionHandler.handle( Catch::ResultWas::DidntThrowException ); \
- } \
- catch( exceptionType const& ex ) { \
- catchAssertionHandler.handle( Catch::makeMatchExpr( ex, matcher, #matcher ) ); \
- } \
- catch( ... ) { \
- catchAssertionHandler.useActiveException(); \
- } \
- else \
- catchAssertionHandler.handle( Catch::ResultWas::Ok ); \
- INTERNAL_CATCH_REACT( catchAssertionHandler ) \
- } while( Catch::alwaysFalse() )
-
-// end catch_capture_matchers.h
-#endif
-
-// These files are included here so the single_include script doesn't put them
-// in the conditionally compiled sections
-// start catch_test_case_info.h
-
-#include <string>
-#include <vector>
-#include <memory>
-
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wpadded"
-#endif
-
-namespace Catch {
-
- struct ITestInvoker;
-
- struct TestCaseInfo {
- enum SpecialProperties{
- None = 0,
- IsHidden = 1 << 1,
- ShouldFail = 1 << 2,
- MayFail = 1 << 3,
- Throws = 1 << 4,
- NonPortable = 1 << 5,
- Benchmark = 1 << 6
- };
-
- TestCaseInfo( std::string const& _name,
- std::string const& _className,
- std::string const& _description,
- std::vector<std::string> const& _tags,
- SourceLineInfo const& _lineInfo );
-
- friend void setTags( TestCaseInfo& testCaseInfo, std::vector<std::string> tags );
-
- bool isHidden() const;
- bool throws() const;
- bool okToFail() const;
- bool expectedToFail() const;
-
- std::string tagsAsString() const;
-
- std::string name;
- std::string className;
- std::string description;
- std::vector<std::string> tags;
- std::vector<std::string> lcaseTags;
- SourceLineInfo lineInfo;
- SpecialProperties properties;
- };
-
- class TestCase : public TestCaseInfo {
- public:
-
- TestCase( ITestInvoker* testCase, TestCaseInfo const& info );
-
- TestCase withName( std::string const& _newName ) const;
-
- void invoke() const;
-
- TestCaseInfo const& getTestCaseInfo() const;
-
- bool operator == ( TestCase const& other ) const;
- bool operator < ( TestCase const& other ) const;
-
- private:
- std::shared_ptr<ITestInvoker> test;
- };
-
- TestCase makeTestCase( ITestInvoker* testCase,
- std::string const& className,
- std::string const& name,
- std::string const& description,
- SourceLineInfo const& lineInfo );
-}
-
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
-
-// end catch_test_case_info.h
-// start catch_interfaces_runner.h
-
-namespace Catch {
-
- struct IRunner {
- virtual ~IRunner();
- virtual bool aborting() const = 0;
- };
-}
-
-// end catch_interfaces_runner.h
-
-#ifdef __OBJC__
-// start catch_objc.hpp
-
-#import <objc/runtime.h>
-
-#include <string>
-
-// NB. Any general catch headers included here must be included
-// in catch.hpp first to make sure they are included by the single
-// header for non obj-usage
-
-///////////////////////////////////////////////////////////////////////////////
-// This protocol is really only here for (self) documenting purposes, since
-// all its methods are optional.
-@protocol OcFixture
-
-@optional
-
--(void) setUp;
--(void) tearDown;
-
-@end
-
-namespace Catch {
-
- class OcMethod : public ITestInvoker {
-
- public:
- OcMethod( Class cls, SEL sel ) : m_cls( cls ), m_sel( sel ) {}
-
- virtual void invoke() const {
- id obj = [[m_cls alloc] init];
-
- performOptionalSelector( obj, @selector(setUp) );
- performOptionalSelector( obj, m_sel );
- performOptionalSelector( obj, @selector(tearDown) );
-
- arcSafeRelease( obj );
- }
- private:
- virtual ~OcMethod() {}
-
- Class m_cls;
- SEL m_sel;
- };
-
- namespace Detail{
-
- inline std::string getAnnotation( Class cls,
- std::string const& annotationName,
- std::string const& testCaseName ) {
- NSString* selStr = [[NSString alloc] initWithFormat:@"Catch_%s_%s", annotationName.c_str(), testCaseName.c_str()];
- SEL sel = NSSelectorFromString( selStr );
- arcSafeRelease( selStr );
- id value = performOptionalSelector( cls, sel );
- if( value )
- return [(NSString*)value UTF8String];
- return "";
- }
- }
-
- inline std::size_t registerTestMethods() {
- std::size_t noTestMethods = 0;
- int noClasses = objc_getClassList( nullptr, 0 );
-
- Class* classes = (CATCH_UNSAFE_UNRETAINED Class *)malloc( sizeof(Class) * noClasses);
- objc_getClassList( classes, noClasses );
-
- for( int c = 0; c < noClasses; c++ ) {
- Class cls = classes[c];
- {
- u_int count;
- Method* methods = class_copyMethodList( cls, &count );
- for( u_int m = 0; m < count ; m++ ) {
- SEL selector = method_getName(methods[m]);
- std::string methodName = sel_getName(selector);
- if( startsWith( methodName, "Catch_TestCase_" ) ) {
- std::string testCaseName = methodName.substr( 15 );
- std::string name = Detail::getAnnotation( cls, "Name", testCaseName );
- std::string desc = Detail::getAnnotation( cls, "Description", testCaseName );
- const char* className = class_getName( cls );
-
- getMutableRegistryHub().registerTest( makeTestCase( new OcMethod( cls, selector ), className, name.c_str(), desc.c_str(), SourceLineInfo("",0) ) );
- noTestMethods++;
- }
- }
- free(methods);
- }
- }
- return noTestMethods;
- }
-
-#if !defined(CATCH_CONFIG_DISABLE_MATCHERS)
-
- namespace Matchers {
- namespace Impl {
- namespace NSStringMatchers {
-
- struct StringHolder : MatcherBase<NSString*>{
- StringHolder( NSString* substr ) : m_substr( [substr copy] ){}
- StringHolder( StringHolder const& other ) : m_substr( [other.m_substr copy] ){}
- StringHolder() {
- arcSafeRelease( m_substr );
- }
-
- bool match( NSString* arg ) const override {
- return false;
- }
-
- NSString* CATCH_ARC_STRONG m_substr;
- };
-
- struct Equals : StringHolder {
- Equals( NSString* substr ) : StringHolder( substr ){}
-
- bool match( NSString* str ) const override {
- return (str != nil || m_substr == nil ) &&
- [str isEqualToString:m_substr];
- }
-
- std::string describe() const override {
- return "equals string: " + Catch::Detail::stringify( m_substr );
- }
- };
-
- struct Contains : StringHolder {
- Contains( NSString* substr ) : StringHolder( substr ){}
-
- bool match( NSString* str ) const {
- return (str != nil || m_substr == nil ) &&
- [str rangeOfString:m_substr].location != NSNotFound;
- }
-
- std::string describe() const override {
- return "contains string: " + Catch::Detail::stringify( m_substr );
- }
- };
-
- struct StartsWith : StringHolder {
- StartsWith( NSString* substr ) : StringHolder( substr ){}
-
- bool match( NSString* str ) const override {
- return (str != nil || m_substr == nil ) &&
- [str rangeOfString:m_substr].location == 0;
- }
-
- std::string describe() const override {
- return "starts with: " + Catch::Detail::stringify( m_substr );
- }
- };
- struct EndsWith : StringHolder {
- EndsWith( NSString* substr ) : StringHolder( substr ){}
-
- bool match( NSString* str ) const override {
- return (str != nil || m_substr == nil ) &&
- [str rangeOfString:m_substr].location == [str length] - [m_substr length];
- }
-
- std::string describe() const override {
- return "ends with: " + Catch::Detail::stringify( m_substr );
- }
- };
-
- } // namespace NSStringMatchers
- } // namespace Impl
-
- inline Impl::NSStringMatchers::Equals
- Equals( NSString* substr ){ return Impl::NSStringMatchers::Equals( substr ); }
-
- inline Impl::NSStringMatchers::Contains
- Contains( NSString* substr ){ return Impl::NSStringMatchers::Contains( substr ); }
-
- inline Impl::NSStringMatchers::StartsWith
- StartsWith( NSString* substr ){ return Impl::NSStringMatchers::StartsWith( substr ); }
-
- inline Impl::NSStringMatchers::EndsWith
- EndsWith( NSString* substr ){ return Impl::NSStringMatchers::EndsWith( substr ); }
-
- } // namespace Matchers
-
- using namespace Matchers;
-
-#endif // CATCH_CONFIG_DISABLE_MATCHERS
-
-} // namespace Catch
-
-///////////////////////////////////////////////////////////////////////////////
-#define OC_MAKE_UNIQUE_NAME( root, uniqueSuffix ) root##uniqueSuffix
-#define OC_TEST_CASE2( name, desc, uniqueSuffix ) \
-+(NSString*) OC_MAKE_UNIQUE_NAME( Catch_Name_test_, uniqueSuffix ) \
-{ \
-return @ name; \
-} \
-+(NSString*) OC_MAKE_UNIQUE_NAME( Catch_Description_test_, uniqueSuffix ) \
-{ \
-return @ desc; \
-} \
--(void) OC_MAKE_UNIQUE_NAME( Catch_TestCase_test_, uniqueSuffix )
-
-#define OC_TEST_CASE( name, desc ) OC_TEST_CASE2( name, desc, __LINE__ )
-
-// end catch_objc.hpp
-#endif
-
-#ifdef CATCH_CONFIG_EXTERNAL_INTERFACES
-// start catch_external_interfaces.h
-
-// start catch_reporter_bases.hpp
-
-// start catch_interfaces_reporter.h
-
-// start catch_config.hpp
-
-// start catch_test_spec_parser.h
-
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wpadded"
-#endif
-
-// start catch_test_spec.h
-
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wpadded"
-#endif
-
-// start catch_wildcard_pattern.h
-
-namespace Catch
-{
- class WildcardPattern {
- enum WildcardPosition {
- NoWildcard = 0,
- WildcardAtStart = 1,
- WildcardAtEnd = 2,
- WildcardAtBothEnds = WildcardAtStart | WildcardAtEnd
- };
-
- public:
-
- WildcardPattern( std::string const& pattern, CaseSensitive::Choice caseSensitivity );
- virtual ~WildcardPattern() = default;
- virtual bool matches( std::string const& str ) const;
-
- private:
- std::string adjustCase( std::string const& str ) const;
- CaseSensitive::Choice m_caseSensitivity;
- WildcardPosition m_wildcard = NoWildcard;
- std::string m_pattern;
- };
-}
-
-// end catch_wildcard_pattern.h
-#include <string>
-#include <vector>
-#include <memory>
-
-namespace Catch {
-
- class TestSpec {
- struct Pattern {
- virtual ~Pattern();
- virtual bool matches( TestCaseInfo const& testCase ) const = 0;
- };
- using PatternPtr = std::shared_ptr<Pattern>;
-
- class NamePattern : public Pattern {
- public:
- NamePattern( std::string const& name );
- virtual ~NamePattern();
- virtual bool matches( TestCaseInfo const& testCase ) const override;
- private:
- WildcardPattern m_wildcardPattern;
- };
-
- class TagPattern : public Pattern {
- public:
- TagPattern( std::string const& tag );
- virtual ~TagPattern();
- virtual bool matches( TestCaseInfo const& testCase ) const override;
- private:
- std::string m_tag;
- };
-
- class ExcludedPattern : public Pattern {
- public:
- ExcludedPattern( PatternPtr const& underlyingPattern );
- virtual ~ExcludedPattern();
- virtual bool matches( TestCaseInfo const& testCase ) const override;
- private:
- PatternPtr m_underlyingPattern;
- };
-
- struct Filter {
- std::vector<PatternPtr> m_patterns;
-
- bool matches( TestCaseInfo const& testCase ) const;
- };
-
- public:
- bool hasFilters() const;
- bool matches( TestCaseInfo const& testCase ) const;
-
- private:
- std::vector<Filter> m_filters;
-
- friend class TestSpecParser;
- };
-}
-
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
-
-// end catch_test_spec.h
-// start catch_interfaces_tag_alias_registry.h
-
-#include <string>
-
-namespace Catch {
-
- struct TagAlias;
-
- struct ITagAliasRegistry {
- virtual ~ITagAliasRegistry();
- // Nullptr if not present
- virtual TagAlias const* find( std::string const& alias ) const = 0;
- virtual std::string expandAliases( std::string const& unexpandedTestSpec ) const = 0;
-
- static ITagAliasRegistry const& get();
- };
-
-} // end namespace Catch
-
-// end catch_interfaces_tag_alias_registry.h
-namespace Catch {
-
- class TestSpecParser {
- enum Mode{ None, Name, QuotedName, Tag, EscapedName };
- Mode m_mode = None;
- bool m_exclusion = false;
- std::size_t m_start = std::string::npos, m_pos = 0;
- std::string m_arg;
- std::vector<std::size_t> m_escapeChars;
- TestSpec::Filter m_currentFilter;
- TestSpec m_testSpec;
- ITagAliasRegistry const* m_tagAliases = nullptr;
-
- public:
- TestSpecParser( ITagAliasRegistry const& tagAliases );
-
- TestSpecParser& parse( std::string const& arg );
- TestSpec testSpec();
-
- private:
- void visitChar( char c );
- void startNewMode( Mode mode, std::size_t start );
- void escape();
- std::string subString() const;
-
- template<typename T>
- void addPattern() {
- std::string token = subString();
- for( std::size_t i = 0; i < m_escapeChars.size(); ++i )
- token = token.substr( 0, m_escapeChars[i]-m_start-i ) + token.substr( m_escapeChars[i]-m_start-i+1 );
- m_escapeChars.clear();
- if( startsWith( token, "exclude:" ) ) {
- m_exclusion = true;
- token = token.substr( 8 );
- }
- if( !token.empty() ) {
- TestSpec::PatternPtr pattern = std::make_shared<T>( token );
- if( m_exclusion )
- pattern = std::make_shared<TestSpec::ExcludedPattern>( pattern );
- m_currentFilter.m_patterns.push_back( pattern );
- }
- m_exclusion = false;
- m_mode = None;
- }
-
- void addFilter();
- };
- TestSpec parseTestSpec( std::string const& arg );
-
-} // namespace Catch
-
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
-
-// end catch_test_spec_parser.h
-// start catch_interfaces_config.h
-
-#include <iosfwd>
-#include <string>
-#include <vector>
-#include <memory>
-
-namespace Catch {
-
- enum class Verbosity {
- Quiet = 0,
- Normal,
- High
- };
-
- struct WarnAbout { enum What {
- Nothing = 0x00,
- NoAssertions = 0x01
- }; };
-
- struct ShowDurations { enum OrNot {
- DefaultForReporter,
- Always,
- Never
- }; };
- struct RunTests { enum InWhatOrder {
- InDeclarationOrder,
- InLexicographicalOrder,
- InRandomOrder
- }; };
- struct UseColour { enum YesOrNo {
- Auto,
- Yes,
- No
- }; };
- struct WaitForKeypress { enum When {
- Never,
- BeforeStart = 1,
- BeforeExit = 2,
- BeforeStartAndExit = BeforeStart | BeforeExit
- }; };
-
- class TestSpec;
-
- struct IConfig : NonCopyable {
-
- virtual ~IConfig();
-
- virtual bool allowThrows() const = 0;
- virtual std::ostream& stream() const = 0;
- virtual std::string name() const = 0;
- virtual bool includeSuccessfulResults() const = 0;
- virtual bool shouldDebugBreak() const = 0;
- virtual bool warnAboutMissingAssertions() const = 0;
- virtual int abortAfter() const = 0;
- virtual bool showInvisibles() const = 0;
- virtual ShowDurations::OrNot showDurations() const = 0;
- virtual TestSpec const& testSpec() const = 0;
- virtual RunTests::InWhatOrder runOrder() const = 0;
- virtual unsigned int rngSeed() const = 0;
- virtual int benchmarkResolutionMultiple() const = 0;
- virtual UseColour::YesOrNo useColour() const = 0;
- virtual std::vector<std::string> const& getSectionsToRun() const = 0;
- virtual Verbosity verbosity() const = 0;
- };
-
- using IConfigPtr = std::shared_ptr<IConfig const>;
-}
-
-// end catch_interfaces_config.h
-// Libstdc++ doesn't like incomplete classes for unique_ptr
-// start catch_stream.h
-
-// start catch_streambuf.h
-
-#include <streambuf>
-
-namespace Catch {
-
- class StreamBufBase : public std::streambuf {
- public:
- virtual ~StreamBufBase();
- };
-}
-
-// end catch_streambuf.h
-#include <streambuf>
-#include <ostream>
-#include <fstream>
-#include <memory>
-
-namespace Catch {
-
- std::ostream& cout();
- std::ostream& cerr();
- std::ostream& clog();
-
- struct IStream {
- virtual ~IStream();
- virtual std::ostream& stream() const = 0;
- };
-
- class FileStream : public IStream {
- mutable std::ofstream m_ofs;
- public:
- FileStream( std::string const& filename );
- ~FileStream() override = default;
- public: // IStream
- std::ostream& stream() const override;
- };
-
- class CoutStream : public IStream {
- mutable std::ostream m_os;
- public:
- CoutStream();
- ~CoutStream() override = default;
-
- public: // IStream
- std::ostream& stream() const override;
- };
-
- class DebugOutStream : public IStream {
- std::unique_ptr<StreamBufBase> m_streamBuf;
- mutable std::ostream m_os;
- public:
- DebugOutStream();
- ~DebugOutStream() override = default;
-
- public: // IStream
- std::ostream& stream() const override;
- };
-}
-
-// end catch_stream.h
-
-#include <memory>
-#include <vector>
-#include <string>
-
-#ifndef CATCH_CONFIG_CONSOLE_WIDTH
-#define CATCH_CONFIG_CONSOLE_WIDTH 80
-#endif
-
-namespace Catch {
-
- struct IStream;
-
- struct ConfigData {
- bool listTests = false;
- bool listTags = false;
- bool listReporters = false;
- bool listTestNamesOnly = false;
-
- bool showSuccessfulTests = false;
- bool shouldDebugBreak = false;
- bool noThrow = false;
- bool showHelp = false;
- bool showInvisibles = false;
- bool filenamesAsTags = false;
- bool libIdentify = false;
-
- int abortAfter = -1;
- unsigned int rngSeed = 0;
- int benchmarkResolutionMultiple = 100;
-
- Verbosity verbosity = Verbosity::Normal;
- WarnAbout::What warnings = WarnAbout::Nothing;
- ShowDurations::OrNot showDurations = ShowDurations::DefaultForReporter;
- RunTests::InWhatOrder runOrder = RunTests::InDeclarationOrder;
- UseColour::YesOrNo useColour = UseColour::Auto;
- WaitForKeypress::When waitForKeypress = WaitForKeypress::Never;
-
- std::string outputFilename;
- std::string name;
- std::string processName;
-
- std::vector<std::string> reporterNames;
- std::vector<std::string> testsOrTags;
- std::vector<std::string> sectionsToRun;
- };
-
- class Config : public IConfig {
- public:
-
- Config() = default;
- Config( ConfigData const& data );
- virtual ~Config() = default;
-
- std::string const& getFilename() const;
-
- bool listTests() const;
- bool listTestNamesOnly() const;
- bool listTags() const;
- bool listReporters() const;
-
- std::string getProcessName() const;
-
- std::vector<std::string> const& getReporterNames() const;
- std::vector<std::string> const& getSectionsToRun() const override;
-
- virtual TestSpec const& testSpec() const override;
-
- bool showHelp() const;
-
- // IConfig interface
- bool allowThrows() const override;
- std::ostream& stream() const override;
- std::string name() const override;
- bool includeSuccessfulResults() const override;
- bool warnAboutMissingAssertions() const override;
- ShowDurations::OrNot showDurations() const override;
- RunTests::InWhatOrder runOrder() const override;
- unsigned int rngSeed() const override;
- int benchmarkResolutionMultiple() const override;
- UseColour::YesOrNo useColour() const override;
- bool shouldDebugBreak() const override;
- int abortAfter() const override;
- bool showInvisibles() const override;
- Verbosity verbosity() const override;
-
- private:
-
- IStream const* openStream();
- ConfigData m_data;
-
- std::unique_ptr<IStream const> m_stream;
- TestSpec m_testSpec;
- };
-
-} // end namespace Catch
-
-// end catch_config.hpp
-// start catch_assertionresult.h
-
-#include <string>
-
-namespace Catch {
-
- struct AssertionResultData
- {
- AssertionResultData() = delete;
-
- AssertionResultData( ResultWas::OfType _resultType, LazyExpression const& _lazyExpression );
-
- std::string message;
- mutable std::string reconstructedExpression;
- LazyExpression lazyExpression;
- ResultWas::OfType resultType;
-
- std::string reconstructExpression() const;
- };
-
- class AssertionResult {
- public:
- AssertionResult() = delete;
- AssertionResult( AssertionInfo const& info, AssertionResultData const& data );
-
- bool isOk() const;
- bool succeeded() const;
- ResultWas::OfType getResultType() const;
- bool hasExpression() const;
- bool hasMessage() const;
- std::string getExpression() const;
- std::string getExpressionInMacro() const;
- bool hasExpandedExpression() const;
- std::string getExpandedExpression() const;
- std::string getMessage() const;
- SourceLineInfo getSourceInfo() const;
- std::string getTestMacroName() const;
-
- //protected:
- AssertionInfo m_info;
- AssertionResultData m_resultData;
- };
-
-} // end namespace Catch
-
-// end catch_assertionresult.h
-// start catch_option.hpp
-
-namespace Catch {
-
- // An optional type
- template<typename T>
- class Option {
- public:
- Option() : nullableValue( nullptr ) {}
- Option( T const& _value )
- : nullableValue( new( storage ) T( _value ) )
- {}
- Option( Option const& _other )
- : nullableValue( _other ? new( storage ) T( *_other ) : nullptr )
- {}
-
- ~Option() {
- reset();
- }
-
- Option& operator= ( Option const& _other ) {
- if( &_other != this ) {
- reset();
- if( _other )
- nullableValue = new( storage ) T( *_other );
- }
- return *this;
- }
- Option& operator = ( T const& _value ) {
- reset();
- nullableValue = new( storage ) T( _value );
- return *this;
- }
-
- void reset() {
- if( nullableValue )
- nullableValue->~T();
- nullableValue = nullptr;
- }
-
- T& operator*() { return *nullableValue; }
- T const& operator*() const { return *nullableValue; }
- T* operator->() { return nullableValue; }
- const T* operator->() const { return nullableValue; }
-
- T valueOr( T const& defaultValue ) const {
- return nullableValue ? *nullableValue : defaultValue;
- }
-
- bool some() const { return nullableValue != nullptr; }
- bool none() const { return nullableValue == nullptr; }
-
- bool operator !() const { return nullableValue == nullptr; }
- explicit operator bool() const {
- return some();
- }
-
- private:
- T *nullableValue;
- alignas(alignof(T)) char storage[sizeof(T)];
- };
-
-} // end namespace Catch
-
-// end catch_option.hpp
-#include <string>
-#include <iosfwd>
-#include <map>
-#include <set>
-#include <memory>
-
-namespace Catch {
-
- struct ReporterConfig {
- explicit ReporterConfig( IConfigPtr const& _fullConfig );
-
- ReporterConfig( IConfigPtr const& _fullConfig, std::ostream& _stream );
-
- std::ostream& stream() const;
- IConfigPtr fullConfig() const;
-
- private:
- std::ostream* m_stream;
- IConfigPtr m_fullConfig;
- };
-
- struct ReporterPreferences {
- bool shouldRedirectStdOut = false;
- };
-
- template<typename T>
- struct LazyStat : Option<T> {
- LazyStat& operator=( T const& _value ) {
- Option<T>::operator=( _value );
- used = false;
- return *this;
- }
- void reset() {
- Option<T>::reset();
- used = false;
- }
- bool used = false;
- };
-
- struct TestRunInfo {
- TestRunInfo( std::string const& _name );
- std::string name;
- };
- struct GroupInfo {
- GroupInfo( std::string const& _name,
- std::size_t _groupIndex,
- std::size_t _groupsCount );
-
- std::string name;
- std::size_t groupIndex;
- std::size_t groupsCounts;
- };
-
- struct AssertionStats {
- AssertionStats( AssertionResult const& _assertionResult,
- std::vector<MessageInfo> const& _infoMessages,
- Totals const& _totals );
-
- AssertionStats( AssertionStats const& ) = default;
- AssertionStats( AssertionStats && ) = default;
- AssertionStats& operator = ( AssertionStats const& ) = default;
- AssertionStats& operator = ( AssertionStats && ) = default;
- virtual ~AssertionStats();
-
- AssertionResult assertionResult;
- std::vector<MessageInfo> infoMessages;
- Totals totals;
- };
-
- struct SectionStats {
- SectionStats( SectionInfo const& _sectionInfo,
- Counts const& _assertions,
- double _durationInSeconds,
- bool _missingAssertions );
- SectionStats( SectionStats const& ) = default;
- SectionStats( SectionStats && ) = default;
- SectionStats& operator = ( SectionStats const& ) = default;
- SectionStats& operator = ( SectionStats && ) = default;
- virtual ~SectionStats();
-
- SectionInfo sectionInfo;
- Counts assertions;
- double durationInSeconds;
- bool missingAssertions;
- };
-
- struct TestCaseStats {
- TestCaseStats( TestCaseInfo const& _testInfo,
- Totals const& _totals,
- std::string const& _stdOut,
- std::string const& _stdErr,
- bool _aborting );
-
- TestCaseStats( TestCaseStats const& ) = default;
- TestCaseStats( TestCaseStats && ) = default;
- TestCaseStats& operator = ( TestCaseStats const& ) = default;
- TestCaseStats& operator = ( TestCaseStats && ) = default;
- virtual ~TestCaseStats();
-
- TestCaseInfo testInfo;
- Totals totals;
- std::string stdOut;
- std::string stdErr;
- bool aborting;
- };
-
- struct TestGroupStats {
- TestGroupStats( GroupInfo const& _groupInfo,
- Totals const& _totals,
- bool _aborting );
- TestGroupStats( GroupInfo const& _groupInfo );
-
- TestGroupStats( TestGroupStats const& ) = default;
- TestGroupStats( TestGroupStats && ) = default;
- TestGroupStats& operator = ( TestGroupStats const& ) = default;
- TestGroupStats& operator = ( TestGroupStats && ) = default;
- virtual ~TestGroupStats();
-
- GroupInfo groupInfo;
- Totals totals;
- bool aborting;
- };
-
- struct TestRunStats {
- TestRunStats( TestRunInfo const& _runInfo,
- Totals const& _totals,
- bool _aborting );
-
- TestRunStats( TestRunStats const& ) = default;
- TestRunStats( TestRunStats && ) = default;
- TestRunStats& operator = ( TestRunStats const& ) = default;
- TestRunStats& operator = ( TestRunStats && ) = default;
- virtual ~TestRunStats();
-
- TestRunInfo runInfo;
- Totals totals;
- bool aborting;
- };
-
- struct BenchmarkInfo {
- std::string name;
- };
- struct BenchmarkStats {
- BenchmarkInfo info;
- std::size_t iterations;
- uint64_t elapsedTimeInNanoseconds;
- };
-
- struct IStreamingReporter {
- virtual ~IStreamingReporter() = default;
-
- // Implementing class must also provide the following static methods:
- // static std::string getDescription();
- // static std::set<Verbosity> getSupportedVerbosities()
-
- virtual ReporterPreferences getPreferences() const = 0;
-
- virtual void noMatchingTestCases( std::string const& spec ) = 0;
-
- virtual void testRunStarting( TestRunInfo const& testRunInfo ) = 0;
- virtual void testGroupStarting( GroupInfo const& groupInfo ) = 0;
-
- virtual void testCaseStarting( TestCaseInfo const& testInfo ) = 0;
- virtual void sectionStarting( SectionInfo const& sectionInfo ) = 0;
-
- // *** experimental ***
- virtual void benchmarkStarting( BenchmarkInfo const& ) {}
-
- virtual void assertionStarting( AssertionInfo const& assertionInfo ) = 0;
-
- // The return value indicates if the messages buffer should be cleared:
- virtual bool assertionEnded( AssertionStats const& assertionStats ) = 0;
-
- // *** experimental ***
- virtual void benchmarkEnded( BenchmarkStats const& ) {}
-
- virtual void sectionEnded( SectionStats const& sectionStats ) = 0;
- virtual void testCaseEnded( TestCaseStats const& testCaseStats ) = 0;
- virtual void testGroupEnded( TestGroupStats const& testGroupStats ) = 0;
- virtual void testRunEnded( TestRunStats const& testRunStats ) = 0;
-
- virtual void skipTest( TestCaseInfo const& testInfo ) = 0;
-
- // Default empty implementation provided
- virtual void fatalErrorEncountered( StringRef name );
-
- virtual bool isMulti() const;
- };
- using IStreamingReporterPtr = std::unique_ptr<IStreamingReporter>;
-
- struct IReporterFactory {
- virtual ~IReporterFactory();
- virtual IStreamingReporterPtr create( ReporterConfig const& config ) const = 0;
- virtual std::string getDescription() const = 0;
- };
- using IReporterFactoryPtr = std::shared_ptr<IReporterFactory>;
-
- struct IReporterRegistry {
- using FactoryMap = std::map<std::string, IReporterFactoryPtr>;
- using Listeners = std::vector<IReporterFactoryPtr>;
-
- virtual ~IReporterRegistry();
- virtual IStreamingReporterPtr create( std::string const& name, IConfigPtr const& config ) const = 0;
- virtual FactoryMap const& getFactories() const = 0;
- virtual Listeners const& getListeners() const = 0;
- };
-
- void addReporter( IStreamingReporterPtr& existingReporter, IStreamingReporterPtr&& additionalReporter );
-
-} // end namespace Catch
-
-// end catch_interfaces_reporter.h
-#include <algorithm>
-#include <cstring>
-#include <cfloat>
-#include <cstdio>
-#include <assert.h>
-#include <memory>
-
-namespace Catch {
- void prepareExpandedExpression(AssertionResult& result);
-
- // Returns double formatted as %.3f (format expected on output)
- std::string getFormattedDuration( double duration );
-
- template<typename DerivedT>
- struct StreamingReporterBase : IStreamingReporter {
-
- StreamingReporterBase( ReporterConfig const& _config )
- : m_config( _config.fullConfig() ),
- stream( _config.stream() )
- {
- m_reporterPrefs.shouldRedirectStdOut = false;
- CATCH_ENFORCE( DerivedT::getSupportedVerbosities().count( m_config->verbosity() ), "Verbosity level not supported by this reporter" );
- }
-
- ReporterPreferences getPreferences() const override {
- return m_reporterPrefs;
- }
-
- static std::set<Verbosity> getSupportedVerbosities() {
- return { Verbosity::Normal };
- }
-
- ~StreamingReporterBase() override = default;
-
- void noMatchingTestCases(std::string const&) override {}
-
- void testRunStarting(TestRunInfo const& _testRunInfo) override {
- currentTestRunInfo = _testRunInfo;
- }
- void testGroupStarting(GroupInfo const& _groupInfo) override {
- currentGroupInfo = _groupInfo;
- }
-
- void testCaseStarting(TestCaseInfo const& _testInfo) override {
- currentTestCaseInfo = _testInfo;
- }
- void sectionStarting(SectionInfo const& _sectionInfo) override {
- m_sectionStack.push_back(_sectionInfo);
- }
-
- void sectionEnded(SectionStats const& /* _sectionStats */) override {
- m_sectionStack.pop_back();
- }
- void testCaseEnded(TestCaseStats const& /* _testCaseStats */) override {
- currentTestCaseInfo.reset();
- }
- void testGroupEnded(TestGroupStats const& /* _testGroupStats */) override {
- currentGroupInfo.reset();
- }
- void testRunEnded(TestRunStats const& /* _testRunStats */) override {
- currentTestCaseInfo.reset();
- currentGroupInfo.reset();
- currentTestRunInfo.reset();
- }
-
- void skipTest(TestCaseInfo const&) override {
- // Don't do anything with this by default.
- // It can optionally be overridden in the derived class.
- }
-
- IConfigPtr m_config;
- std::ostream& stream;
-
- LazyStat<TestRunInfo> currentTestRunInfo;
- LazyStat<GroupInfo> currentGroupInfo;
- LazyStat<TestCaseInfo> currentTestCaseInfo;
-
- std::vector<SectionInfo> m_sectionStack;
- ReporterPreferences m_reporterPrefs;
- };
-
- template<typename DerivedT>
- struct CumulativeReporterBase : IStreamingReporter {
- template<typename T, typename ChildNodeT>
- struct Node {
- explicit Node( T const& _value ) : value( _value ) {}
- virtual ~Node() {}
-
- using ChildNodes = std::vector<std::shared_ptr<ChildNodeT>>;
- T value;
- ChildNodes children;
- };
- struct SectionNode {
- explicit SectionNode(SectionStats const& _stats) : stats(_stats) {}
- virtual ~SectionNode() = default;
-
- bool operator == (SectionNode const& other) const {
- return stats.sectionInfo.lineInfo == other.stats.sectionInfo.lineInfo;
- }
- bool operator == (std::shared_ptr<SectionNode> const& other) const {
- return operator==(*other);
- }
-
- SectionStats stats;
- using ChildSections = std::vector<std::shared_ptr<SectionNode>>;
- using Assertions = std::vector<AssertionStats>;
- ChildSections childSections;
- Assertions assertions;
- std::string stdOut;
- std::string stdErr;
- };
-
- struct BySectionInfo {
- BySectionInfo( SectionInfo const& other ) : m_other( other ) {}
- BySectionInfo( BySectionInfo const& other ) : m_other( other.m_other ) {}
- bool operator() (std::shared_ptr<SectionNode> const& node) const {
- return ((node->stats.sectionInfo.name == m_other.name) &&
- (node->stats.sectionInfo.lineInfo == m_other.lineInfo));
- }
- void operator=(BySectionInfo const&) = delete;
-
- private:
- SectionInfo const& m_other;
- };
-
- using TestCaseNode = Node<TestCaseStats, SectionNode>;
- using TestGroupNode = Node<TestGroupStats, TestCaseNode>;
- using TestRunNode = Node<TestRunStats, TestGroupNode>;
-
- CumulativeReporterBase( ReporterConfig const& _config )
- : m_config( _config.fullConfig() ),
- stream( _config.stream() )
- {
- m_reporterPrefs.shouldRedirectStdOut = false;
- CATCH_ENFORCE( DerivedT::getSupportedVerbosities().count( m_config->verbosity() ), "Verbosity level not supported by this reporter" );
- }
- ~CumulativeReporterBase() override = default;
-
- ReporterPreferences getPreferences() const override {
- return m_reporterPrefs;
- }
-
- static std::set<Verbosity> getSupportedVerbosities() {
- return { Verbosity::Normal };
- }
-
- void testRunStarting( TestRunInfo const& ) override {}
- void testGroupStarting( GroupInfo const& ) override {}
-
- void testCaseStarting( TestCaseInfo const& ) override {}
-
- void sectionStarting( SectionInfo const& sectionInfo ) override {
- SectionStats incompleteStats( sectionInfo, Counts(), 0, false );
- std::shared_ptr<SectionNode> node;
- if( m_sectionStack.empty() ) {
- if( !m_rootSection )
- m_rootSection = std::make_shared<SectionNode>( incompleteStats );
- node = m_rootSection;
- }
- else {
- SectionNode& parentNode = *m_sectionStack.back();
- auto it =
- std::find_if( parentNode.childSections.begin(),
- parentNode.childSections.end(),
- BySectionInfo( sectionInfo ) );
- if( it == parentNode.childSections.end() ) {
- node = std::make_shared<SectionNode>( incompleteStats );
- parentNode.childSections.push_back( node );
- }
- else
- node = *it;
- }
- m_sectionStack.push_back( node );
- m_deepestSection = std::move(node);
- }
-
- void assertionStarting(AssertionInfo const&) override {}
-
- bool assertionEnded(AssertionStats const& assertionStats) override {
- assert(!m_sectionStack.empty());
- // AssertionResult holds a pointer to a temporary DecomposedExpression,
- // which getExpandedExpression() calls to build the expression string.
- // Our section stack copy of the assertionResult will likely outlive the
- // temporary, so it must be expanded or discarded now to avoid calling
- // a destroyed object later.
- prepareExpandedExpression(const_cast<AssertionResult&>( assertionStats.assertionResult ) );
- SectionNode& sectionNode = *m_sectionStack.back();
- sectionNode.assertions.push_back(assertionStats);
- return true;
- }
- void sectionEnded(SectionStats const& sectionStats) override {
- assert(!m_sectionStack.empty());
- SectionNode& node = *m_sectionStack.back();
- node.stats = sectionStats;
- m_sectionStack.pop_back();
- }
- void testCaseEnded(TestCaseStats const& testCaseStats) override {
- auto node = std::make_shared<TestCaseNode>(testCaseStats);
- assert(m_sectionStack.size() == 0);
- node->children.push_back(m_rootSection);
- m_testCases.push_back(node);
- m_rootSection.reset();
-
- assert(m_deepestSection);
- m_deepestSection->stdOut = testCaseStats.stdOut;
- m_deepestSection->stdErr = testCaseStats.stdErr;
- }
- void testGroupEnded(TestGroupStats const& testGroupStats) override {
- auto node = std::make_shared<TestGroupNode>(testGroupStats);
- node->children.swap(m_testCases);
- m_testGroups.push_back(node);
- }
- void testRunEnded(TestRunStats const& testRunStats) override {
- auto node = std::make_shared<TestRunNode>(testRunStats);
- node->children.swap(m_testGroups);
- m_testRuns.push_back(node);
- testRunEndedCumulative();
- }
- virtual void testRunEndedCumulative() = 0;
-
- void skipTest(TestCaseInfo const&) override {}
-
- IConfigPtr m_config;
- std::ostream& stream;
- std::vector<AssertionStats> m_assertions;
- std::vector<std::vector<std::shared_ptr<SectionNode>>> m_sections;
- std::vector<std::shared_ptr<TestCaseNode>> m_testCases;
- std::vector<std::shared_ptr<TestGroupNode>> m_testGroups;
-
- std::vector<std::shared_ptr<TestRunNode>> m_testRuns;
-
- std::shared_ptr<SectionNode> m_rootSection;
- std::shared_ptr<SectionNode> m_deepestSection;
- std::vector<std::shared_ptr<SectionNode>> m_sectionStack;
- ReporterPreferences m_reporterPrefs;
- };
-
- template<char C>
- char const* getLineOfChars() {
- static char line[CATCH_CONFIG_CONSOLE_WIDTH] = {0};
- if( !*line ) {
- std::memset( line, C, CATCH_CONFIG_CONSOLE_WIDTH-1 );
- line[CATCH_CONFIG_CONSOLE_WIDTH-1] = 0;
- }
- return line;
- }
-
- struct TestEventListenerBase : StreamingReporterBase<TestEventListenerBase> {
- TestEventListenerBase( ReporterConfig const& _config );
-
- void assertionStarting(AssertionInfo const&) override;
- bool assertionEnded(AssertionStats const&) override;
- };
-
-} // end namespace Catch
-
-// end catch_reporter_bases.hpp
-// start catch_console_colour.h
-
-namespace Catch {
-
- struct Colour {
- enum Code {
- None = 0,
-
- White,
- Red,
- Green,
- Blue,
- Cyan,
- Yellow,
- Grey,
-
- Bright = 0x10,
-
- BrightRed = Bright | Red,
- BrightGreen = Bright | Green,
- LightGrey = Bright | Grey,
- BrightWhite = Bright | White,
-
- // By intention
- FileName = LightGrey,
- Warning = Yellow,
- ResultError = BrightRed,
- ResultSuccess = BrightGreen,
- ResultExpectedFailure = Warning,
-
- Error = BrightRed,
- Success = Green,
-
- OriginalExpression = Cyan,
- ReconstructedExpression = Yellow,
-
- SecondaryText = LightGrey,
- Headers = White
- };
-
- // Use constructed object for RAII guard
- Colour( Code _colourCode );
- Colour( Colour&& other ) noexcept;
- Colour& operator=( Colour&& other ) noexcept;
- ~Colour();
-
- // Use static method for one-shot changes
- static void use( Code _colourCode );
-
- private:
- bool m_moved = false;
- };
-
- std::ostream& operator << ( std::ostream& os, Colour const& );
-
-} // end namespace Catch
-
-// end catch_console_colour.h
-// start catch_reporter_registrars.hpp
-
-
-namespace Catch {
-
- template<typename T>
- class ReporterRegistrar {
-
- class ReporterFactory : public IReporterFactory {
-
- virtual IStreamingReporterPtr create( ReporterConfig const& config ) const override {
- return std::unique_ptr<T>( new T( config ) );
- }
-
- virtual std::string getDescription() const override {
- return T::getDescription();
- }
- };
-
- public:
-
- ReporterRegistrar( std::string const& name ) {
- getMutableRegistryHub().registerReporter( name, std::make_shared<ReporterFactory>() );
- }
- };
-
- template<typename T>
- class ListenerRegistrar {
-
- class ListenerFactory : public IReporterFactory {
-
- virtual IStreamingReporterPtr create( ReporterConfig const& config ) const override {
- return std::unique_ptr<T>( new T( config ) );
- }
- virtual std::string getDescription() const override {
- return std::string();
- }
- };
-
- public:
-
- ListenerRegistrar() {
- getMutableRegistryHub().registerListener( std::make_shared<ListenerFactory>() );
- }
- };
-}
-
-#if !defined(CATCH_CONFIG_DISABLE)
-
-#define CATCH_REGISTER_REPORTER( name, reporterType ) \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- namespace{ Catch::ReporterRegistrar<reporterType> catch_internal_RegistrarFor##reporterType( name ); } \
- CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS
-
-#define CATCH_REGISTER_LISTENER( listenerType ) \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \
- namespace{ Catch::ListenerRegistrar<listenerType> catch_internal_RegistrarFor##listenerType; } \
- CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS
-#else // CATCH_CONFIG_DISABLE
-
-#define CATCH_REGISTER_REPORTER(name, reporterType)
-#define CATCH_REGISTER_LISTENER(listenerType)
-
-#endif // CATCH_CONFIG_DISABLE
-
-// end catch_reporter_registrars.hpp
-// end catch_external_interfaces.h
-#endif
-
-#ifdef CATCH_IMPL
-// start catch_impl.hpp
-
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wweak-vtables"
-#endif
-
-// Keep these here for external reporters
-// start catch_test_case_tracker.h
-
-#include <string>
-#include <vector>
-#include <memory>
-
-namespace Catch {
-namespace TestCaseTracking {
-
- struct NameAndLocation {
- std::string name;
- SourceLineInfo location;
-
- NameAndLocation( std::string const& _name, SourceLineInfo const& _location );
- };
-
- struct ITracker;
-
- using ITrackerPtr = std::shared_ptr<ITracker>;
-
- struct ITracker {
- virtual ~ITracker();
-
- // static queries
- virtual NameAndLocation const& nameAndLocation() const = 0;
-
- // dynamic queries
- virtual bool isComplete() const = 0; // Successfully completed or failed
- virtual bool isSuccessfullyCompleted() const = 0;
- virtual bool isOpen() const = 0; // Started but not complete
- virtual bool hasChildren() const = 0;
-
- virtual ITracker& parent() = 0;
-
- // actions
- virtual void close() = 0; // Successfully complete
- virtual void fail() = 0;
- virtual void markAsNeedingAnotherRun() = 0;
-
- virtual void addChild( ITrackerPtr const& child ) = 0;
- virtual ITrackerPtr findChild( NameAndLocation const& nameAndLocation ) = 0;
- virtual void openChild() = 0;
-
- // Debug/ checking
- virtual bool isSectionTracker() const = 0;
- virtual bool isIndexTracker() const = 0;
- };
-
- class TrackerContext {
-
- enum RunState {
- NotStarted,
- Executing,
- CompletedCycle
- };
-
- ITrackerPtr m_rootTracker;
- ITracker* m_currentTracker = nullptr;
- RunState m_runState = NotStarted;
-
- public:
-
- static TrackerContext& instance();
-
- ITracker& startRun();
- void endRun();
-
- void startCycle();
- void completeCycle();
-
- bool completedCycle() const;
- ITracker& currentTracker();
- void setCurrentTracker( ITracker* tracker );
- };
-
- class TrackerBase : public ITracker {
- protected:
- enum CycleState {
- NotStarted,
- Executing,
- ExecutingChildren,
- NeedsAnotherRun,
- CompletedSuccessfully,
- Failed
- };
-
- class TrackerHasName {
- NameAndLocation m_nameAndLocation;
- public:
- TrackerHasName( NameAndLocation const& nameAndLocation );
- bool operator ()( ITrackerPtr const& tracker ) const;
- };
-
- using Children = std::vector<ITrackerPtr>;
- NameAndLocation m_nameAndLocation;
- TrackerContext& m_ctx;
- ITracker* m_parent;
- Children m_children;
- CycleState m_runState = NotStarted;
-
- public:
- TrackerBase( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent );
-
- NameAndLocation const& nameAndLocation() const override;
- bool isComplete() const override;
- bool isSuccessfullyCompleted() const override;
- bool isOpen() const override;
- bool hasChildren() const override;
-
- void addChild( ITrackerPtr const& child ) override;
-
- ITrackerPtr findChild( NameAndLocation const& nameAndLocation ) override;
- ITracker& parent() override;
-
- void openChild() override;
-
- bool isSectionTracker() const override;
- bool isIndexTracker() const override;
-
- void open();
-
- void close() override;
- void fail() override;
- void markAsNeedingAnotherRun() override;
-
- private:
- void moveToParent();
- void moveToThis();
- };
-
- class SectionTracker : public TrackerBase {
- std::vector<std::string> m_filters;
- public:
- SectionTracker( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent );
-
- bool isSectionTracker() const override;
-
- static SectionTracker& acquire( TrackerContext& ctx, NameAndLocation const& nameAndLocation );
-
- void tryOpen();
-
- void addInitialFilters( std::vector<std::string> const& filters );
- void addNextFilters( std::vector<std::string> const& filters );
- };
-
- class IndexTracker : public TrackerBase {
- int m_size;
- int m_index = -1;
- public:
- IndexTracker( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent, int size );
-
- bool isIndexTracker() const override;
- void close() override;
-
- static IndexTracker& acquire( TrackerContext& ctx, NameAndLocation const& nameAndLocation, int size );
-
- int index() const;
-
- void moveNext();
- };
-
-} // namespace TestCaseTracking
-
-using TestCaseTracking::ITracker;
-using TestCaseTracking::TrackerContext;
-using TestCaseTracking::SectionTracker;
-using TestCaseTracking::IndexTracker;
-
-} // namespace Catch
-
-// end catch_test_case_tracker.h
-
-// start catch_leak_detector.h
-
-namespace Catch {
-
- struct LeakDetector {
- LeakDetector();
- };
-
-}
-// end catch_leak_detector.h
-// Cpp files will be included in the single-header file here
-// start catch_approx.cpp
-
-#include <cmath>
-#include <limits>
-
-namespace {
-
-// Performs equivalent check of std::fabs(lhs - rhs) <= margin
-// But without the subtraction to allow for INFINITY in comparison
-bool marginComparison(double lhs, double rhs, double margin) {
- return (lhs + margin >= rhs) && (rhs + margin >= lhs);
-}
-
-}
-
-namespace Catch {
-namespace Detail {
-
- Approx::Approx ( double value )
- : m_epsilon( std::numeric_limits<float>::epsilon()*100 ),
- m_margin( 0.0 ),
- m_scale( 0.0 ),
- m_value( value )
- {}
-
- Approx Approx::custom() {
- return Approx( 0 );
- }
-
- std::string Approx::toString() const {
- std::ostringstream oss;
- oss << "Approx( " << ::Catch::Detail::stringify( m_value ) << " )";
- return oss.str();
- }
-
- bool Approx::equalityComparisonImpl(const double other) const {
- // First try with fixed margin, then compute margin based on epsilon, scale and Approx's value
- // Thanks to Richard Harris for his help refining the scaled margin value
- return marginComparison(m_value, other, m_margin) || marginComparison(m_value, other, m_epsilon * (m_scale + std::fabs(m_value)));
- }
-
-} // end namespace Detail
-
-std::string StringMaker<Catch::Detail::Approx>::convert(Catch::Detail::Approx const& value) {
- return value.toString();
-}
-
-} // end namespace Catch
-// end catch_approx.cpp
-// start catch_assertionhandler.cpp
-
-// start catch_context.h
-
-#include <memory>
-
-namespace Catch {
-
- struct IResultCapture;
- struct IRunner;
- struct IConfig;
-
- using IConfigPtr = std::shared_ptr<IConfig const>;
-
- struct IContext
- {
- virtual ~IContext();
-
- virtual IResultCapture* getResultCapture() = 0;
- virtual IRunner* getRunner() = 0;
- virtual IConfigPtr getConfig() const = 0;
- };
-
- struct IMutableContext : IContext
- {
- virtual ~IMutableContext();
- virtual void setResultCapture( IResultCapture* resultCapture ) = 0;
- virtual void setRunner( IRunner* runner ) = 0;
- virtual void setConfig( IConfigPtr const& config ) = 0;
- };
-
- IContext& getCurrentContext();
- IMutableContext& getCurrentMutableContext();
- void cleanUpContext();
-}
-
-// end catch_context.h
-#include <cassert>
-
-namespace Catch {
-
- auto operator <<( std::ostream& os, ITransientExpression const& expr ) -> std::ostream& {
- expr.streamReconstructedExpression( os );
- return os;
- }
-
- LazyExpression::LazyExpression( bool isNegated )
- : m_isNegated( isNegated )
- {}
-
- LazyExpression::LazyExpression( LazyExpression const& other ) : m_isNegated( other.m_isNegated ) {}
-
- LazyExpression::operator bool() const {
- return m_transientExpression != nullptr;
- }
-
- auto operator << ( std::ostream& os, LazyExpression const& lazyExpr ) -> std::ostream& {
- if( lazyExpr.m_isNegated )
- os << "!";
-
- if( lazyExpr ) {
- if( lazyExpr.m_isNegated && lazyExpr.m_transientExpression->isBinaryExpression() )
- os << "(" << *lazyExpr.m_transientExpression << ")";
- else
- os << *lazyExpr.m_transientExpression;
- }
- else {
- os << "{** error - unchecked empty expression requested **}";
- }
- return os;
- }
-
- AssertionHandler::AssertionHandler
- ( StringRef macroName,
- SourceLineInfo const& lineInfo,
- StringRef capturedExpression,
- ResultDisposition::Flags resultDisposition )
- : m_assertionInfo{ macroName, lineInfo, capturedExpression, resultDisposition }
- {
- getCurrentContext().getResultCapture()->assertionStarting( m_assertionInfo );
- }
- AssertionHandler::~AssertionHandler() {
- if ( m_inExceptionGuard ) {
- handle( ResultWas::ThrewException, "Exception translation was disabled by CATCH_CONFIG_FAST_COMPILE" );
- getCurrentContext().getResultCapture()->exceptionEarlyReported();
- }
- }
-
- void AssertionHandler::handle( ITransientExpression const& expr ) {
-
- bool negated = isFalseTest( m_assertionInfo.resultDisposition );
- bool result = expr.getResult() != negated;
-
- handle( result ? ResultWas::Ok : ResultWas::ExpressionFailed, &expr, negated );
- }
- void AssertionHandler::handle( ResultWas::OfType resultType ) {
- handle( resultType, nullptr, false );
- }
- void AssertionHandler::handle( ResultWas::OfType resultType, StringRef const& message ) {
- AssertionResultData data( resultType, LazyExpression( false ) );
- data.message = message;
- handle( data, nullptr );
- }
- void AssertionHandler::handle( ResultWas::OfType resultType, ITransientExpression const* expr, bool negated ) {
- AssertionResultData data( resultType, LazyExpression( negated ) );
- handle( data, expr );
- }
- void AssertionHandler::handle( AssertionResultData const& resultData, ITransientExpression const* expr ) {
-
- getResultCapture().assertionRun();
-
- AssertionResult assertionResult{ m_assertionInfo, resultData };
- assertionResult.m_resultData.lazyExpression.m_transientExpression = expr;
-
- getResultCapture().assertionEnded( assertionResult );
-
- if( !assertionResult.isOk() ) {
- m_shouldDebugBreak = getCurrentContext().getConfig()->shouldDebugBreak();
- m_shouldThrow =
- getCurrentContext().getRunner()->aborting() ||
- (m_assertionInfo.resultDisposition & ResultDisposition::Normal);
- }
- }
-
- auto AssertionHandler::allowThrows() const -> bool {
- return getCurrentContext().getConfig()->allowThrows();
- }
-
- auto AssertionHandler::shouldDebugBreak() const -> bool {
- return m_shouldDebugBreak;
- }
- void AssertionHandler::reactWithDebugBreak() const {
- if (m_shouldDebugBreak) {
- ///////////////////////////////////////////////////////////////////
- // To inspect the state during test, you need to go one level up the callstack
- // To go back to the test and change execution, jump over the reactWithoutDebugBreak() call
- ///////////////////////////////////////////////////////////////////
- CATCH_BREAK_INTO_DEBUGGER();
- }
- reactWithoutDebugBreak();
- }
- void AssertionHandler::reactWithoutDebugBreak() const {
- if( m_shouldThrow )
- throw Catch::TestFailureException();
- }
-
- void AssertionHandler::useActiveException() {
- handle( ResultWas::ThrewException, Catch::translateActiveException() );
- }
-
- void AssertionHandler::setExceptionGuard() {
- assert( m_inExceptionGuard == false );
- m_inExceptionGuard = true;
- }
- void AssertionHandler::unsetExceptionGuard() {
- assert( m_inExceptionGuard == true );
- m_inExceptionGuard = false;
- }
-
- // This is the overload that takes a string and infers the Equals matcher from it
- // The more general overload, that takes any string matcher, is in catch_capture_matchers.cpp
- void handleExceptionMatchExpr( AssertionHandler& handler, std::string const& str, StringRef matcherString ) {
- handleExceptionMatchExpr( handler, Matchers::Equals( str ), matcherString );
- }
-
-} // namespace Catch
-// end catch_assertionhandler.cpp
-// start catch_assertionresult.cpp
-
-namespace Catch {
- AssertionResultData::AssertionResultData(ResultWas::OfType _resultType, LazyExpression const & _lazyExpression):
- lazyExpression(_lazyExpression),
- resultType(_resultType) {}
-
- std::string AssertionResultData::reconstructExpression() const {
-
- if( reconstructedExpression.empty() ) {
- if( lazyExpression ) {
- // !TBD Use stringstream for now, but rework above to pass stream in
- std::ostringstream oss;
- oss << lazyExpression;
- reconstructedExpression = oss.str();
- }
- }
- return reconstructedExpression;
- }
-
- AssertionResult::AssertionResult( AssertionInfo const& info, AssertionResultData const& data )
- : m_info( info ),
- m_resultData( data )
- {}
-
- // Result was a success
- bool AssertionResult::succeeded() const {
- return Catch::isOk( m_resultData.resultType );
- }
-
- // Result was a success, or failure is suppressed
- bool AssertionResult::isOk() const {
- return Catch::isOk( m_resultData.resultType ) || shouldSuppressFailure( m_info.resultDisposition );
- }
-
- ResultWas::OfType AssertionResult::getResultType() const {
- return m_resultData.resultType;
- }
-
- bool AssertionResult::hasExpression() const {
- return m_info.capturedExpression[0] != 0;
- }
-
- bool AssertionResult::hasMessage() const {
- return !m_resultData.message.empty();
- }
-
- std::string AssertionResult::getExpression() const {
- if( isFalseTest( m_info.resultDisposition ) )
- return "!(" + std::string(m_info.capturedExpression) + ")";
- else
- return m_info.capturedExpression;
- }
-
- std::string AssertionResult::getExpressionInMacro() const {
- std::string expr;
- if( m_info.macroName[0] == 0 )
- expr = m_info.capturedExpression;
- else {
- expr.reserve( m_info.macroName.size() + m_info.capturedExpression.size() + 4 );
- expr += m_info.macroName;
- expr += "( ";
- expr += m_info.capturedExpression;
- expr += " )";
- }
- return expr;
- }
-
- bool AssertionResult::hasExpandedExpression() const {
- return hasExpression() && getExpandedExpression() != getExpression();
- }
-
- std::string AssertionResult::getExpandedExpression() const {
- std::string expr = m_resultData.reconstructExpression();
- return expr.empty()
- ? getExpression()
- : expr;
- }
-
- std::string AssertionResult::getMessage() const {
- return m_resultData.message;
- }
- SourceLineInfo AssertionResult::getSourceInfo() const {
- return m_info.lineInfo;
- }
-
- std::string AssertionResult::getTestMacroName() const {
- return m_info.macroName;
- }
-
-} // end namespace Catch
-// end catch_assertionresult.cpp
-// start catch_benchmark.cpp
-
-namespace Catch {
-
- auto BenchmarkLooper::getResolution() -> uint64_t {
- return getEstimatedClockResolution() * getCurrentContext().getConfig()->benchmarkResolutionMultiple();
- }
-
- void BenchmarkLooper::reportStart() {
- getResultCapture().benchmarkStarting( { m_name } );
- }
- auto BenchmarkLooper::needsMoreIterations() -> bool {
- auto elapsed = m_timer.getElapsedNanoseconds();
-
- // Exponentially increasing iterations until we're confident in our timer resolution
- if( elapsed < m_resolution ) {
- m_iterationsToRun *= 10;
- return true;
- }
-
- getResultCapture().benchmarkEnded( { { m_name }, m_count, elapsed } );
- return false;
- }
-
-} // end namespace Catch
-// end catch_benchmark.cpp
-// start catch_capture_matchers.cpp
-
-namespace Catch {
-
- using StringMatcher = Matchers::Impl::MatcherBase<std::string>;
-
- // This is the general overload that takes a any string matcher
- // There is another overload, in catch_assertinhandler.h/.cpp, that only takes a string and infers
- // the Equals matcher (so the header does not mention matchers)
- void handleExceptionMatchExpr( AssertionHandler& handler, StringMatcher const& matcher, StringRef matcherString ) {
- std::string exceptionMessage = Catch::translateActiveException();
- MatchExpr<std::string, StringMatcher const&> expr( exceptionMessage, matcher, matcherString );
- handler.handle( expr );
- }
-
-} // namespace Catch
-// end catch_capture_matchers.cpp
-// start catch_commandline.cpp
-
-// start catch_commandline.h
-
-// start catch_clara.h
-
-// Use Catch's value for console width (store Clara's off to the side, if present)
-#ifdef CLARA_CONFIG_CONSOLE_WIDTH
-#define CATCH_TEMP_CLARA_CONFIG_CONSOLE_WIDTH CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH
-#undef CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH
-#endif
-#define CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH CATCH_CONFIG_CONSOLE_WIDTH-1
-
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wweak-vtables"
-#pragma clang diagnostic ignored "-Wexit-time-destructors"
-#pragma clang diagnostic ignored "-Wshadow"
-#endif
-
-// start clara.hpp
-// v1.0-develop.2
-// See https://github.com/philsquared/Clara
-
-
-#ifndef CATCH_CLARA_CONFIG_CONSOLE_WIDTH
-#define CATCH_CLARA_CONFIG_CONSOLE_WIDTH 80
-#endif
-
-#ifndef CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH
-#define CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH CATCH_CLARA_CONFIG_CONSOLE_WIDTH
-#endif
-
-// ----------- #included from clara_textflow.hpp -----------
-
-// TextFlowCpp
-//
-// A single-header library for wrapping and laying out basic text, by Phil Nash
-//
-// This work is licensed under the BSD 2-Clause license.
-// See the accompanying LICENSE file, or the one at https://opensource.org/licenses/BSD-2-Clause
-//
-// This project is hosted at https://github.com/philsquared/textflowcpp
-
-
-#include <cassert>
-#include <ostream>
-#include <sstream>
-#include <vector>
-
-#ifndef CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH
-#define CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH 80
-#endif
-
-namespace Catch { namespace clara { namespace TextFlow {
-
- inline auto isWhitespace( char c ) -> bool {
- static std::string chars = " \t\n\r";
- return chars.find( c ) != std::string::npos;
- }
- inline auto isBreakableBefore( char c ) -> bool {
- static std::string chars = "[({<|";
- return chars.find( c ) != std::string::npos;
- }
- inline auto isBreakableAfter( char c ) -> bool {
- static std::string chars = "])}>.,:;*+-=&/\\";
- return chars.find( c ) != std::string::npos;
- }
-
- class Columns;
-
- class Column {
- std::vector<std::string> m_strings;
- size_t m_width = CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH;
- size_t m_indent = 0;
- size_t m_initialIndent = std::string::npos;
-
- public:
- class iterator {
- friend Column;
-
- Column const& m_column;
- size_t m_stringIndex = 0;
- size_t m_pos = 0;
-
- size_t m_len = 0;
- size_t m_end = 0;
- bool m_suffix = false;
-
- iterator( Column const& column, size_t stringIndex )
- : m_column( column ),
- m_stringIndex( stringIndex )
- {}
-
- auto line() const -> std::string const& { return m_column.m_strings[m_stringIndex]; }
-
- auto isBoundary( size_t at ) const -> bool {
- assert( at > 0 );
- assert( at <= line().size() );
-
- return at == line().size() ||
- ( isWhitespace( line()[at] ) && !isWhitespace( line()[at-1] ) ) ||
- isBreakableBefore( line()[at] ) ||
- isBreakableAfter( line()[at-1] );
- }
-
- void calcLength() {
- assert( m_stringIndex < m_column.m_strings.size() );
-
- m_suffix = false;
- auto width = m_column.m_width-indent();
- m_end = m_pos;
- while( m_end < line().size() && line()[m_end] != '\n' )
- ++m_end;
-
- if( m_end < m_pos + width ) {
- m_len = m_end - m_pos;
- }
- else {
- size_t len = width;
- while (len > 0 && !isBoundary(m_pos + len))
- --len;
- while (len > 0 && isWhitespace( line()[m_pos + len - 1] ))
- --len;
-
- if (len > 0) {
- m_len = len;
- } else {
- m_suffix = true;
- m_len = width - 1;
- }
- }
- }
-
- auto indent() const -> size_t {
- auto initial = m_pos == 0 && m_stringIndex == 0 ? m_column.m_initialIndent : std::string::npos;
- return initial == std::string::npos ? m_column.m_indent : initial;
- }
-
- auto addIndentAndSuffix(std::string const &plain) const -> std::string {
- return std::string( indent(), ' ' ) + (m_suffix ? plain + "-" : plain);
- }
-
- public:
- explicit iterator( Column const& column ) : m_column( column ) {
- assert( m_column.m_width > m_column.m_indent );
- assert( m_column.m_initialIndent == std::string::npos || m_column.m_width > m_column.m_initialIndent );
- calcLength();
- if( m_len == 0 )
- m_stringIndex++; // Empty string
- }
-
- auto operator *() const -> std::string {
- assert( m_stringIndex < m_column.m_strings.size() );
- assert( m_pos <= m_end );
- if( m_pos + m_column.m_width < m_end )
- return addIndentAndSuffix(line().substr(m_pos, m_len));
- else
- return addIndentAndSuffix(line().substr(m_pos, m_end - m_pos));
- }
-
- auto operator ++() -> iterator& {
- m_pos += m_len;
- if( m_pos < line().size() && line()[m_pos] == '\n' )
- m_pos += 1;
- else
- while( m_pos < line().size() && isWhitespace( line()[m_pos] ) )
- ++m_pos;
-
- if( m_pos == line().size() ) {
- m_pos = 0;
- ++m_stringIndex;
- }
- if( m_stringIndex < m_column.m_strings.size() )
- calcLength();
- return *this;
- }
- auto operator ++(int) -> iterator {
- iterator prev( *this );
- operator++();
- return prev;
- }
-
- auto operator ==( iterator const& other ) const -> bool {
- return
- m_pos == other.m_pos &&
- m_stringIndex == other.m_stringIndex &&
- &m_column == &other.m_column;
- }
- auto operator !=( iterator const& other ) const -> bool {
- return !operator==( other );
- }
- };
- using const_iterator = iterator;
-
- explicit Column( std::string const& text ) { m_strings.push_back( text ); }
-
- auto width( size_t newWidth ) -> Column& {
- assert( newWidth > 0 );
- m_width = newWidth;
- return *this;
- }
- auto indent( size_t newIndent ) -> Column& {
- m_indent = newIndent;
- return *this;
- }
- auto initialIndent( size_t newIndent ) -> Column& {
- m_initialIndent = newIndent;
- return *this;
- }
-
- auto width() const -> size_t { return m_width; }
- auto begin() const -> iterator { return iterator( *this ); }
- auto end() const -> iterator { return { *this, m_strings.size() }; }
-
- inline friend std::ostream& operator << ( std::ostream& os, Column const& col ) {
- bool first = true;
- for( auto line : col ) {
- if( first )
- first = false;
- else
- os << "\n";
- os << line;
- }
- return os;
- }
-
- auto operator + ( Column const& other ) -> Columns;
-
- auto toString() const -> std::string {
- std::ostringstream oss;
- oss << *this;
- return oss.str();
- }
- };
-
- class Spacer : public Column {
-
- public:
- explicit Spacer( size_t spaceWidth ) : Column( "" ) {
- width( spaceWidth );
- }
- };
-
- class Columns {
- std::vector<Column> m_columns;
-
- public:
-
- class iterator {
- friend Columns;
- struct EndTag {};
-
- std::vector<Column> const& m_columns;
- std::vector<Column::iterator> m_iterators;
- size_t m_activeIterators;
-
- iterator( Columns const& columns, EndTag )
- : m_columns( columns.m_columns ),
- m_activeIterators( 0 )
- {
- m_iterators.reserve( m_columns.size() );
-
- for( auto const& col : m_columns )
- m_iterators.push_back( col.end() );
- }
-
- public:
- explicit iterator( Columns const& columns )
- : m_columns( columns.m_columns ),
- m_activeIterators( m_columns.size() )
- {
- m_iterators.reserve( m_columns.size() );
-
- for( auto const& col : m_columns )
- m_iterators.push_back( col.begin() );
- }
-
- auto operator ==( iterator const& other ) const -> bool {
- return m_iterators == other.m_iterators;
- }
- auto operator !=( iterator const& other ) const -> bool {
- return m_iterators != other.m_iterators;
- }
- auto operator *() const -> std::string {
- std::string row, padding;
-
- for( size_t i = 0; i < m_columns.size(); ++i ) {
- auto width = m_columns[i].width();
- if( m_iterators[i] != m_columns[i].end() ) {
- std::string col = *m_iterators[i];
- row += padding + col;
- if( col.size() < width )
- padding = std::string( width - col.size(), ' ' );
- else
- padding = "";
- }
- else {
- padding += std::string( width, ' ' );
- }
- }
- return row;
- }
- auto operator ++() -> iterator& {
- for( size_t i = 0; i < m_columns.size(); ++i ) {
- if (m_iterators[i] != m_columns[i].end())
- ++m_iterators[i];
- }
- return *this;
- }
- auto operator ++(int) -> iterator {
- iterator prev( *this );
- operator++();
- return prev;
- }
- };
- using const_iterator = iterator;
-
- auto begin() const -> iterator { return iterator( *this ); }
- auto end() const -> iterator { return { *this, iterator::EndTag() }; }
-
- auto operator += ( Column const& col ) -> Columns& {
- m_columns.push_back( col );
- return *this;
- }
- auto operator + ( Column const& col ) -> Columns {
- Columns combined = *this;
- combined += col;
- return combined;
- }
-
- inline friend std::ostream& operator << ( std::ostream& os, Columns const& cols ) {
-
- bool first = true;
- for( auto line : cols ) {
- if( first )
- first = false;
- else
- os << "\n";
- os << line;
- }
- return os;
- }
-
- auto toString() const -> std::string {
- std::ostringstream oss;
- oss << *this;
- return oss.str();
- }
- };
-
- inline auto Column::operator + ( Column const& other ) -> Columns {
- Columns cols;
- cols += *this;
- cols += other;
- return cols;
- }
-}}} // namespace Catch::clara::TextFlow
-
-// ----------- end of #include from clara_textflow.hpp -----------
-// ........... back in clara.hpp
-
-#include <memory>
-#include <set>
-#include <algorithm>
-
-#if !defined(CATCH_PLATFORM_WINDOWS) && ( defined(WIN32) || defined(__WIN32__) || defined(_WIN32) || defined(_MSC_VER) )
-#define CATCH_PLATFORM_WINDOWS
-#endif
-
-namespace Catch { namespace clara {
-namespace detail {
-
- // Traits for extracting arg and return type of lambdas (for single argument lambdas)
- template<typename L>
- struct UnaryLambdaTraits : UnaryLambdaTraits<decltype( &L::operator() )> {};
-
- template<typename ClassT, typename ReturnT, typename... Args>
- struct UnaryLambdaTraits<ReturnT( ClassT::* )( Args... ) const> {
- static const bool isValid = false;
- };
-
- template<typename ClassT, typename ReturnT, typename ArgT>
- struct UnaryLambdaTraits<ReturnT( ClassT::* )( ArgT ) const> {
- static const bool isValid = true;
- using ArgType = typename std::remove_const<typename std::remove_reference<ArgT>::type>::type;;
- using ReturnType = ReturnT;
- };
-
- class TokenStream;
-
- // Transport for raw args (copied from main args, or supplied via init list for testing)
- class Args {
- friend TokenStream;
- std::string m_exeName;
- std::vector<std::string> m_args;
-
- public:
- Args( int argc, char *argv[] ) {
- m_exeName = argv[0];
- for( int i = 1; i < argc; ++i )
- m_args.push_back( argv[i] );
- }
-
- Args( std::initializer_list<std::string> args )
- : m_exeName( *args.begin() ),
- m_args( args.begin()+1, args.end() )
- {}
-
- auto exeName() const -> std::string {
- return m_exeName;
- }
- };
-
- // Wraps a token coming from a token stream. These may not directly correspond to strings as a single string
- // may encode an option + its argument if the : or = form is used
- enum class TokenType {
- Option, Argument
- };
- struct Token {
- TokenType type;
- std::string token;
- };
-
- inline auto isOptPrefix( char c ) -> bool {
- return c == '-'
-#ifdef CATCH_PLATFORM_WINDOWS
- || c == '/'
-#endif
- ;
- }
-
- // Abstracts iterators into args as a stream of tokens, with option arguments uniformly handled
- class TokenStream {
- using Iterator = std::vector<std::string>::const_iterator;
- Iterator it;
- Iterator itEnd;
- std::vector<Token> m_tokenBuffer;
-
- void loadBuffer() {
- m_tokenBuffer.resize( 0 );
-
- // Skip any empty strings
- while( it != itEnd && it->empty() )
- ++it;
-
- if( it != itEnd ) {
- auto const &next = *it;
- if( isOptPrefix( next[0] ) ) {
- auto delimiterPos = next.find_first_of( " :=" );
- if( delimiterPos != std::string::npos ) {
- m_tokenBuffer.push_back( { TokenType::Option, next.substr( 0, delimiterPos ) } );
- m_tokenBuffer.push_back( { TokenType::Argument, next.substr( delimiterPos + 1 ) } );
- } else {
- if( next[1] != '-' && next.size() > 2 ) {
- std::string opt = "- ";
- for( size_t i = 1; i < next.size(); ++i ) {
- opt[1] = next[i];
- m_tokenBuffer.push_back( { TokenType::Option, opt } );
- }
- } else {
- m_tokenBuffer.push_back( { TokenType::Option, next } );
- }
- }
- } else {
- m_tokenBuffer.push_back( { TokenType::Argument, next } );
- }
- }
- }
-
- public:
- explicit TokenStream( Args const &args ) : TokenStream( args.m_args.begin(), args.m_args.end() ) {}
-
- TokenStream( Iterator it, Iterator itEnd ) : it( it ), itEnd( itEnd ) {
- loadBuffer();
- }
-
- explicit operator bool() const {
- return !m_tokenBuffer.empty() || it != itEnd;
- }
-
- auto count() const -> size_t { return m_tokenBuffer.size() + (itEnd - it); }
-
- auto operator*() const -> Token {
- assert( !m_tokenBuffer.empty() );
- return m_tokenBuffer.front();
- }
-
- auto operator->() const -> Token const * {
- assert( !m_tokenBuffer.empty() );
- return &m_tokenBuffer.front();
- }
-
- auto operator++() -> TokenStream & {
- if( m_tokenBuffer.size() >= 2 ) {
- m_tokenBuffer.erase( m_tokenBuffer.begin() );
- } else {
- if( it != itEnd )
- ++it;
- loadBuffer();
- }
- return *this;
- }
- };
-
- class ResultBase {
- public:
- enum Type {
- Ok, LogicError, RuntimeError
- };
-
- protected:
- ResultBase( Type type ) : m_type( type ) {}
- virtual ~ResultBase() = default;
-
- virtual void enforceOk() const = 0;
-
- Type m_type;
- };
-
- template<typename T>
- class ResultValueBase : public ResultBase {
- public:
- auto value() const -> T const & {
- enforceOk();
- return m_value;
- }
-
- protected:
- ResultValueBase( Type type ) : ResultBase( type ) {}
-
- ResultValueBase( ResultValueBase const &other ) : ResultBase( other ) {
- if( m_type == ResultBase::Ok )
- new( &m_value ) T( other.m_value );
- }
-
- ResultValueBase( Type, T const &value ) : ResultBase( Ok ) {
- new( &m_value ) T( value );
- }
-
- auto operator=( ResultValueBase const &other ) -> ResultValueBase & {
- if( m_type == ResultBase::Ok )
- m_value.~T();
- ResultBase::operator=(other);
- if( m_type == ResultBase::Ok )
- new( &m_value ) T( other.m_value );
- return *this;
- }
-
- ~ResultValueBase() {
- if( m_type == Ok )
- m_value.~T();
- }
-
- union {
- T m_value;
- };
- };
-
- template<>
- class ResultValueBase<void> : public ResultBase {
- protected:
- using ResultBase::ResultBase;
- };
-
- template<typename T = void>
- class BasicResult : public ResultValueBase<T> {
- public:
- template<typename U>
- explicit BasicResult( BasicResult<U> const &other )
- : ResultValueBase<T>( other.type() ),
- m_errorMessage( other.errorMessage() )
- {
- assert( type() != ResultBase::Ok );
- }
-
- template<typename U>
- static auto ok( U const &value ) -> BasicResult { return { ResultBase::Ok, value }; }
- static auto ok() -> BasicResult { return { ResultBase::Ok }; }
- static auto logicError( std::string const &message ) -> BasicResult { return { ResultBase::LogicError, message }; }
- static auto runtimeError( std::string const &message ) -> BasicResult { return { ResultBase::RuntimeError, message }; }
-
- explicit operator bool() const { return m_type == ResultBase::Ok; }
- auto type() const -> ResultBase::Type { return m_type; }
- auto errorMessage() const -> std::string { return m_errorMessage; }
-
- protected:
- virtual void enforceOk() const {
- // !TBD: If no exceptions, std::terminate here or something
- switch( m_type ) {
- case ResultBase::LogicError:
- throw std::logic_error( m_errorMessage );
- case ResultBase::RuntimeError:
- throw std::runtime_error( m_errorMessage );
- case ResultBase::Ok:
- break;
- }
- }
-
- std::string m_errorMessage; // Only populated if resultType is an error
-
- BasicResult( ResultBase::Type type, std::string const &message )
- : ResultValueBase<T>(type),
- m_errorMessage(message)
- {
- assert( m_type != ResultBase::Ok );
- }
-
- using ResultValueBase<T>::ResultValueBase;
- using ResultBase::m_type;
- };
-
- enum class ParseResultType {
- Matched, NoMatch, ShortCircuitAll, ShortCircuitSame
- };
-
- class ParseState {
- public:
-
- ParseState( ParseResultType type, TokenStream const &remainingTokens )
- : m_type(type),
- m_remainingTokens( remainingTokens )
- {}
-
- auto type() const -> ParseResultType { return m_type; }
- auto remainingTokens() const -> TokenStream { return m_remainingTokens; }
-
- private:
- ParseResultType m_type;
- TokenStream m_remainingTokens;
- };
-
- using Result = BasicResult<void>;
- using ParserResult = BasicResult<ParseResultType>;
- using InternalParseResult = BasicResult<ParseState>;
-
- struct HelpColumns {
- std::string left;
- std::string right;
- };
-
- template<typename T>
- inline auto convertInto( std::string const &source, T& target ) -> ParserResult {
- std::stringstream ss;
- ss << source;
- ss >> target;
- if( ss.fail() )
- return ParserResult::runtimeError( "Unable to convert '" + source + "' to destination type" );
- else
- return ParserResult::ok( ParseResultType::Matched );
- }
- inline auto convertInto( std::string const &source, std::string& target ) -> ParserResult {
- target = source;
- return ParserResult::ok( ParseResultType::Matched );
- }
- inline auto convertInto( std::string const &source, bool &target ) -> ParserResult {
- std::string srcLC = source;
- std::transform( srcLC.begin(), srcLC.end(), srcLC.begin(), []( char c ) { return static_cast<char>( ::tolower(c) ); } );
- if (srcLC == "y" || srcLC == "1" || srcLC == "true" || srcLC == "yes" || srcLC == "on")
- target = true;
- else if (srcLC == "n" || srcLC == "0" || srcLC == "false" || srcLC == "no" || srcLC == "off")
- target = false;
- else
- return ParserResult::runtimeError( "Expected a boolean value but did not recognise: '" + source + "'" );
- return ParserResult::ok( ParseResultType::Matched );
- }
-
- struct BoundRefBase {
- BoundRefBase() = default;
- BoundRefBase( BoundRefBase const & ) = delete;
- BoundRefBase( BoundRefBase && ) = delete;
- BoundRefBase &operator=( BoundRefBase const & ) = delete;
- BoundRefBase &operator=( BoundRefBase && ) = delete;
-
- virtual ~BoundRefBase() = default;
-
- virtual auto isFlag() const -> bool = 0;
- virtual auto isContainer() const -> bool { return false; }
- virtual auto setValue( std::string const &arg ) -> ParserResult = 0;
- virtual auto setFlag( bool flag ) -> ParserResult = 0;
- };
-
- struct BoundValueRefBase : BoundRefBase {
- auto isFlag() const -> bool override { return false; }
-
- auto setFlag( bool ) -> ParserResult override {
- return ParserResult::logicError( "Flags can only be set on boolean fields" );
- }
- };
-
- struct BoundFlagRefBase : BoundRefBase {
- auto isFlag() const -> bool override { return true; }
-
- auto setValue( std::string const &arg ) -> ParserResult override {
- bool flag;
- auto result = convertInto( arg, flag );
- if( result )
- setFlag( flag );
- return result;
- }
- };
-
- template<typename T>
- struct BoundRef : BoundValueRefBase {
- T &m_ref;
-
- explicit BoundRef( T &ref ) : m_ref( ref ) {}
-
- auto setValue( std::string const &arg ) -> ParserResult override {
- return convertInto( arg, m_ref );
- }
- };
-
- template<typename T>
- struct BoundRef<std::vector<T>> : BoundValueRefBase {
- std::vector<T> &m_ref;
-
- explicit BoundRef( std::vector<T> &ref ) : m_ref( ref ) {}
-
- auto isContainer() const -> bool override { return true; }
-
- auto setValue( std::string const &arg ) -> ParserResult override {
- T temp;
- auto result = convertInto( arg, temp );
- if( result )
- m_ref.push_back( temp );
- return result;
- }
- };
-
- struct BoundFlagRef : BoundFlagRefBase {
- bool &m_ref;
-
- explicit BoundFlagRef( bool &ref ) : m_ref( ref ) {}
-
- auto setFlag( bool flag ) -> ParserResult override {
- m_ref = flag;
- return ParserResult::ok( ParseResultType::Matched );
- }
- };
-
- template<typename ReturnType>
- struct LambdaInvoker {
- static_assert( std::is_same<ReturnType, ParserResult>::value, "Lambda must return void or clara::ParserResult" );
-
- template<typename L, typename ArgType>
- static auto invoke( L const &lambda, ArgType const &arg ) -> ParserResult {
- return lambda( arg );
- }
- };
-
- template<>
- struct LambdaInvoker<void> {
- template<typename L, typename ArgType>
- static auto invoke( L const &lambda, ArgType const &arg ) -> ParserResult {
- lambda( arg );
- return ParserResult::ok( ParseResultType::Matched );
- }
- };
-
- template<typename ArgType, typename L>
- inline auto invokeLambda( L const &lambda, std::string const &arg ) -> ParserResult {
- ArgType temp;
- auto result = convertInto( arg, temp );
- return !result
- ? result
- : LambdaInvoker<typename UnaryLambdaTraits<L>::ReturnType>::invoke( lambda, temp );
- };
-
- template<typename L>
- struct BoundLambda : BoundValueRefBase {
- L m_lambda;
-
- static_assert( UnaryLambdaTraits<L>::isValid, "Supplied lambda must take exactly one argument" );
- explicit BoundLambda( L const &lambda ) : m_lambda( lambda ) {}
-
- auto setValue( std::string const &arg ) -> ParserResult override {
- return invokeLambda<typename UnaryLambdaTraits<L>::ArgType>( m_lambda, arg );
- }
- };
-
- template<typename L>
- struct BoundFlagLambda : BoundFlagRefBase {
- L m_lambda;
-
- static_assert( UnaryLambdaTraits<L>::isValid, "Supplied lambda must take exactly one argument" );
- static_assert( std::is_same<typename UnaryLambdaTraits<L>::ArgType, bool>::value, "flags must be boolean" );
-
- explicit BoundFlagLambda( L const &lambda ) : m_lambda( lambda ) {}
-
- auto setFlag( bool flag ) -> ParserResult override {
- return LambdaInvoker<typename UnaryLambdaTraits<L>::ReturnType>::invoke( m_lambda, flag );
- }
- };
-
- enum class Optionality { Optional, Required };
-
- struct Parser;
-
- class ParserBase {
- public:
- virtual ~ParserBase() = default;
- virtual auto validate() const -> Result { return Result::ok(); }
- virtual auto parse( std::string const& exeName, TokenStream const &tokens) const -> InternalParseResult = 0;
- virtual auto cardinality() const -> size_t { return 1; }
-
- auto parse( Args const &args ) const -> InternalParseResult {
- return parse( args.exeName(), TokenStream( args ) );
- }
- };
-
- template<typename DerivedT>
- class ComposableParserImpl : public ParserBase {
- public:
- template<typename T>
- auto operator|( T const &other ) const -> Parser;
- };
-
- // Common code and state for Args and Opts
- template<typename DerivedT>
- class ParserRefImpl : public ComposableParserImpl<DerivedT> {
- protected:
- Optionality m_optionality = Optionality::Optional;
- std::shared_ptr<BoundRefBase> m_ref;
- std::string m_hint;
- std::string m_description;
-
- explicit ParserRefImpl( std::shared_ptr<BoundRefBase> const &ref ) : m_ref( ref ) {}
-
- public:
- template<typename T>
- ParserRefImpl( T &ref, std::string const &hint )
- : m_ref( std::make_shared<BoundRef<T>>( ref ) ),
- m_hint( hint )
- {}
-
- template<typename LambdaT>
- ParserRefImpl( LambdaT const &ref, std::string const &hint )
- : m_ref( std::make_shared<BoundLambda<LambdaT>>( ref ) ),
- m_hint(hint)
- {}
-
- auto operator()( std::string const &description ) -> DerivedT & {
- m_description = description;
- return static_cast<DerivedT &>( *this );
- }
-
- auto optional() -> DerivedT & {
- m_optionality = Optionality::Optional;
- return static_cast<DerivedT &>( *this );
- };
-
- auto required() -> DerivedT & {
- m_optionality = Optionality::Required;
- return static_cast<DerivedT &>( *this );
- };
-
- auto isOptional() const -> bool {
- return m_optionality == Optionality::Optional;
- }
-
- auto cardinality() const -> size_t override {
- if( m_ref->isContainer() )
- return 0;
- else
- return 1;
- }
-
- auto hint() const -> std::string { return m_hint; }
- };
-
- class ExeName : public ComposableParserImpl<ExeName> {
- std::shared_ptr<std::string> m_name;
- std::shared_ptr<BoundRefBase> m_ref;
-
- template<typename LambdaT>
- static auto makeRef(LambdaT const &lambda) -> std::shared_ptr<BoundRefBase> {
- return std::make_shared<BoundLambda<LambdaT>>( lambda) ;
- }
-
- public:
- ExeName() : m_name( std::make_shared<std::string>( "<executable>" ) ) {}
-
- explicit ExeName( std::string &ref ) : ExeName() {
- m_ref = std::make_shared<BoundRef<std::string>>( ref );
- }
-
- template<typename LambdaT>
- explicit ExeName( LambdaT const& lambda ) : ExeName() {
- m_ref = std::make_shared<BoundLambda<LambdaT>>( lambda );
- }
-
- // The exe name is not parsed out of the normal tokens, but is handled specially
- auto parse( std::string const&, TokenStream const &tokens ) const -> InternalParseResult override {
- return InternalParseResult::ok( ParseState( ParseResultType::NoMatch, tokens ) );
- }
-
- auto name() const -> std::string { return *m_name; }
- auto set( std::string const& newName ) -> ParserResult {
-
- auto lastSlash = newName.find_last_of( "\\/" );
- auto filename = ( lastSlash == std::string::npos )
- ? newName
- : newName.substr( lastSlash+1 );
-
- *m_name = filename;
- if( m_ref )
- return m_ref->setValue( filename );
- else
- return ParserResult::ok( ParseResultType::Matched );
- }
- };
-
- class Arg : public ParserRefImpl<Arg> {
- public:
- using ParserRefImpl::ParserRefImpl;
-
- auto parse( std::string const &, TokenStream const &tokens ) const -> InternalParseResult override {
- auto validationResult = validate();
- if( !validationResult )
- return InternalParseResult( validationResult );
-
- auto remainingTokens = tokens;
- auto const &token = *remainingTokens;
- if( token.type != TokenType::Argument )
- return InternalParseResult::ok( ParseState( ParseResultType::NoMatch, remainingTokens ) );
-
- auto result = m_ref->setValue( remainingTokens->token );
- if( !result )
- return InternalParseResult( result );
- else
- return InternalParseResult::ok( ParseState( ParseResultType::Matched, ++remainingTokens ) );
- }
- };
-
- inline auto normaliseOpt( std::string const &optName ) -> std::string {
-#ifdef CATCH_PLATFORM_WINDOWS
- if( optName[0] == '/' )
- return "-" + optName.substr( 1 );
- else
-#endif
- return optName;
- }
-
- class Opt : public ParserRefImpl<Opt> {
- protected:
- std::vector<std::string> m_optNames;
-
- public:
- template<typename LambdaT>
- explicit Opt( LambdaT const &ref ) : ParserRefImpl( std::make_shared<BoundFlagLambda<LambdaT>>( ref ) ) {}
-
- explicit Opt( bool &ref ) : ParserRefImpl( std::make_shared<BoundFlagRef>( ref ) ) {}
-
- template<typename LambdaT>
- Opt( LambdaT const &ref, std::string const &hint ) : ParserRefImpl( ref, hint ) {}
-
- template<typename T>
- Opt( T &ref, std::string const &hint ) : ParserRefImpl( ref, hint ) {}
-
- auto operator[]( std::string const &optName ) -> Opt & {
- m_optNames.push_back( optName );
- return *this;
- }
-
- auto getHelpColumns() const -> std::vector<HelpColumns> {
- std::ostringstream oss;
- bool first = true;
- for( auto const &opt : m_optNames ) {
- if (first)
- first = false;
- else
- oss << ", ";
- oss << opt;
- }
- if( !m_hint.empty() )
- oss << " <" << m_hint << ">";
- return { { oss.str(), m_description } };
- }
-
- auto isMatch( std::string const &optToken ) const -> bool {
- auto normalisedToken = normaliseOpt( optToken );
- for( auto const &name : m_optNames ) {
- if( normaliseOpt( name ) == normalisedToken )
- return true;
- }
- return false;
- }
-
- using ParserBase::parse;
-
- auto parse( std::string const&, TokenStream const &tokens ) const -> InternalParseResult override {
- auto validationResult = validate();
- if( !validationResult )
- return InternalParseResult( validationResult );
-
- auto remainingTokens = tokens;
- if( remainingTokens && remainingTokens->type == TokenType::Option ) {
- auto const &token = *remainingTokens;
- if( isMatch(token.token ) ) {
- if( m_ref->isFlag() ) {
- auto result = m_ref->setFlag( true );
- if( !result )
- return InternalParseResult( result );
- if( result.value() == ParseResultType::ShortCircuitAll )
- return InternalParseResult::ok( ParseState( result.value(), remainingTokens ) );
- } else {
- ++remainingTokens;
- if( !remainingTokens )
- return InternalParseResult::runtimeError( "Expected argument following " + token.token );
- auto const &argToken = *remainingTokens;
- if( argToken.type != TokenType::Argument )
- return InternalParseResult::runtimeError( "Expected argument following " + token.token );
- auto result = m_ref->setValue( argToken.token );
- if( !result )
- return InternalParseResult( result );
- if( result.value() == ParseResultType::ShortCircuitAll )
- return InternalParseResult::ok( ParseState( result.value(), remainingTokens ) );
- }
- return InternalParseResult::ok( ParseState( ParseResultType::Matched, ++remainingTokens ) );
- }
- }
- return InternalParseResult::ok( ParseState( ParseResultType::NoMatch, remainingTokens ) );
- }
-
- auto validate() const -> Result override {
- if( m_optNames.empty() )
- return Result::logicError( "No options supplied to Opt" );
- for( auto const &name : m_optNames ) {
- if( name.empty() )
- return Result::logicError( "Option name cannot be empty" );
-#ifdef CATCH_PLATFORM_WINDOWS
- if( name[0] != '-' && name[0] != '/' )
- return Result::logicError( "Option name must begin with '-' or '/'" );
-#else
- if( name[0] != '-' )
- return Result::logicError( "Option name must begin with '-'" );
-#endif
- }
- return ParserRefImpl::validate();
- }
- };
-
- struct Help : Opt {
- Help( bool &showHelpFlag )
- : Opt([&]( bool flag ) {
- showHelpFlag = flag;
- return ParserResult::ok( ParseResultType::ShortCircuitAll );
- })
- {
- static_cast<Opt &>( *this )
- ("display usage information")
- ["-?"]["-h"]["--help"]
- .optional();
- }
- };
-
- struct Parser : ParserBase {
-
- mutable ExeName m_exeName;
- std::vector<Opt> m_options;
- std::vector<Arg> m_args;
-
- auto operator|=( ExeName const &exeName ) -> Parser & {
- m_exeName = exeName;
- return *this;
- }
-
- auto operator|=( Arg const &arg ) -> Parser & {
- m_args.push_back(arg);
- return *this;
- }
-
- auto operator|=( Opt const &opt ) -> Parser & {
- m_options.push_back(opt);
- return *this;
- }
-
- auto operator|=( Parser const &other ) -> Parser & {
- m_options.insert(m_options.end(), other.m_options.begin(), other.m_options.end());
- m_args.insert(m_args.end(), other.m_args.begin(), other.m_args.end());
- return *this;
- }
-
- template<typename T>
- auto operator|( T const &other ) const -> Parser {
- return Parser( *this ) |= other;
- }
-
- auto getHelpColumns() const -> std::vector<HelpColumns> {
- std::vector<HelpColumns> cols;
- for (auto const &o : m_options) {
- auto childCols = o.getHelpColumns();
- cols.insert( cols.end(), childCols.begin(), childCols.end() );
- }
- return cols;
- }
-
- void writeToStream( std::ostream &os ) const {
- if (!m_exeName.name().empty()) {
- os << "usage:\n" << " " << m_exeName.name() << " ";
- bool required = true, first = true;
- for( auto const &arg : m_args ) {
- if (first)
- first = false;
- else
- os << " ";
- if( arg.isOptional() && required ) {
- os << "[";
- required = false;
- }
- os << "<" << arg.hint() << ">";
- if( arg.cardinality() == 0 )
- os << " ... ";
- }
- if( !required )
- os << "]";
- if( !m_options.empty() )
- os << " options";
- os << "\n\nwhere options are:" << std::endl;
- }
-
- auto rows = getHelpColumns();
- size_t consoleWidth = CATCH_CLARA_CONFIG_CONSOLE_WIDTH;
- size_t optWidth = 0;
- for( auto const &cols : rows )
- optWidth = (std::max)(optWidth, cols.left.size() + 2);
-
- for( auto const &cols : rows ) {
- auto row =
- TextFlow::Column( cols.left ).width( optWidth ).indent( 2 ) +
- TextFlow::Spacer(4) +
- TextFlow::Column( cols.right ).width( consoleWidth - 7 - optWidth );
- os << row << std::endl;
- }
- }
-
- friend auto operator<<( std::ostream &os, Parser const &parser ) -> std::ostream& {
- parser.writeToStream( os );
- return os;
- }
-
- auto validate() const -> Result override {
- for( auto const &opt : m_options ) {
- auto result = opt.validate();
- if( !result )
- return result;
- }
- for( auto const &arg : m_args ) {
- auto result = arg.validate();
- if( !result )
- return result;
- }
- return Result::ok();
- }
-
- using ParserBase::parse;
-
- auto parse( std::string const& exeName, TokenStream const &tokens ) const -> InternalParseResult override {
-
- struct ParserInfo {
- ParserBase const* parser = nullptr;
- size_t count = 0;
- };
- const size_t totalParsers = m_options.size() + m_args.size();
- assert( totalParsers < 512 );
- // ParserInfo parseInfos[totalParsers]; // <-- this is what we really want to do
- ParserInfo parseInfos[512];
-
- {
- size_t i = 0;
- for (auto const &opt : m_options) parseInfos[i++].parser = &opt;
- for (auto const &arg : m_args) parseInfos[i++].parser = &arg;
- }
-
- m_exeName.set( exeName );
-
- auto result = InternalParseResult::ok( ParseState( ParseResultType::NoMatch, tokens ) );
- while( result.value().remainingTokens() ) {
- bool tokenParsed = false;
-
- for( size_t i = 0; i < totalParsers; ++i ) {
- auto& parseInfo = parseInfos[i];
- if( parseInfo.parser->cardinality() == 0 || parseInfo.count < parseInfo.parser->cardinality() ) {
- result = parseInfo.parser->parse(exeName, result.value().remainingTokens());
- if (!result)
- return result;
- if (result.value().type() != ParseResultType::NoMatch) {
- tokenParsed = true;
- ++parseInfo.count;
- break;
- }
- }
- }
-
- if( result.value().type() == ParseResultType::ShortCircuitAll )
- return result;
- if( !tokenParsed )
- return InternalParseResult::runtimeError( "Unrecognised token: " + result.value().remainingTokens()->token );
- }
- // !TBD Check missing required options
- return result;
- }
- };
-
- template<typename DerivedT>
- template<typename T>
- auto ComposableParserImpl<DerivedT>::operator|( T const &other ) const -> Parser {
- return Parser() | static_cast<DerivedT const &>( *this ) | other;
- }
-} // namespace detail
-
-// A Combined parser
-using detail::Parser;
-
-// A parser for options
-using detail::Opt;
-
-// A parser for arguments
-using detail::Arg;
-
-// Wrapper for argc, argv from main()
-using detail::Args;
-
-// Specifies the name of the executable
-using detail::ExeName;
-
-// Convenience wrapper for option parser that specifies the help option
-using detail::Help;
-
-// enum of result types from a parse
-using detail::ParseResultType;
-
-// Result type for parser operation
-using detail::ParserResult;
-
-}} // namespace Catch::clara
-
-// end clara.hpp
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
-
-// Restore Clara's value for console width, if present
-#ifdef CATCH_TEMP_CLARA_CONFIG_CONSOLE_WIDTH
-#define CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH CATCH_TEMP_CLARA_CONFIG_CONSOLE_WIDTH
-#undef CATCH_TEMP_CLARA_CONFIG_CONSOLE_WIDTH
-#endif
-
-// end catch_clara.h
-namespace Catch {
-
- clara::Parser makeCommandLineParser( ConfigData& config );
-
-} // end namespace Catch
-
-// end catch_commandline.h
-#include <fstream>
-#include <ctime>
-
-namespace Catch {
-
- clara::Parser makeCommandLineParser( ConfigData& config ) {
-
- using namespace clara;
-
- auto const setWarning = [&]( std::string const& warning ) {
- if( warning != "NoAssertions" )
- return ParserResult::runtimeError( "Unrecognised warning: '" + warning + "'" );
- config.warnings = static_cast<WarnAbout::What>( config.warnings | WarnAbout::NoAssertions );
- return ParserResult::ok( ParseResultType::Matched );
- };
- auto const loadTestNamesFromFile = [&]( std::string const& filename ) {
- std::ifstream f( filename.c_str() );
- if( !f.is_open() )
- return ParserResult::runtimeError( "Unable to load input file: '" + filename + "'" );
-
- std::string line;
- while( std::getline( f, line ) ) {
- line = trim(line);
- if( !line.empty() && !startsWith( line, '#' ) ) {
- if( !startsWith( line, '"' ) )
- line = '"' + line + '"';
- config.testsOrTags.push_back( line + ',' );
- }
- }
- return ParserResult::ok( ParseResultType::Matched );
- };
- auto const setTestOrder = [&]( std::string const& order ) {
- if( startsWith( "declared", order ) )
- config.runOrder = RunTests::InDeclarationOrder;
- else if( startsWith( "lexical", order ) )
- config.runOrder = RunTests::InLexicographicalOrder;
- else if( startsWith( "random", order ) )
- config.runOrder = RunTests::InRandomOrder;
- else
- return clara::ParserResult::runtimeError( "Unrecognised ordering: '" + order + "'" );
- return ParserResult::ok( ParseResultType::Matched );
- };
- auto const setRngSeed = [&]( std::string const& seed ) {
- if( seed != "time" )
- return clara::detail::convertInto( seed, config.rngSeed );
- config.rngSeed = static_cast<unsigned int>( std::time(nullptr) );
- return ParserResult::ok( ParseResultType::Matched );
- };
- auto const setColourUsage = [&]( std::string const& useColour ) {
- auto mode = toLower( useColour );
-
- if( mode == "yes" )
- config.useColour = UseColour::Yes;
- else if( mode == "no" )
- config.useColour = UseColour::No;
- else if( mode == "auto" )
- config.useColour = UseColour::Auto;
- else
- return ParserResult::runtimeError( "colour mode must be one of: auto, yes or no. '" + useColour + "' not recognised" );
- return ParserResult::ok( ParseResultType::Matched );
- };
- auto const setWaitForKeypress = [&]( std::string const& keypress ) {
- auto keypressLc = toLower( keypress );
- if( keypressLc == "start" )
- config.waitForKeypress = WaitForKeypress::BeforeStart;
- else if( keypressLc == "exit" )
- config.waitForKeypress = WaitForKeypress::BeforeExit;
- else if( keypressLc == "both" )
- config.waitForKeypress = WaitForKeypress::BeforeStartAndExit;
- else
- return ParserResult::runtimeError( "keypress argument must be one of: start, exit or both. '" + keypress + "' not recognised" );
- return ParserResult::ok( ParseResultType::Matched );
- };
- auto const setVerbosity = [&]( std::string const& verbosity ) {
- auto lcVerbosity = toLower( verbosity );
- if( lcVerbosity == "quiet" )
- config.verbosity = Verbosity::Quiet;
- else if( lcVerbosity == "normal" )
- config.verbosity = Verbosity::Normal;
- else if( lcVerbosity == "high" )
- config.verbosity = Verbosity::High;
- else
- return ParserResult::runtimeError( "Unrecognised verbosity, '" + verbosity + "'" );
- return ParserResult::ok( ParseResultType::Matched );
- };
-
- auto cli
- = ExeName( config.processName )
- | Help( config.showHelp )
- | Opt( config.listTests )
- ["-l"]["--list-tests"]
- ( "list all/matching test cases" )
- | Opt( config.listTags )
- ["-t"]["--list-tags"]
- ( "list all/matching tags" )
- | Opt( config.showSuccessfulTests )
- ["-s"]["--success"]
- ( "include successful tests in output" )
- | Opt( config.shouldDebugBreak )
- ["-b"]["--break"]
- ( "break into debugger on failure" )
- | Opt( config.noThrow )
- ["-e"]["--nothrow"]
- ( "skip exception tests" )
- | Opt( config.showInvisibles )
- ["-i"]["--invisibles"]
- ( "show invisibles (tabs, newlines)" )
- | Opt( config.outputFilename, "filename" )
- ["-o"]["--out"]
- ( "output filename" )
- | Opt( config.reporterNames, "name" )
- ["-r"]["--reporter"]
- ( "reporter to use (defaults to console)" )
- | Opt( config.name, "name" )
- ["-n"]["--name"]
- ( "suite name" )
- | Opt( [&]( bool ){ config.abortAfter = 1; } )
- ["-a"]["--abort"]
- ( "abort at first failure" )
- | Opt( [&]( int x ){ config.abortAfter = x; }, "no. failures" )
- ["-x"]["--abortx"]
- ( "abort after x failures" )
- | Opt( setWarning, "warning name" )
- ["-w"]["--warn"]
- ( "enable warnings" )
- | Opt( [&]( bool flag ) { config.showDurations = flag ? ShowDurations::Always : ShowDurations::Never; }, "yes|no" )
- ["-d"]["--durations"]
- ( "show test durations" )
- | Opt( loadTestNamesFromFile, "filename" )
- ["-f"]["--input-file"]
- ( "load test names to run from a file" )
- | Opt( config.filenamesAsTags )
- ["-#"]["--filenames-as-tags"]
- ( "adds a tag for the filename" )
- | Opt( config.sectionsToRun, "section name" )
- ["-c"]["--section"]
- ( "specify section to run" )
- | Opt( setVerbosity, "quiet|normal|high" )
- ["-v"]["--verbosity"]
- ( "set output verbosity" )
- | Opt( config.listTestNamesOnly )
- ["--list-test-names-only"]
- ( "list all/matching test cases names only" )
- | Opt( config.listReporters )
- ["--list-reporters"]
- ( "list all reporters" )
- | Opt( setTestOrder, "decl|lex|rand" )
- ["--order"]
- ( "test case order (defaults to decl)" )
- | Opt( setRngSeed, "'time'|number" )
- ["--rng-seed"]
- ( "set a specific seed for random numbers" )
- | Opt( setColourUsage, "yes|no" )
- ["--use-colour"]
- ( "should output be colourised" )
- | Opt( config.libIdentify )
- ["--libidentify"]
- ( "report name and version according to libidentify standard" )
- | Opt( setWaitForKeypress, "start|exit|both" )
- ["--wait-for-keypress"]
- ( "waits for a keypress before exiting" )
- | Opt( config.benchmarkResolutionMultiple, "multiplier" )
- ["--benchmark-resolution-multiple"]
- ( "multiple of clock resolution to run benchmarks" )
-
- | Arg( config.testsOrTags, "test name|pattern|tags" )
- ( "which test or tests to use" );
-
- return cli;
- }
-
-} // end namespace Catch
-// end catch_commandline.cpp
-// start catch_common.cpp
-
-#include <cstring>
-#include <ostream>
-
-namespace Catch {
-
- SourceLineInfo::SourceLineInfo( char const* _file, std::size_t _line ) noexcept
- : file( _file ),
- line( _line )
- {}
- bool SourceLineInfo::empty() const noexcept {
- return file[0] == '\0';
- }
- bool SourceLineInfo::operator == ( SourceLineInfo const& other ) const noexcept {
- return line == other.line && (file == other.file || std::strcmp(file, other.file) == 0);
- }
- bool SourceLineInfo::operator < ( SourceLineInfo const& other ) const noexcept {
- return line < other.line || ( line == other.line && (std::strcmp(file, other.file) < 0));
- }
-
- std::ostream& operator << ( std::ostream& os, SourceLineInfo const& info ) {
-#ifndef __GNUG__
- os << info.file << '(' << info.line << ')';
-#else
- os << info.file << ':' << info.line;
-#endif
- return os;
- }
-
- bool isTrue( bool value ){ return value; }
- bool alwaysTrue() { return true; }
- bool alwaysFalse() { return false; }
-
- std::string StreamEndStop::operator+() const {
- return std::string();
- }
-
- NonCopyable::NonCopyable() = default;
- NonCopyable::~NonCopyable() = default;
-
-}
-// end catch_common.cpp
-// start catch_config.cpp
-
-namespace Catch {
-
- Config::Config( ConfigData const& data )
- : m_data( data ),
- m_stream( openStream() )
- {
- if( !data.testsOrTags.empty() ) {
- TestSpecParser parser( ITagAliasRegistry::get() );
- for( auto const& testOrTags : data.testsOrTags )
- parser.parse( testOrTags );
- m_testSpec = parser.testSpec();
- }
- }
-
- std::string const& Config::getFilename() const {
- return m_data.outputFilename ;
- }
-
- bool Config::listTests() const { return m_data.listTests; }
- bool Config::listTestNamesOnly() const { return m_data.listTestNamesOnly; }
- bool Config::listTags() const { return m_data.listTags; }
- bool Config::listReporters() const { return m_data.listReporters; }
-
- std::string Config::getProcessName() const { return m_data.processName; }
-
- std::vector<std::string> const& Config::getReporterNames() const { return m_data.reporterNames; }
- std::vector<std::string> const& Config::getSectionsToRun() const { return m_data.sectionsToRun; }
-
- TestSpec const& Config::testSpec() const { return m_testSpec; }
-
- bool Config::showHelp() const { return m_data.showHelp; }
-
- // IConfig interface
- bool Config::allowThrows() const { return !m_data.noThrow; }
- std::ostream& Config::stream() const { return m_stream->stream(); }
- std::string Config::name() const { return m_data.name.empty() ? m_data.processName : m_data.name; }
- bool Config::includeSuccessfulResults() const { return m_data.showSuccessfulTests; }
- bool Config::warnAboutMissingAssertions() const { return m_data.warnings & WarnAbout::NoAssertions; }
- ShowDurations::OrNot Config::showDurations() const { return m_data.showDurations; }
- RunTests::InWhatOrder Config::runOrder() const { return m_data.runOrder; }
- unsigned int Config::rngSeed() const { return m_data.rngSeed; }
- int Config::benchmarkResolutionMultiple() const { return m_data.benchmarkResolutionMultiple; }
- UseColour::YesOrNo Config::useColour() const { return m_data.useColour; }
- bool Config::shouldDebugBreak() const { return m_data.shouldDebugBreak; }
- int Config::abortAfter() const { return m_data.abortAfter; }
- bool Config::showInvisibles() const { return m_data.showInvisibles; }
- Verbosity Config::verbosity() const { return m_data.verbosity; }
-
- IStream const* Config::openStream() {
- if( m_data.outputFilename.empty() )
- return new CoutStream();
- else if( m_data.outputFilename[0] == '%' ) {
- if( m_data.outputFilename == "%debug" )
- return new DebugOutStream();
- else
- CATCH_ERROR( "Unrecognised stream: '" << m_data.outputFilename << "'" );
- }
- else
- return new FileStream( m_data.outputFilename );
- }
-
-} // end namespace Catch
-// end catch_config.cpp
-// start catch_console_colour.cpp
-
-#if defined(__clang__)
-# pragma clang diagnostic push
-# pragma clang diagnostic ignored "-Wexit-time-destructors"
-#endif
-
-// start catch_errno_guard.h
-
-namespace Catch {
-
- class ErrnoGuard {
- public:
- ErrnoGuard();
- ~ErrnoGuard();
- private:
- int m_oldErrno;
- };
-
-}
-
-// end catch_errno_guard.h
-// start catch_windows_h_proxy.h
-
-
-#if defined(CATCH_PLATFORM_WINDOWS)
-
-#if !defined(NOMINMAX) && !defined(CATCH_CONFIG_NO_NOMINMAX)
-# define CATCH_DEFINED_NOMINMAX
-# define NOMINMAX
-#endif
-#if !defined(WIN32_LEAN_AND_MEAN) && !defined(CATCH_CONFIG_NO_WIN32_LEAN_AND_MEAN)
-# define CATCH_DEFINED_WIN32_LEAN_AND_MEAN
-# define WIN32_LEAN_AND_MEAN
-#endif
-
-#ifdef __AFXDLL
-#include <AfxWin.h>
-#else
-#include <windows.h>
-#endif
-
-#ifdef CATCH_DEFINED_NOMINMAX
-# undef NOMINMAX
-#endif
-#ifdef CATCH_DEFINED_WIN32_LEAN_AND_MEAN
-# undef WIN32_LEAN_AND_MEAN
-#endif
-
-#endif // defined(CATCH_PLATFORM_WINDOWS)
-
-// end catch_windows_h_proxy.h
-namespace Catch {
- namespace {
-
- struct IColourImpl {
- virtual ~IColourImpl() = default;
- virtual void use( Colour::Code _colourCode ) = 0;
- };
-
- struct NoColourImpl : IColourImpl {
- void use( Colour::Code ) {}
-
- static IColourImpl* instance() {
- static NoColourImpl s_instance;
- return &s_instance;
- }
- };
-
- } // anon namespace
-} // namespace Catch
-
-#if !defined( CATCH_CONFIG_COLOUR_NONE ) && !defined( CATCH_CONFIG_COLOUR_WINDOWS ) && !defined( CATCH_CONFIG_COLOUR_ANSI )
-# ifdef CATCH_PLATFORM_WINDOWS
-# define CATCH_CONFIG_COLOUR_WINDOWS
-# else
-# define CATCH_CONFIG_COLOUR_ANSI
-# endif
-#endif
-
-#if defined ( CATCH_CONFIG_COLOUR_WINDOWS ) /////////////////////////////////////////
-
-namespace Catch {
-namespace {
-
- class Win32ColourImpl : public IColourImpl {
- public:
- Win32ColourImpl() : stdoutHandle( GetStdHandle(STD_OUTPUT_HANDLE) )
- {
- CONSOLE_SCREEN_BUFFER_INFO csbiInfo;
- GetConsoleScreenBufferInfo( stdoutHandle, &csbiInfo );
- originalForegroundAttributes = csbiInfo.wAttributes & ~( BACKGROUND_GREEN | BACKGROUND_RED | BACKGROUND_BLUE | BACKGROUND_INTENSITY );
- originalBackgroundAttributes = csbiInfo.wAttributes & ~( FOREGROUND_GREEN | FOREGROUND_RED | FOREGROUND_BLUE | FOREGROUND_INTENSITY );
- }
-
- virtual void use( Colour::Code _colourCode ) override {
- switch( _colourCode ) {
- case Colour::None: return setTextAttribute( originalForegroundAttributes );
- case Colour::White: return setTextAttribute( FOREGROUND_GREEN | FOREGROUND_RED | FOREGROUND_BLUE );
- case Colour::Red: return setTextAttribute( FOREGROUND_RED );
- case Colour::Green: return setTextAttribute( FOREGROUND_GREEN );
- case Colour::Blue: return setTextAttribute( FOREGROUND_BLUE );
- case Colour::Cyan: return setTextAttribute( FOREGROUND_BLUE | FOREGROUND_GREEN );
- case Colour::Yellow: return setTextAttribute( FOREGROUND_RED | FOREGROUND_GREEN );
- case Colour::Grey: return setTextAttribute( 0 );
-
- case Colour::LightGrey: return setTextAttribute( FOREGROUND_INTENSITY );
- case Colour::BrightRed: return setTextAttribute( FOREGROUND_INTENSITY | FOREGROUND_RED );
- case Colour::BrightGreen: return setTextAttribute( FOREGROUND_INTENSITY | FOREGROUND_GREEN );
- case Colour::BrightWhite: return setTextAttribute( FOREGROUND_INTENSITY | FOREGROUND_GREEN | FOREGROUND_RED | FOREGROUND_BLUE );
-
- case Colour::Bright: CATCH_INTERNAL_ERROR( "not a colour" );
- }
- }
-
- private:
- void setTextAttribute( WORD _textAttribute ) {
- SetConsoleTextAttribute( stdoutHandle, _textAttribute | originalBackgroundAttributes );
- }
- HANDLE stdoutHandle;
- WORD originalForegroundAttributes;
- WORD originalBackgroundAttributes;
- };
-
- IColourImpl* platformColourInstance() {
- static Win32ColourImpl s_instance;
-
- IConfigPtr config = getCurrentContext().getConfig();
- UseColour::YesOrNo colourMode = config
- ? config->useColour()
- : UseColour::Auto;
- if( colourMode == UseColour::Auto )
- colourMode = UseColour::Yes;
- return colourMode == UseColour::Yes
- ? &s_instance
- : NoColourImpl::instance();
- }
-
-} // end anon namespace
-} // end namespace Catch
-
-#elif defined( CATCH_CONFIG_COLOUR_ANSI ) //////////////////////////////////////
-
-#include <unistd.h>
-
-namespace Catch {
-namespace {
-
- // use POSIX/ ANSI console terminal codes
- // Thanks to Adam Strzelecki for original contribution
- // (http://github.com/nanoant)
- // https://github.com/philsquared/Catch/pull/131
- class PosixColourImpl : public IColourImpl {
- public:
- virtual void use( Colour::Code _colourCode ) override {
- switch( _colourCode ) {
- case Colour::None:
- case Colour::White: return setColour( "[0m" );
- case Colour::Red: return setColour( "[0;31m" );
- case Colour::Green: return setColour( "[0;32m" );
- case Colour::Blue: return setColour( "[0;34m" );
- case Colour::Cyan: return setColour( "[0;36m" );
- case Colour::Yellow: return setColour( "[0;33m" );
- case Colour::Grey: return setColour( "[1;30m" );
-
- case Colour::LightGrey: return setColour( "[0;37m" );
- case Colour::BrightRed: return setColour( "[1;31m" );
- case Colour::BrightGreen: return setColour( "[1;32m" );
- case Colour::BrightWhite: return setColour( "[1;37m" );
-
- case Colour::Bright: CATCH_INTERNAL_ERROR( "not a colour" );
- }
- }
- static IColourImpl* instance() {
- static PosixColourImpl s_instance;
- return &s_instance;
- }
-
- private:
- void setColour( const char* _escapeCode ) {
- Catch::cout() << '\033' << _escapeCode;
- }
- };
-
- bool useColourOnPlatform() {
- return
-#ifdef CATCH_PLATFORM_MAC
- !isDebuggerActive() &&
-#endif
- isatty(STDOUT_FILENO);
- }
- IColourImpl* platformColourInstance() {
- ErrnoGuard guard;
- IConfigPtr config = getCurrentContext().getConfig();
- UseColour::YesOrNo colourMode = config
- ? config->useColour()
- : UseColour::Auto;
- if( colourMode == UseColour::Auto )
- colourMode = useColourOnPlatform()
- ? UseColour::Yes
- : UseColour::No;
- return colourMode == UseColour::Yes
- ? PosixColourImpl::instance()
- : NoColourImpl::instance();
- }
-
-} // end anon namespace
-} // end namespace Catch
-
-#else // not Windows or ANSI ///////////////////////////////////////////////
-
-namespace Catch {
-
- static IColourImpl* platformColourInstance() { return NoColourImpl::instance(); }
-
-} // end namespace Catch
-
-#endif // Windows/ ANSI/ None
-
-namespace Catch {
-
- Colour::Colour( Code _colourCode ) { use( _colourCode ); }
- Colour::Colour( Colour&& rhs ) noexcept {
- m_moved = rhs.m_moved;
- rhs.m_moved = true;
- }
- Colour& Colour::operator=( Colour&& rhs ) noexcept {
- m_moved = rhs.m_moved;
- rhs.m_moved = true;
- return *this;
- }
-
- Colour::~Colour(){ if( !m_moved ) use( None ); }
-
- void Colour::use( Code _colourCode ) {
- static IColourImpl* impl = platformColourInstance();
- impl->use( _colourCode );
- }
-
- std::ostream& operator << ( std::ostream& os, Colour const& ) {
- return os;
- }
-
-} // end namespace Catch
-
-#if defined(__clang__)
-# pragma clang diagnostic pop
-#endif
-
-// end catch_console_colour.cpp
-// start catch_context.cpp
-
-namespace Catch {
-
- class Context : public IMutableContext, NonCopyable {
-
- public: // IContext
- virtual IResultCapture* getResultCapture() override {
- return m_resultCapture;
- }
- virtual IRunner* getRunner() override {
- return m_runner;
- }
-
- virtual IConfigPtr getConfig() const override {
- return m_config;
- }
-
- virtual ~Context() override;
-
- public: // IMutableContext
- virtual void setResultCapture( IResultCapture* resultCapture ) override {
- m_resultCapture = resultCapture;
- }
- virtual void setRunner( IRunner* runner ) override {
- m_runner = runner;
- }
- virtual void setConfig( IConfigPtr const& config ) override {
- m_config = config;
- }
-
- friend IMutableContext& getCurrentMutableContext();
-
- private:
- IConfigPtr m_config;
- IRunner* m_runner = nullptr;
- IResultCapture* m_resultCapture = nullptr;
- };
-
- namespace {
- Context* currentContext = nullptr;
- }
- IMutableContext& getCurrentMutableContext() {
- if( !currentContext )
- currentContext = new Context();
- return *currentContext;
- }
- IContext& getCurrentContext() {
- return getCurrentMutableContext();
- }
-
- void cleanUpContext() {
- delete currentContext;
- currentContext = nullptr;
- }
- IContext::~IContext() = default;
- IMutableContext::~IMutableContext() = default;
- Context::~Context() = default;
-}
-// end catch_context.cpp
-// start catch_debug_console.cpp
-
-// start catch_debug_console.h
-
-#include <string>
-
-namespace Catch {
- void writeToDebugConsole( std::string const& text );
-}
-
-// end catch_debug_console.h
-#ifdef CATCH_PLATFORM_WINDOWS
-
- namespace Catch {
- void writeToDebugConsole( std::string const& text ) {
- ::OutputDebugStringA( text.c_str() );
- }
- }
-#else
- namespace Catch {
- void writeToDebugConsole( std::string const& text ) {
- // !TBD: Need a version for Mac/ XCode and other IDEs
- Catch::cout() << text;
- }
- }
-#endif // Platform
-// end catch_debug_console.cpp
-// start catch_debugger.cpp
-
-#ifdef CATCH_PLATFORM_MAC
-
- #include <assert.h>
- #include <stdbool.h>
- #include <sys/types.h>
- #include <unistd.h>
- #include <sys/sysctl.h>
-
- namespace Catch {
-
- // The following function is taken directly from the following technical note:
- // http://developer.apple.com/library/mac/#qa/qa2004/qa1361.html
-
- // Returns true if the current process is being debugged (either
- // running under the debugger or has a debugger attached post facto).
- bool isDebuggerActive(){
-
- int mib[4];
- struct kinfo_proc info;
- std::size_t size;
-
- // Initialize the flags so that, if sysctl fails for some bizarre
- // reason, we get a predictable result.
-
- info.kp_proc.p_flag = 0;
-
- // Initialize mib, which tells sysctl the info we want, in this case
- // we're looking for information about a specific process ID.
-
- mib[0] = CTL_KERN;
- mib[1] = KERN_PROC;
- mib[2] = KERN_PROC_PID;
- mib[3] = getpid();
-
- // Call sysctl.
-
- size = sizeof(info);
- if( sysctl(mib, sizeof(mib) / sizeof(*mib), &info, &size, nullptr, 0) != 0 ) {
- Catch::cerr() << "\n** Call to sysctl failed - unable to determine if debugger is active **\n" << std::endl;
- return false;
- }
-
- // We're being debugged if the P_TRACED flag is set.
-
- return ( (info.kp_proc.p_flag & P_TRACED) != 0 );
- }
- } // namespace Catch
-
-#elif defined(CATCH_PLATFORM_LINUX)
- #include <fstream>
- #include <string>
-
- namespace Catch{
- // The standard POSIX way of detecting a debugger is to attempt to
- // ptrace() the process, but this needs to be done from a child and not
- // this process itself to still allow attaching to this process later
- // if wanted, so is rather heavy. Under Linux we have the PID of the
- // "debugger" (which doesn't need to be gdb, of course, it could also
- // be strace, for example) in /proc/$PID/status, so just get it from
- // there instead.
- bool isDebuggerActive(){
- // Libstdc++ has a bug, where std::ifstream sets errno to 0
- // This way our users can properly assert over errno values
- ErrnoGuard guard;
- std::ifstream in("/proc/self/status");
- for( std::string line; std::getline(in, line); ) {
- static const int PREFIX_LEN = 11;
- if( line.compare(0, PREFIX_LEN, "TracerPid:\t") == 0 ) {
- // We're traced if the PID is not 0 and no other PID starts
- // with 0 digit, so it's enough to check for just a single
- // character.
- return line.length() > PREFIX_LEN && line[PREFIX_LEN] != '0';
- }
- }
-
- return false;
- }
- } // namespace Catch
-#elif defined(_MSC_VER)
- extern "C" __declspec(dllimport) int __stdcall IsDebuggerPresent();
- namespace Catch {
- bool isDebuggerActive() {
- return IsDebuggerPresent() != 0;
- }
- }
-#elif defined(__MINGW32__)
- extern "C" __declspec(dllimport) int __stdcall IsDebuggerPresent();
- namespace Catch {
- bool isDebuggerActive() {
- return IsDebuggerPresent() != 0;
- }
- }
-#else
- namespace Catch {
- bool isDebuggerActive() { return false; }
- }
-#endif // Platform
-// end catch_debugger.cpp
-// start catch_decomposer.cpp
-
-namespace Catch {
-
- ITransientExpression::~ITransientExpression() = default;
-
- void formatReconstructedExpression( std::ostream &os, std::string const& lhs, StringRef op, std::string const& rhs ) {
- if( lhs.size() + rhs.size() < 40 &&
- lhs.find('\n') == std::string::npos &&
- rhs.find('\n') == std::string::npos )
- os << lhs << " " << op << " " << rhs;
- else
- os << lhs << "\n" << op << "\n" << rhs;
- }
-}
-// end catch_decomposer.cpp
-// start catch_errno_guard.cpp
-
-#include <cerrno>
-
-namespace Catch {
- ErrnoGuard::ErrnoGuard():m_oldErrno(errno){}
- ErrnoGuard::~ErrnoGuard() { errno = m_oldErrno; }
-}
-// end catch_errno_guard.cpp
-// start catch_exception_translator_registry.cpp
-
-// start catch_exception_translator_registry.h
-
-#include <vector>
-#include <string>
-#include <memory>
-
-namespace Catch {
-
- class ExceptionTranslatorRegistry : public IExceptionTranslatorRegistry {
- public:
- ~ExceptionTranslatorRegistry();
- virtual void registerTranslator( const IExceptionTranslator* translator );
- virtual std::string translateActiveException() const override;
- std::string tryTranslators() const;
-
- private:
- std::vector<std::unique_ptr<IExceptionTranslator const>> m_translators;
- };
-}
-
-// end catch_exception_translator_registry.h
-#ifdef __OBJC__
-#import "Foundation/Foundation.h"
-#endif
-
-namespace Catch {
-
- ExceptionTranslatorRegistry::~ExceptionTranslatorRegistry() {
- }
-
- void ExceptionTranslatorRegistry::registerTranslator( const IExceptionTranslator* translator ) {
- m_translators.push_back( std::unique_ptr<const IExceptionTranslator>( translator ) );
- }
-
- std::string ExceptionTranslatorRegistry::translateActiveException() const {
- try {
-#ifdef __OBJC__
- // In Objective-C try objective-c exceptions first
- @try {
- return tryTranslators();
- }
- @catch (NSException *exception) {
- return Catch::Detail::stringify( [exception description] );
- }
-#else
- return tryTranslators();
-#endif
- }
- catch( TestFailureException& ) {
- std::rethrow_exception(std::current_exception());
- }
- catch( std::exception& ex ) {
- return ex.what();
- }
- catch( std::string& msg ) {
- return msg;
- }
- catch( const char* msg ) {
- return msg;
- }
- catch(...) {
- return "Unknown exception";
- }
- }
-
- std::string ExceptionTranslatorRegistry::tryTranslators() const {
- if( m_translators.empty() )
- std::rethrow_exception(std::current_exception());
- else
- return m_translators[0]->translate( m_translators.begin()+1, m_translators.end() );
- }
-}
-// end catch_exception_translator_registry.cpp
-// start catch_fatal_condition.cpp
-
-// start catch_fatal_condition.h
-
-#include <string>
-
-#if defined ( CATCH_PLATFORM_WINDOWS ) /////////////////////////////////////////
-
-# if !defined ( CATCH_CONFIG_WINDOWS_SEH )
-
-namespace Catch {
- struct FatalConditionHandler {
- void reset();
- };
-}
-
-# else // CATCH_CONFIG_WINDOWS_SEH is defined
-
-namespace Catch {
-
- struct FatalConditionHandler {
-
- static LONG CALLBACK handleVectoredException(PEXCEPTION_POINTERS ExceptionInfo);
- FatalConditionHandler();
- static void reset();
- ~FatalConditionHandler();
-
- private:
- static bool isSet;
- static ULONG guaranteeSize;
- static PVOID exceptionHandlerHandle;
- };
-
-} // namespace Catch
-
-# endif // CATCH_CONFIG_WINDOWS_SEH
-
-#else // Not Windows - assumed to be POSIX compatible //////////////////////////
-
-# if !defined(CATCH_CONFIG_POSIX_SIGNALS)
-
-namespace Catch {
- struct FatalConditionHandler {
- void reset();
- };
-}
-
-# else // CATCH_CONFIG_POSIX_SIGNALS is defined
-
-#include <signal.h>
-
-namespace Catch {
-
- struct FatalConditionHandler {
-
- static bool isSet;
- static struct sigaction oldSigActions[];// [sizeof(signalDefs) / sizeof(SignalDefs)];
- static stack_t oldSigStack;
- static char altStackMem[];
-
- static void handleSignal( int sig );
-
- FatalConditionHandler();
- ~FatalConditionHandler();
- static void reset();
- };
-
-} // namespace Catch
-
-# endif // CATCH_CONFIG_POSIX_SIGNALS
-
-#endif // not Windows
-
-// end catch_fatal_condition.h
-namespace {
- // Report the error condition
- void reportFatal( char const * const message ) {
- Catch::getCurrentContext().getResultCapture()->handleFatalErrorCondition( message );
- }
-}
-
-#if defined ( CATCH_PLATFORM_WINDOWS ) /////////////////////////////////////////
-
-# if !defined ( CATCH_CONFIG_WINDOWS_SEH )
-
-namespace Catch {
- void FatalConditionHandler::reset() {}
-}
-
-# else // CATCH_CONFIG_WINDOWS_SEH is defined
-
-namespace Catch {
- struct SignalDefs { DWORD id; const char* name; };
-
- // There is no 1-1 mapping between signals and windows exceptions.
- // Windows can easily distinguish between SO and SigSegV,
- // but SigInt, SigTerm, etc are handled differently.
- static SignalDefs signalDefs[] = {
- { EXCEPTION_ILLEGAL_INSTRUCTION, "SIGILL - Illegal instruction signal" },
- { EXCEPTION_STACK_OVERFLOW, "SIGSEGV - Stack overflow" },
- { EXCEPTION_ACCESS_VIOLATION, "SIGSEGV - Segmentation violation signal" },
- { EXCEPTION_INT_DIVIDE_BY_ZERO, "Divide by zero error" },
- };
-
- LONG CALLBACK FatalConditionHandler::handleVectoredException(PEXCEPTION_POINTERS ExceptionInfo) {
- for (auto const& def : signalDefs) {
- if (ExceptionInfo->ExceptionRecord->ExceptionCode == def.id) {
- reportFatal(def.name);
- }
- }
- // If its not an exception we care about, pass it along.
- // This stops us from eating debugger breaks etc.
- return EXCEPTION_CONTINUE_SEARCH;
- }
-
- FatalConditionHandler::FatalConditionHandler() {
- isSet = true;
- // 32k seems enough for Catch to handle stack overflow,
- // but the value was found experimentally, so there is no strong guarantee
- guaranteeSize = 32 * 1024;
- exceptionHandlerHandle = nullptr;
- // Register as first handler in current chain
- exceptionHandlerHandle = AddVectoredExceptionHandler(1, handleVectoredException);
- // Pass in guarantee size to be filled
- SetThreadStackGuarantee(&guaranteeSize);
- }
-
- void FatalConditionHandler::reset() {
- if (isSet) {
- // Unregister handler and restore the old guarantee
- RemoveVectoredExceptionHandler(exceptionHandlerHandle);
- SetThreadStackGuarantee(&guaranteeSize);
- exceptionHandlerHandle = nullptr;
- isSet = false;
- }
- }
-
- FatalConditionHandler::~FatalConditionHandler() {
- reset();
- }
-
-bool FatalConditionHandler::isSet = false;
-ULONG FatalConditionHandler::guaranteeSize = 0;
-PVOID FatalConditionHandler::exceptionHandlerHandle = nullptr;
-
-} // namespace Catch
-
-# endif // CATCH_CONFIG_WINDOWS_SEH
-
-#else // Not Windows - assumed to be POSIX compatible //////////////////////////
-
-# if !defined(CATCH_CONFIG_POSIX_SIGNALS)
-
-namespace Catch {
- void FatalConditionHandler::reset() {}
-}
-
-# else // CATCH_CONFIG_POSIX_SIGNALS is defined
-
-#include <signal.h>
-
-namespace Catch {
-
- struct SignalDefs {
- int id;
- const char* name;
- };
- static SignalDefs signalDefs[] = {
- { SIGINT, "SIGINT - Terminal interrupt signal" },
- { SIGILL, "SIGILL - Illegal instruction signal" },
- { SIGFPE, "SIGFPE - Floating point error signal" },
- { SIGSEGV, "SIGSEGV - Segmentation violation signal" },
- { SIGTERM, "SIGTERM - Termination request signal" },
- { SIGABRT, "SIGABRT - Abort (abnormal termination) signal" }
- };
-
- void FatalConditionHandler::handleSignal( int sig ) {
- char const * name = "<unknown signal>";
- for (auto const& def : signalDefs) {
- if (sig == def.id) {
- name = def.name;
- break;
- }
- }
- reset();
- reportFatal(name);
- raise( sig );
- }
-
- FatalConditionHandler::FatalConditionHandler() {
- isSet = true;
- stack_t sigStack;
- sigStack.ss_sp = altStackMem;
- sigStack.ss_size = SIGSTKSZ;
- sigStack.ss_flags = 0;
- sigaltstack(&sigStack, &oldSigStack);
- struct sigaction sa = { };
-
- sa.sa_handler = handleSignal;
- sa.sa_flags = SA_ONSTACK;
- for (std::size_t i = 0; i < sizeof(signalDefs)/sizeof(SignalDefs); ++i) {
- sigaction(signalDefs[i].id, &sa, &oldSigActions[i]);
- }
- }
-
- FatalConditionHandler::~FatalConditionHandler() {
- reset();
- }
-
- void FatalConditionHandler::reset() {
- if( isSet ) {
- // Set signals back to previous values -- hopefully nobody overwrote them in the meantime
- for( std::size_t i = 0; i < sizeof(signalDefs)/sizeof(SignalDefs); ++i ) {
- sigaction(signalDefs[i].id, &oldSigActions[i], nullptr);
- }
- // Return the old stack
- sigaltstack(&oldSigStack, nullptr);
- isSet = false;
- }
- }
-
- bool FatalConditionHandler::isSet = false;
- struct sigaction FatalConditionHandler::oldSigActions[sizeof(signalDefs)/sizeof(SignalDefs)] = {};
- stack_t FatalConditionHandler::oldSigStack = {};
- char FatalConditionHandler::altStackMem[SIGSTKSZ] = {};
-
-} // namespace Catch
-
-# endif // CATCH_CONFIG_POSIX_SIGNALS
-
-#endif // not Windows
-// end catch_fatal_condition.cpp
-// start catch_interfaces_capture.cpp
-
-namespace Catch {
- IResultCapture::~IResultCapture() = default;
-}
-// end catch_interfaces_capture.cpp
-// start catch_interfaces_config.cpp
-
-namespace Catch {
- IConfig::~IConfig() = default;
-}
-// end catch_interfaces_config.cpp
-// start catch_interfaces_exception.cpp
-
-namespace Catch {
- IExceptionTranslator::~IExceptionTranslator() = default;
- IExceptionTranslatorRegistry::~IExceptionTranslatorRegistry() = default;
-}
-// end catch_interfaces_exception.cpp
-// start catch_interfaces_registry_hub.cpp
-
-namespace Catch {
- IRegistryHub::~IRegistryHub() = default;
- IMutableRegistryHub::~IMutableRegistryHub() = default;
-}
-// end catch_interfaces_registry_hub.cpp
-// start catch_interfaces_reporter.cpp
-
-// start catch_reporter_multi.h
-
-namespace Catch {
-
- class MultipleReporters : public IStreamingReporter {
- using Reporters = std::vector<IStreamingReporterPtr>;
- Reporters m_reporters;
-
- public:
- void add( IStreamingReporterPtr&& reporter );
-
- public: // IStreamingReporter
-
- ReporterPreferences getPreferences() const override;
-
- void noMatchingTestCases( std::string const& spec ) override;
-
- static std::set<Verbosity> getSupportedVerbosities();
-
- void benchmarkStarting( BenchmarkInfo const& benchmarkInfo ) override;
- void benchmarkEnded( BenchmarkStats const& benchmarkStats ) override;
-
- void testRunStarting( TestRunInfo const& testRunInfo ) override;
- void testGroupStarting( GroupInfo const& groupInfo ) override;
- void testCaseStarting( TestCaseInfo const& testInfo ) override;
- void sectionStarting( SectionInfo const& sectionInfo ) override;
- void assertionStarting( AssertionInfo const& assertionInfo ) override;
-
- // The return value indicates if the messages buffer should be cleared:
- bool assertionEnded( AssertionStats const& assertionStats ) override;
- void sectionEnded( SectionStats const& sectionStats ) override;
- void testCaseEnded( TestCaseStats const& testCaseStats ) override;
- void testGroupEnded( TestGroupStats const& testGroupStats ) override;
- void testRunEnded( TestRunStats const& testRunStats ) override;
-
- void skipTest( TestCaseInfo const& testInfo ) override;
- bool isMulti() const override;
-
- };
-
-} // end namespace Catch
-
-// end catch_reporter_multi.h
-namespace Catch {
-
- ReporterConfig::ReporterConfig( IConfigPtr const& _fullConfig )
- : m_stream( &_fullConfig->stream() ), m_fullConfig( _fullConfig ) {}
-
- ReporterConfig::ReporterConfig( IConfigPtr const& _fullConfig, std::ostream& _stream )
- : m_stream( &_stream ), m_fullConfig( _fullConfig ) {}
-
- std::ostream& ReporterConfig::stream() const { return *m_stream; }
- IConfigPtr ReporterConfig::fullConfig() const { return m_fullConfig; }
-
- TestRunInfo::TestRunInfo( std::string const& _name ) : name( _name ) {}
-
- GroupInfo::GroupInfo( std::string const& _name,
- std::size_t _groupIndex,
- std::size_t _groupsCount )
- : name( _name ),
- groupIndex( _groupIndex ),
- groupsCounts( _groupsCount )
- {}
-
- AssertionStats::AssertionStats( AssertionResult const& _assertionResult,
- std::vector<MessageInfo> const& _infoMessages,
- Totals const& _totals )
- : assertionResult( _assertionResult ),
- infoMessages( _infoMessages ),
- totals( _totals )
- {
- assertionResult.m_resultData.lazyExpression.m_transientExpression = _assertionResult.m_resultData.lazyExpression.m_transientExpression;
-
- if( assertionResult.hasMessage() ) {
- // Copy message into messages list.
- // !TBD This should have been done earlier, somewhere
- MessageBuilder builder( assertionResult.getTestMacroName(), assertionResult.getSourceInfo(), assertionResult.getResultType() );
- builder << assertionResult.getMessage();
- builder.m_info.message = builder.m_stream.str();
-
- infoMessages.push_back( builder.m_info );
- }
- }
-
- AssertionStats::~AssertionStats() = default;
-
- SectionStats::SectionStats( SectionInfo const& _sectionInfo,
- Counts const& _assertions,
- double _durationInSeconds,
- bool _missingAssertions )
- : sectionInfo( _sectionInfo ),
- assertions( _assertions ),
- durationInSeconds( _durationInSeconds ),
- missingAssertions( _missingAssertions )
- {}
-
- SectionStats::~SectionStats() = default;
-
- TestCaseStats::TestCaseStats( TestCaseInfo const& _testInfo,
- Totals const& _totals,
- std::string const& _stdOut,
- std::string const& _stdErr,
- bool _aborting )
- : testInfo( _testInfo ),
- totals( _totals ),
- stdOut( _stdOut ),
- stdErr( _stdErr ),
- aborting( _aborting )
- {}
-
- TestCaseStats::~TestCaseStats() = default;
-
- TestGroupStats::TestGroupStats( GroupInfo const& _groupInfo,
- Totals const& _totals,
- bool _aborting )
- : groupInfo( _groupInfo ),
- totals( _totals ),
- aborting( _aborting )
- {}
-
- TestGroupStats::TestGroupStats( GroupInfo const& _groupInfo )
- : groupInfo( _groupInfo ),
- aborting( false )
- {}
-
- TestGroupStats::~TestGroupStats() = default;
-
- TestRunStats::TestRunStats( TestRunInfo const& _runInfo,
- Totals const& _totals,
- bool _aborting )
- : runInfo( _runInfo ),
- totals( _totals ),
- aborting( _aborting )
- {}
-
- TestRunStats::~TestRunStats() = default;
-
- void IStreamingReporter::fatalErrorEncountered( StringRef ) {}
- bool IStreamingReporter::isMulti() const { return false; }
-
- IReporterFactory::~IReporterFactory() = default;
- IReporterRegistry::~IReporterRegistry() = default;
-
- void addReporter( IStreamingReporterPtr& existingReporter, IStreamingReporterPtr&& additionalReporter ) {
-
- if( !existingReporter ) {
- existingReporter = std::move( additionalReporter );
- return;
- }
-
- MultipleReporters* multi = nullptr;
-
- if( existingReporter->isMulti() ) {
- multi = static_cast<MultipleReporters*>( existingReporter.get() );
- }
- else {
- auto newMulti = std::unique_ptr<MultipleReporters>( new MultipleReporters );
- newMulti->add( std::move( existingReporter ) );
- multi = newMulti.get();
- existingReporter = std::move( newMulti );
- }
- multi->add( std::move( additionalReporter ) );
- }
-
-} // end namespace Catch
-// end catch_interfaces_reporter.cpp
-// start catch_interfaces_runner.cpp
-
-namespace Catch {
- IRunner::~IRunner() = default;
-}
-// end catch_interfaces_runner.cpp
-// start catch_interfaces_testcase.cpp
-
-namespace Catch {
- ITestInvoker::~ITestInvoker() = default;
- ITestCaseRegistry::~ITestCaseRegistry() = default;
-}
-// end catch_interfaces_testcase.cpp
-// start catch_leak_detector.cpp
-
-namespace Catch {
-
-#ifdef CATCH_CONFIG_WINDOWS_CRTDBG
-#include <crtdbg.h>
-
- LeakDetector::LeakDetector() {
- int flag = _CrtSetDbgFlag(_CRTDBG_REPORT_FLAG);
- flag |= _CRTDBG_LEAK_CHECK_DF;
- flag |= _CRTDBG_ALLOC_MEM_DF;
- _CrtSetDbgFlag(flag);
- _CrtSetReportMode(_CRT_WARN, _CRTDBG_MODE_FILE | _CRTDBG_MODE_DEBUG);
- _CrtSetReportFile(_CRT_WARN, _CRTDBG_FILE_STDERR);
- // Change this to leaking allocation's number to break there
- _CrtSetBreakAlloc(-1);
- }
-
-#else
-
- LeakDetector::LeakDetector(){}
-
-#endif
-
-}
-// end catch_leak_detector.cpp
-// start catch_list.cpp
-
-// start catch_list.h
-
-#include <set>
-
-namespace Catch {
-
- std::size_t listTests( Config const& config );
-
- std::size_t listTestsNamesOnly( Config const& config );
-
- struct TagInfo {
- void add( std::string const& spelling );
- std::string all() const;
-
- std::set<std::string> spellings;
- std::size_t count = 0;
- };
-
- std::size_t listTags( Config const& config );
-
- std::size_t listReporters( Config const& /*config*/ );
-
- Option<std::size_t> list( Config const& config );
-
-} // end namespace Catch
-
-// end catch_list.h
-// start catch_text.h
-
-namespace Catch {
- using namespace clara::TextFlow;
-}
-
-// end catch_text.h
-#include <limits>
-#include <algorithm>
-#include <iomanip>
-
-namespace Catch {
-
- std::size_t listTests( Config const& config ) {
- TestSpec testSpec = config.testSpec();
- if( config.testSpec().hasFilters() )
- Catch::cout() << "Matching test cases:\n";
- else {
- Catch::cout() << "All available test cases:\n";
- testSpec = TestSpecParser( ITagAliasRegistry::get() ).parse( "*" ).testSpec();
- }
-
- auto matchedTestCases = filterTests( getAllTestCasesSorted( config ), testSpec, config );
- for( auto const& testCaseInfo : matchedTestCases ) {
- Colour::Code colour = testCaseInfo.isHidden()
- ? Colour::SecondaryText
- : Colour::None;
- Colour colourGuard( colour );
-
- Catch::cout() << Column( testCaseInfo.name ).initialIndent( 2 ).indent( 4 ) << "\n";
- if( config.verbosity() >= Verbosity::High ) {
- Catch::cout() << Column( Catch::Detail::stringify( testCaseInfo.lineInfo ) ).indent(4) << std::endl;
- std::string description = testCaseInfo.description;
- if( description.empty() )
- description = "(NO DESCRIPTION)";
- Catch::cout() << Column( description ).indent(4) << std::endl;
- }
- if( !testCaseInfo.tags.empty() )
- Catch::cout() << Column( testCaseInfo.tagsAsString() ).indent( 6 ) << "\n";
- }
-
- if( !config.testSpec().hasFilters() )
- Catch::cout() << pluralise( matchedTestCases.size(), "test case" ) << '\n' << std::endl;
- else
- Catch::cout() << pluralise( matchedTestCases.size(), "matching test case" ) << '\n' << std::endl;
- return matchedTestCases.size();
- }
-
- std::size_t listTestsNamesOnly( Config const& config ) {
- TestSpec testSpec = config.testSpec();
- if( !config.testSpec().hasFilters() )
- testSpec = TestSpecParser( ITagAliasRegistry::get() ).parse( "*" ).testSpec();
- std::size_t matchedTests = 0;
- std::vector<TestCase> matchedTestCases = filterTests( getAllTestCasesSorted( config ), testSpec, config );
- for( auto const& testCaseInfo : matchedTestCases ) {
- matchedTests++;
- if( startsWith( testCaseInfo.name, '#' ) )
- Catch::cout() << '"' << testCaseInfo.name << '"';
- else
- Catch::cout() << testCaseInfo.name;
- if ( config.verbosity() >= Verbosity::High )
- Catch::cout() << "\t@" << testCaseInfo.lineInfo;
- Catch::cout() << std::endl;
- }
- return matchedTests;
- }
-
- void TagInfo::add( std::string const& spelling ) {
- ++count;
- spellings.insert( spelling );
- }
-
- std::string TagInfo::all() const {
- std::string out;
- for( auto const& spelling : spellings )
- out += "[" + spelling + "]";
- return out;
- }
-
- std::size_t listTags( Config const& config ) {
- TestSpec testSpec = config.testSpec();
- if( config.testSpec().hasFilters() )
- Catch::cout() << "Tags for matching test cases:\n";
- else {
- Catch::cout() << "All available tags:\n";
- testSpec = TestSpecParser( ITagAliasRegistry::get() ).parse( "*" ).testSpec();
- }
-
- std::map<std::string, TagInfo> tagCounts;
-
- std::vector<TestCase> matchedTestCases = filterTests( getAllTestCasesSorted( config ), testSpec, config );
- for( auto const& testCase : matchedTestCases ) {
- for( auto const& tagName : testCase.getTestCaseInfo().tags ) {
- std::string lcaseTagName = toLower( tagName );
- auto countIt = tagCounts.find( lcaseTagName );
- if( countIt == tagCounts.end() )
- countIt = tagCounts.insert( std::make_pair( lcaseTagName, TagInfo() ) ).first;
- countIt->second.add( tagName );
- }
- }
-
- for( auto const& tagCount : tagCounts ) {
- std::ostringstream oss;
- oss << " " << std::setw(2) << tagCount.second.count << " ";
- auto wrapper = Column( tagCount.second.all() )
- .initialIndent( 0 )
- .indent( oss.str().size() )
- .width( CATCH_CONFIG_CONSOLE_WIDTH-10 );
- Catch::cout() << oss.str() << wrapper << '\n';
- }
- Catch::cout() << pluralise( tagCounts.size(), "tag" ) << '\n' << std::endl;
- return tagCounts.size();
- }
-
- std::size_t listReporters( Config const& /*config*/ ) {
- Catch::cout() << "Available reporters:\n";
- IReporterRegistry::FactoryMap const& factories = getRegistryHub().getReporterRegistry().getFactories();
- std::size_t maxNameLen = 0;
- for( auto const& factoryKvp : factories )
- maxNameLen = (std::max)( maxNameLen, factoryKvp.first.size() );
-
- for( auto const& factoryKvp : factories ) {
- Catch::cout()
- << Column( factoryKvp.first + ":" )
- .indent(2)
- .width( 5+maxNameLen )
- + Column( factoryKvp.second->getDescription() )
- .initialIndent(0)
- .indent(2)
- .width( CATCH_CONFIG_CONSOLE_WIDTH - maxNameLen-8 )
- << "\n";
- }
- Catch::cout() << std::endl;
- return factories.size();
- }
-
- Option<std::size_t> list( Config const& config ) {
- Option<std::size_t> listedCount;
- if( config.listTests() )
- listedCount = listedCount.valueOr(0) + listTests( config );
- if( config.listTestNamesOnly() )
- listedCount = listedCount.valueOr(0) + listTestsNamesOnly( config );
- if( config.listTags() )
- listedCount = listedCount.valueOr(0) + listTags( config );
- if( config.listReporters() )
- listedCount = listedCount.valueOr(0) + listReporters( config );
- return listedCount;
- }
-
-} // end namespace Catch
-// end catch_list.cpp
-// start catch_matchers.cpp
-
-namespace Catch {
-namespace Matchers {
- namespace Impl {
-
- std::string MatcherUntypedBase::toString() const {
- if( m_cachedToString.empty() )
- m_cachedToString = describe();
- return m_cachedToString;
- }
-
- MatcherUntypedBase::~MatcherUntypedBase() = default;
-
- } // namespace Impl
-} // namespace Matchers
-
-using namespace Matchers;
-using Matchers::Impl::MatcherBase;
-
-} // namespace Catch
-// end catch_matchers.cpp
-// start catch_matchers_string.cpp
-
-namespace Catch {
-namespace Matchers {
-
- namespace StdString {
-
- CasedString::CasedString( std::string const& str, CaseSensitive::Choice caseSensitivity )
- : m_caseSensitivity( caseSensitivity ),
- m_str( adjustString( str ) )
- {}
- std::string CasedString::adjustString( std::string const& str ) const {
- return m_caseSensitivity == CaseSensitive::No
- ? toLower( str )
- : str;
- }
- std::string CasedString::caseSensitivitySuffix() const {
- return m_caseSensitivity == CaseSensitive::No
- ? " (case insensitive)"
- : std::string();
- }
-
- StringMatcherBase::StringMatcherBase( std::string const& operation, CasedString const& comparator )
- : m_comparator( comparator ),
- m_operation( operation ) {
- }
-
- std::string StringMatcherBase::describe() const {
- std::string description;
- description.reserve(5 + m_operation.size() + m_comparator.m_str.size() +
- m_comparator.caseSensitivitySuffix().size());
- description += m_operation;
- description += ": \"";
- description += m_comparator.m_str;
- description += "\"";
- description += m_comparator.caseSensitivitySuffix();
- return description;
- }
-
- EqualsMatcher::EqualsMatcher( CasedString const& comparator ) : StringMatcherBase( "equals", comparator ) {}
-
- bool EqualsMatcher::match( std::string const& source ) const {
- return m_comparator.adjustString( source ) == m_comparator.m_str;
- }
-
- ContainsMatcher::ContainsMatcher( CasedString const& comparator ) : StringMatcherBase( "contains", comparator ) {}
-
- bool ContainsMatcher::match( std::string const& source ) const {
- return contains( m_comparator.adjustString( source ), m_comparator.m_str );
- }
-
- StartsWithMatcher::StartsWithMatcher( CasedString const& comparator ) : StringMatcherBase( "starts with", comparator ) {}
-
- bool StartsWithMatcher::match( std::string const& source ) const {
- return startsWith( m_comparator.adjustString( source ), m_comparator.m_str );
- }
-
- EndsWithMatcher::EndsWithMatcher( CasedString const& comparator ) : StringMatcherBase( "ends with", comparator ) {}
-
- bool EndsWithMatcher::match( std::string const& source ) const {
- return endsWith( m_comparator.adjustString( source ), m_comparator.m_str );
- }
-
- } // namespace StdString
-
- StdString::EqualsMatcher Equals( std::string const& str, CaseSensitive::Choice caseSensitivity ) {
- return StdString::EqualsMatcher( StdString::CasedString( str, caseSensitivity) );
- }
- StdString::ContainsMatcher Contains( std::string const& str, CaseSensitive::Choice caseSensitivity ) {
- return StdString::ContainsMatcher( StdString::CasedString( str, caseSensitivity) );
- }
- StdString::EndsWithMatcher EndsWith( std::string const& str, CaseSensitive::Choice caseSensitivity ) {
- return StdString::EndsWithMatcher( StdString::CasedString( str, caseSensitivity) );
- }
- StdString::StartsWithMatcher StartsWith( std::string const& str, CaseSensitive::Choice caseSensitivity ) {
- return StdString::StartsWithMatcher( StdString::CasedString( str, caseSensitivity) );
- }
-
-} // namespace Matchers
-} // namespace Catch
-// end catch_matchers_string.cpp
-// start catch_message.cpp
-
-namespace Catch {
-
- MessageInfo::MessageInfo( std::string const& _macroName,
- SourceLineInfo const& _lineInfo,
- ResultWas::OfType _type )
- : macroName( _macroName ),
- lineInfo( _lineInfo ),
- type( _type ),
- sequence( ++globalCount )
- {}
-
- bool MessageInfo::operator==( MessageInfo const& other ) const {
- return sequence == other.sequence;
- }
-
- bool MessageInfo::operator<( MessageInfo const& other ) const {
- return sequence < other.sequence;
- }
-
- // This may need protecting if threading support is added
- unsigned int MessageInfo::globalCount = 0;
-
- ////////////////////////////////////////////////////////////////////////////
-
- Catch::MessageBuilder::MessageBuilder( std::string const& macroName,
- SourceLineInfo const& lineInfo,
- ResultWas::OfType type )
- :m_info(macroName, lineInfo, type) {}
-
- ////////////////////////////////////////////////////////////////////////////
-
- ScopedMessage::ScopedMessage( MessageBuilder const& builder )
- : m_info( builder.m_info )
- {
- m_info.message = builder.m_stream.str();
- getResultCapture().pushScopedMessage( m_info );
- }
-
- ScopedMessage::~ScopedMessage() {
- if ( !std::uncaught_exception() ){
- getResultCapture().popScopedMessage(m_info);
- }
- }
-
-} // end namespace Catch
-// end catch_message.cpp
-// start catch_random_number_generator.cpp
-
-// start catch_random_number_generator.h
-
-#include <algorithm>
-
-namespace Catch {
-
- struct IConfig;
-
- void seedRng( IConfig const& config );
-
- unsigned int rngSeed();
-
- struct RandomNumberGenerator {
- using result_type = unsigned int;
-
- static constexpr result_type (min)() { return 0; }
- static constexpr result_type (max)() { return 1000000; }
-
- result_type operator()( result_type n ) const;
- result_type operator()() const;
-
- template<typename V>
- static void shuffle( V& vector ) {
- RandomNumberGenerator rng;
- std::shuffle( vector.begin(), vector.end(), rng );
- }
- };
-
-}
-
-// end catch_random_number_generator.h
-#include <cstdlib>
-
-namespace Catch {
-
- void seedRng( IConfig const& config ) {
- if( config.rngSeed() != 0 )
- std::srand( config.rngSeed() );
- }
- unsigned int rngSeed() {
- return getCurrentContext().getConfig()->rngSeed();
- }
-
- RandomNumberGenerator::result_type RandomNumberGenerator::operator()( result_type n ) const {
- return std::rand() % n;
- }
- RandomNumberGenerator::result_type RandomNumberGenerator::operator()() const {
- return std::rand() % (max)();
- }
-
-}
-// end catch_random_number_generator.cpp
-// start catch_registry_hub.cpp
-
-// start catch_test_case_registry_impl.h
-
-#include <vector>
-#include <set>
-#include <algorithm>
-#include <ios>
-
-namespace Catch {
-
- class TestCase;
- struct IConfig;
-
- std::vector<TestCase> sortTests( IConfig const& config, std::vector<TestCase> const& unsortedTestCases );
- bool matchTest( TestCase const& testCase, TestSpec const& testSpec, IConfig const& config );
-
- void enforceNoDuplicateTestCases( std::vector<TestCase> const& functions );
-
- std::vector<TestCase> filterTests( std::vector<TestCase> const& testCases, TestSpec const& testSpec, IConfig const& config );
- std::vector<TestCase> const& getAllTestCasesSorted( IConfig const& config );
-
- class TestRegistry : public ITestCaseRegistry {
- public:
- virtual ~TestRegistry() = default;
-
- virtual void registerTest( TestCase const& testCase );
-
- std::vector<TestCase> const& getAllTests() const override;
- std::vector<TestCase> const& getAllTestsSorted( IConfig const& config ) const override;
-
- private:
- std::vector<TestCase> m_functions;
- mutable RunTests::InWhatOrder m_currentSortOrder = RunTests::InDeclarationOrder;
- mutable std::vector<TestCase> m_sortedFunctions;
- std::size_t m_unnamedCount = 0;
- std::ios_base::Init m_ostreamInit; // Forces cout/ cerr to be initialised
- };
-
- ///////////////////////////////////////////////////////////////////////////
-
- class TestInvokerAsFunction : public ITestInvoker {
- void(*m_testAsFunction)();
- public:
- TestInvokerAsFunction( void(*testAsFunction)() ) noexcept;
-
- void invoke() const override;
- };
-
- std::string extractClassName( std::string const& classOrQualifiedMethodName );
-
- ///////////////////////////////////////////////////////////////////////////
-
-} // end namespace Catch
-
-// end catch_test_case_registry_impl.h
-// start catch_reporter_registry.h
-
-#include <map>
-
-namespace Catch {
-
- class ReporterRegistry : public IReporterRegistry {
-
- public:
-
- ~ReporterRegistry() override;
-
- IStreamingReporterPtr create( std::string const& name, IConfigPtr const& config ) const override;
-
- void registerReporter( std::string const& name, IReporterFactoryPtr const& factory );
- void registerListener( IReporterFactoryPtr const& factory );
-
- FactoryMap const& getFactories() const override;
- Listeners const& getListeners() const override;
-
- private:
- FactoryMap m_factories;
- Listeners m_listeners;
- };
-}
-
-// end catch_reporter_registry.h
-// start catch_tag_alias_registry.h
-
-// start catch_tag_alias.h
-
-#include <string>
-
-namespace Catch {
-
- struct TagAlias {
- TagAlias(std::string const& _tag, SourceLineInfo _lineInfo);
-
- std::string tag;
- SourceLineInfo lineInfo;
- };
-
-} // end namespace Catch
-
-// end catch_tag_alias.h
-#include <map>
-
-namespace Catch {
-
- class TagAliasRegistry : public ITagAliasRegistry {
- public:
- ~TagAliasRegistry() override;
- TagAlias const* find( std::string const& alias ) const override;
- std::string expandAliases( std::string const& unexpandedTestSpec ) const override;
- void add( std::string const& alias, std::string const& tag, SourceLineInfo const& lineInfo );
-
- private:
- std::map<std::string, TagAlias> m_registry;
- };
-
-} // end namespace Catch
-
-// end catch_tag_alias_registry.h
-// start catch_startup_exception_registry.h
-
-#include <vector>
-#include <exception>
-
-namespace Catch {
-
- class StartupExceptionRegistry {
- public:
- void add(std::exception_ptr const& exception) noexcept;
- std::vector<std::exception_ptr> const& getExceptions() const noexcept;
- private:
- std::vector<std::exception_ptr> m_exceptions;
- };
-
-} // end namespace Catch
-
-// end catch_startup_exception_registry.h
-namespace Catch {
-
- namespace {
-
- class RegistryHub : public IRegistryHub, public IMutableRegistryHub,
- private NonCopyable {
-
- public: // IRegistryHub
- RegistryHub() = default;
- IReporterRegistry const& getReporterRegistry() const override {
- return m_reporterRegistry;
- }
- ITestCaseRegistry const& getTestCaseRegistry() const override {
- return m_testCaseRegistry;
- }
- IExceptionTranslatorRegistry& getExceptionTranslatorRegistry() override {
- return m_exceptionTranslatorRegistry;
- }
- ITagAliasRegistry const& getTagAliasRegistry() const override {
- return m_tagAliasRegistry;
- }
- StartupExceptionRegistry const& getStartupExceptionRegistry() const override {
- return m_exceptionRegistry;
- }
-
- public: // IMutableRegistryHub
- void registerReporter( std::string const& name, IReporterFactoryPtr const& factory ) override {
- m_reporterRegistry.registerReporter( name, factory );
- }
- void registerListener( IReporterFactoryPtr const& factory ) override {
- m_reporterRegistry.registerListener( factory );
- }
- void registerTest( TestCase const& testInfo ) override {
- m_testCaseRegistry.registerTest( testInfo );
- }
- void registerTranslator( const IExceptionTranslator* translator ) override {
- m_exceptionTranslatorRegistry.registerTranslator( translator );
- }
- void registerTagAlias( std::string const& alias, std::string const& tag, SourceLineInfo const& lineInfo ) override {
- m_tagAliasRegistry.add( alias, tag, lineInfo );
- }
- void registerStartupException() noexcept override {
- m_exceptionRegistry.add(std::current_exception());
- }
-
- private:
- TestRegistry m_testCaseRegistry;
- ReporterRegistry m_reporterRegistry;
- ExceptionTranslatorRegistry m_exceptionTranslatorRegistry;
- TagAliasRegistry m_tagAliasRegistry;
- StartupExceptionRegistry m_exceptionRegistry;
- };
-
- // Single, global, instance
- RegistryHub*& getTheRegistryHub() {
- static RegistryHub* theRegistryHub = nullptr;
- if( !theRegistryHub )
- theRegistryHub = new RegistryHub();
- return theRegistryHub;
- }
- }
-
- IRegistryHub& getRegistryHub() {
- return *getTheRegistryHub();
- }
- IMutableRegistryHub& getMutableRegistryHub() {
- return *getTheRegistryHub();
- }
- void cleanUp() {
- delete getTheRegistryHub();
- getTheRegistryHub() = nullptr;
- cleanUpContext();
- }
- std::string translateActiveException() {
- return getRegistryHub().getExceptionTranslatorRegistry().translateActiveException();
- }
-
-} // end namespace Catch
-// end catch_registry_hub.cpp
-// start catch_reporter_registry.cpp
-
-namespace Catch {
-
- ReporterRegistry::~ReporterRegistry() = default;
-
- IStreamingReporterPtr ReporterRegistry::create( std::string const& name, IConfigPtr const& config ) const {
- auto it = m_factories.find( name );
- if( it == m_factories.end() )
- return nullptr;
- return it->second->create( ReporterConfig( config ) );
- }
-
- void ReporterRegistry::registerReporter( std::string const& name, IReporterFactoryPtr const& factory ) {
- m_factories.emplace(name, factory);
- }
- void ReporterRegistry::registerListener( IReporterFactoryPtr const& factory ) {
- m_listeners.push_back( factory );
- }
-
- IReporterRegistry::FactoryMap const& ReporterRegistry::getFactories() const {
- return m_factories;
- }
- IReporterRegistry::Listeners const& ReporterRegistry::getListeners() const {
- return m_listeners;
- }
-
-}
-// end catch_reporter_registry.cpp
-// start catch_result_type.cpp
-
-namespace Catch {
-
- bool isOk( ResultWas::OfType resultType ) {
- return ( resultType & ResultWas::FailureBit ) == 0;
- }
- bool isJustInfo( int flags ) {
- return flags == ResultWas::Info;
- }
-
- ResultDisposition::Flags operator | ( ResultDisposition::Flags lhs, ResultDisposition::Flags rhs ) {
- return static_cast<ResultDisposition::Flags>( static_cast<int>( lhs ) | static_cast<int>( rhs ) );
- }
-
- bool shouldContinueOnFailure( int flags ) { return ( flags & ResultDisposition::ContinueOnFailure ) != 0; }
- bool isFalseTest( int flags ) { return ( flags & ResultDisposition::FalseTest ) != 0; }
- bool shouldSuppressFailure( int flags ) { return ( flags & ResultDisposition::SuppressFail ) != 0; }
-
-} // end namespace Catch
-// end catch_result_type.cpp
-// start catch_run_context.cpp
-// start catch_run_context.h
-
-#include <string>
-
-namespace Catch {
-
- struct IMutableContext;
-
- class StreamRedirect {
-
- public:
- StreamRedirect(std::ostream& stream, std::string& targetString);
-
- ~StreamRedirect();
-
- private:
- std::ostream& m_stream;
- std::streambuf* m_prevBuf;
- std::ostringstream m_oss;
- std::string& m_targetString;
- };
-
- // StdErr has two constituent streams in C++, std::cerr and std::clog
- // This means that we need to redirect 2 streams into 1 to keep proper
- // order of writes and cannot use StreamRedirect on its own
- class StdErrRedirect {
- public:
- StdErrRedirect(std::string& targetString);
- ~StdErrRedirect();
- private:
- std::streambuf* m_cerrBuf;
- std::streambuf* m_clogBuf;
- std::ostringstream m_oss;
- std::string& m_targetString;
- };
-
- ///////////////////////////////////////////////////////////////////////////
-
- class RunContext : public IResultCapture, public IRunner {
-
- public:
- RunContext( RunContext const& ) = delete;
- RunContext& operator =( RunContext const& ) = delete;
-
- explicit RunContext(IConfigPtr const& _config, IStreamingReporterPtr&& reporter);
-
- virtual ~RunContext();
-
- void testGroupStarting(std::string const& testSpec, std::size_t groupIndex, std::size_t groupsCount);
- void testGroupEnded(std::string const& testSpec, Totals const& totals, std::size_t groupIndex, std::size_t groupsCount);
-
- Totals runTest(TestCase const& testCase);
-
- IConfigPtr config() const;
- IStreamingReporter& reporter() const;
-
- private: // IResultCapture
-
- void assertionStarting(AssertionInfo const& info) override;
- void assertionEnded(AssertionResult const& result) override;
-
- bool sectionStarted( SectionInfo const& sectionInfo, Counts& assertions ) override;
- bool testForMissingAssertions(Counts& assertions);
-
- void sectionEnded(SectionEndInfo const& endInfo) override;
- void sectionEndedEarly(SectionEndInfo const& endInfo) override;
-
- void benchmarkStarting( BenchmarkInfo const& info ) override;
- void benchmarkEnded( BenchmarkStats const& stats ) override;
-
- void pushScopedMessage(MessageInfo const& message) override;
- void popScopedMessage(MessageInfo const& message) override;
-
- std::string getCurrentTestName() const override;
-
- const AssertionResult* getLastResult() const override;
-
- void exceptionEarlyReported() override;
-
- void handleFatalErrorCondition( StringRef message ) override;
-
- bool lastAssertionPassed() override;
-
- void assertionPassed() override;
-
- void assertionRun() override;
-
- public:
- // !TBD We need to do this another way!
- bool aborting() const override;
-
- private:
-
- void runCurrentTest(std::string& redirectedCout, std::string& redirectedCerr);
- void invokeActiveTestCase();
-
- private:
-
- void handleUnfinishedSections();
-
- TestRunInfo m_runInfo;
- IMutableContext& m_context;
- TestCase const* m_activeTestCase = nullptr;
- ITracker* m_testCaseTracker;
- Option<AssertionResult> m_lastResult;
-
- IConfigPtr m_config;
- Totals m_totals;
- IStreamingReporterPtr m_reporter;
- std::vector<MessageInfo> m_messages;
- AssertionInfo m_lastAssertionInfo;
- std::vector<SectionEndInfo> m_unfinishedSections;
- std::vector<ITracker*> m_activeSections;
- TrackerContext m_trackerContext;
- std::size_t m_prevPassed = 0;
- bool m_shouldReportUnexpected = true;
- };
-
- IResultCapture& getResultCapture();
-
-} // end namespace Catch
-
-// end catch_run_context.h
-
-#include <cassert>
-#include <algorithm>
-
-namespace Catch {
-
- StreamRedirect::StreamRedirect(std::ostream& stream, std::string& targetString)
- : m_stream(stream),
- m_prevBuf(stream.rdbuf()),
- m_targetString(targetString) {
- stream.rdbuf(m_oss.rdbuf());
- }
-
- StreamRedirect::~StreamRedirect() {
- m_targetString += m_oss.str();
- m_stream.rdbuf(m_prevBuf);
- }
-
- StdErrRedirect::StdErrRedirect(std::string & targetString)
- :m_cerrBuf(cerr().rdbuf()), m_clogBuf(clog().rdbuf()),
- m_targetString(targetString) {
- cerr().rdbuf(m_oss.rdbuf());
- clog().rdbuf(m_oss.rdbuf());
- }
-
- StdErrRedirect::~StdErrRedirect() {
- m_targetString += m_oss.str();
- cerr().rdbuf(m_cerrBuf);
- clog().rdbuf(m_clogBuf);
- }
-
- RunContext::RunContext(IConfigPtr const& _config, IStreamingReporterPtr&& reporter)
- : m_runInfo(_config->name()),
- m_context(getCurrentMutableContext()),
- m_config(_config),
- m_reporter(std::move(reporter)),
- m_lastAssertionInfo{ "", SourceLineInfo("",0), "", ResultDisposition::Normal }
- {
- m_context.setRunner(this);
- m_context.setConfig(m_config);
- m_context.setResultCapture(this);
- m_reporter->testRunStarting(m_runInfo);
- }
-
- RunContext::~RunContext() {
- m_reporter->testRunEnded(TestRunStats(m_runInfo, m_totals, aborting()));
- }
-
- void RunContext::testGroupStarting(std::string const& testSpec, std::size_t groupIndex, std::size_t groupsCount) {
- m_reporter->testGroupStarting(GroupInfo(testSpec, groupIndex, groupsCount));
- }
-
- void RunContext::testGroupEnded(std::string const& testSpec, Totals const& totals, std::size_t groupIndex, std::size_t groupsCount) {
- m_reporter->testGroupEnded(TestGroupStats(GroupInfo(testSpec, groupIndex, groupsCount), totals, aborting()));
- }
-
- Totals RunContext::runTest(TestCase const& testCase) {
- Totals prevTotals = m_totals;
-
- std::string redirectedCout;
- std::string redirectedCerr;
-
- TestCaseInfo testInfo = testCase.getTestCaseInfo();
-
- m_reporter->testCaseStarting(testInfo);
-
- m_activeTestCase = &testCase;
-
- ITracker& rootTracker = m_trackerContext.startRun();
- assert(rootTracker.isSectionTracker());
- static_cast<SectionTracker&>(rootTracker).addInitialFilters(m_config->getSectionsToRun());
- do {
- m_trackerContext.startCycle();
- m_testCaseTracker = &SectionTracker::acquire(m_trackerContext, TestCaseTracking::NameAndLocation(testInfo.name, testInfo.lineInfo));
- runCurrentTest(redirectedCout, redirectedCerr);
- } while (!m_testCaseTracker->isSuccessfullyCompleted() && !aborting());
-
- Totals deltaTotals = m_totals.delta(prevTotals);
- if (testInfo.expectedToFail() && deltaTotals.testCases.passed > 0) {
- deltaTotals.assertions.failed++;
- deltaTotals.testCases.passed--;
- deltaTotals.testCases.failed++;
- }
- m_totals.testCases += deltaTotals.testCases;
- m_reporter->testCaseEnded(TestCaseStats(testInfo,
- deltaTotals,
- redirectedCout,
- redirectedCerr,
- aborting()));
-
- m_activeTestCase = nullptr;
- m_testCaseTracker = nullptr;
-
- return deltaTotals;
- }
-
- IConfigPtr RunContext::config() const {
- return m_config;
- }
-
- IStreamingReporter& RunContext::reporter() const {
- return *m_reporter;
- }
-
- void RunContext::assertionStarting(AssertionInfo const& info) {
- m_reporter->assertionStarting( info );
- }
- void RunContext::assertionEnded(AssertionResult const & result) {
- if (result.getResultType() == ResultWas::Ok) {
- m_totals.assertions.passed++;
- } else if (!result.isOk()) {
- if( m_activeTestCase->getTestCaseInfo().okToFail() )
- m_totals.assertions.failedButOk++;
- else
- m_totals.assertions.failed++;
- }
-
- // We have no use for the return value (whether messages should be cleared), because messages were made scoped
- // and should be let to clear themselves out.
- static_cast<void>(m_reporter->assertionEnded(AssertionStats(result, m_messages, m_totals)));
-
- // Reset working state
- m_lastAssertionInfo = { "", m_lastAssertionInfo.lineInfo, "{Unknown expression after the reported line}", m_lastAssertionInfo.resultDisposition };
- m_lastResult = result;
- }
-
- bool RunContext::sectionStarted(SectionInfo const & sectionInfo, Counts & assertions) {
- ITracker& sectionTracker = SectionTracker::acquire(m_trackerContext, TestCaseTracking::NameAndLocation(sectionInfo.name, sectionInfo.lineInfo));
- if (!sectionTracker.isOpen())
- return false;
- m_activeSections.push_back(§ionTracker);
-
- m_lastAssertionInfo.lineInfo = sectionInfo.lineInfo;
-
- m_reporter->sectionStarting(sectionInfo);
-
- assertions = m_totals.assertions;
-
- return true;
- }
-
- bool RunContext::testForMissingAssertions(Counts& assertions) {
- if (assertions.total() != 0)
- return false;
- if (!m_config->warnAboutMissingAssertions())
- return false;
- if (m_trackerContext.currentTracker().hasChildren())
- return false;
- m_totals.assertions.failed++;
- assertions.failed++;
- return true;
- }
-
- void RunContext::sectionEnded(SectionEndInfo const & endInfo) {
- Counts assertions = m_totals.assertions - endInfo.prevAssertions;
- bool missingAssertions = testForMissingAssertions(assertions);
-
- if (!m_activeSections.empty()) {
- m_activeSections.back()->close();
- m_activeSections.pop_back();
- }
-
- m_reporter->sectionEnded(SectionStats(endInfo.sectionInfo, assertions, endInfo.durationInSeconds, missingAssertions));
- m_messages.clear();
- }
-
- void RunContext::sectionEndedEarly(SectionEndInfo const & endInfo) {
- if (m_unfinishedSections.empty())
- m_activeSections.back()->fail();
- else
- m_activeSections.back()->close();
- m_activeSections.pop_back();
-
- m_unfinishedSections.push_back(endInfo);
- }
- void RunContext::benchmarkStarting( BenchmarkInfo const& info ) {
- m_reporter->benchmarkStarting( info );
- }
- void RunContext::benchmarkEnded( BenchmarkStats const& stats ) {
- m_reporter->benchmarkEnded( stats );
- }
-
- void RunContext::pushScopedMessage(MessageInfo const & message) {
- m_messages.push_back(message);
- }
-
- void RunContext::popScopedMessage(MessageInfo const & message) {
- m_messages.erase(std::remove(m_messages.begin(), m_messages.end(), message), m_messages.end());
- }
-
- std::string RunContext::getCurrentTestName() const {
- return m_activeTestCase
- ? m_activeTestCase->getTestCaseInfo().name
- : std::string();
- }
-
- const AssertionResult * RunContext::getLastResult() const {
- return &(*m_lastResult);
- }
-
- void RunContext::exceptionEarlyReported() {
- m_shouldReportUnexpected = false;
- }
-
- void RunContext::handleFatalErrorCondition( StringRef message ) {
- // First notify reporter that bad things happened
- m_reporter->fatalErrorEncountered(message);
-
- // Don't rebuild the result -- the stringification itself can cause more fatal errors
- // Instead, fake a result data.
- AssertionResultData tempResult( ResultWas::FatalErrorCondition, { false } );
- tempResult.message = message;
- AssertionResult result(m_lastAssertionInfo, tempResult);
-
- getResultCapture().assertionEnded(result);
-
- handleUnfinishedSections();
-
- // Recreate section for test case (as we will lose the one that was in scope)
- auto const& testCaseInfo = m_activeTestCase->getTestCaseInfo();
- SectionInfo testCaseSection(testCaseInfo.lineInfo, testCaseInfo.name, testCaseInfo.description);
-
- Counts assertions;
- assertions.failed = 1;
- SectionStats testCaseSectionStats(testCaseSection, assertions, 0, false);
- m_reporter->sectionEnded(testCaseSectionStats);
-
- auto const& testInfo = m_activeTestCase->getTestCaseInfo();
-
- Totals deltaTotals;
- deltaTotals.testCases.failed = 1;
- deltaTotals.assertions.failed = 1;
- m_reporter->testCaseEnded(TestCaseStats(testInfo,
- deltaTotals,
- std::string(),
- std::string(),
- false));
- m_totals.testCases.failed++;
- testGroupEnded(std::string(), m_totals, 1, 1);
- m_reporter->testRunEnded(TestRunStats(m_runInfo, m_totals, false));
- }
-
- bool RunContext::lastAssertionPassed() {
- return m_totals.assertions.passed == (m_prevPassed + 1);
- }
-
- void RunContext::assertionPassed() {
- ++m_totals.assertions.passed;
- m_lastAssertionInfo.capturedExpression = "{Unknown expression after the reported line}";
- m_lastAssertionInfo.macroName = "";
- }
-
- void RunContext::assertionRun() {
- m_prevPassed = m_totals.assertions.passed;
- }
-
- bool RunContext::aborting() const {
- return m_totals.assertions.failed == static_cast<std::size_t>(m_config->abortAfter());
- }
-
- void RunContext::runCurrentTest(std::string & redirectedCout, std::string & redirectedCerr) {
- auto const& testCaseInfo = m_activeTestCase->getTestCaseInfo();
- SectionInfo testCaseSection(testCaseInfo.lineInfo, testCaseInfo.name, testCaseInfo.description);
- m_reporter->sectionStarting(testCaseSection);
- Counts prevAssertions = m_totals.assertions;
- double duration = 0;
- m_shouldReportUnexpected = true;
- try {
- m_lastAssertionInfo = { "TEST_CASE", testCaseInfo.lineInfo, "", ResultDisposition::Normal };
-
- seedRng(*m_config);
-
- Timer timer;
- timer.start();
- if (m_reporter->getPreferences().shouldRedirectStdOut) {
- StreamRedirect coutRedir(cout(), redirectedCout);
- StdErrRedirect errRedir(redirectedCerr);
- invokeActiveTestCase();
- } else {
- invokeActiveTestCase();
- }
- duration = timer.getElapsedSeconds();
- } catch (TestFailureException&) {
- // This just means the test was aborted due to failure
- } catch (...) {
- // Under CATCH_CONFIG_FAST_COMPILE, unexpected exceptions under REQUIRE assertions
- // are reported without translation at the point of origin.
- if (m_shouldReportUnexpected) {
- AssertionHandler
- ( m_lastAssertionInfo.macroName,
- m_lastAssertionInfo.lineInfo,
- m_lastAssertionInfo.capturedExpression,
- m_lastAssertionInfo.resultDisposition ).useActiveException();
- }
- }
- m_testCaseTracker->close();
- handleUnfinishedSections();
- m_messages.clear();
-
- Counts assertions = m_totals.assertions - prevAssertions;
- bool missingAssertions = testForMissingAssertions(assertions);
- SectionStats testCaseSectionStats(testCaseSection, assertions, duration, missingAssertions);
- m_reporter->sectionEnded(testCaseSectionStats);
- }
-
- void RunContext::invokeActiveTestCase() {
- FatalConditionHandler fatalConditionHandler; // Handle signals
- m_activeTestCase->invoke();
- fatalConditionHandler.reset();
- }
-
- void RunContext::handleUnfinishedSections() {
- // If sections ended prematurely due to an exception we stored their
- // infos here so we can tear them down outside the unwind process.
- for (auto it = m_unfinishedSections.rbegin(),
- itEnd = m_unfinishedSections.rend();
- it != itEnd;
- ++it)
- sectionEnded(*it);
- m_unfinishedSections.clear();
- }
-
- IResultCapture& getResultCapture() {
- if (auto* capture = getCurrentContext().getResultCapture())
- return *capture;
- else
- CATCH_INTERNAL_ERROR("No result capture instance");
- }
-}
-// end catch_run_context.cpp
-// start catch_section.cpp
-
-namespace Catch {
-
- Section::Section( SectionInfo const& info )
- : m_info( info ),
- m_sectionIncluded( getResultCapture().sectionStarted( m_info, m_assertions ) )
- {
- m_timer.start();
- }
-
-#if defined(_MSC_VER)
-#pragma warning(push)
-#pragma warning(disable:4996) // std::uncaught_exception is deprecated in C++17
-#endif
- Section::~Section() {
- if( m_sectionIncluded ) {
- SectionEndInfo endInfo( m_info, m_assertions, m_timer.getElapsedSeconds() );
- if( std::uncaught_exception() )
- getResultCapture().sectionEndedEarly( endInfo );
- else
- getResultCapture().sectionEnded( endInfo );
- }
- }
-#if defined(_MSC_VER)
-#pragma warning(pop)
-#endif
-
- // This indicates whether the section should be executed or not
- Section::operator bool() const {
- return m_sectionIncluded;
- }
-
-} // end namespace Catch
-// end catch_section.cpp
-// start catch_section_info.cpp
-
-namespace Catch {
-
- SectionInfo::SectionInfo
- ( SourceLineInfo const& _lineInfo,
- std::string const& _name,
- std::string const& _description )
- : name( _name ),
- description( _description ),
- lineInfo( _lineInfo )
- {}
-
- SectionEndInfo::SectionEndInfo( SectionInfo const& _sectionInfo, Counts const& _prevAssertions, double _durationInSeconds )
- : sectionInfo( _sectionInfo ), prevAssertions( _prevAssertions ), durationInSeconds( _durationInSeconds )
- {}
-
-} // end namespace Catch
-// end catch_section_info.cpp
-// start catch_session.cpp
-
-// start catch_session.h
-
-#include <memory>
-
-namespace Catch {
-
- class Session : NonCopyable {
- public:
-
- Session();
- ~Session() override;
-
- void showHelp() const;
- void libIdentify();
-
- int applyCommandLine( int argc, char* argv[] );
-
- void useConfigData( ConfigData const& configData );
-
- int run( int argc, char* argv[] );
- #if defined(WIN32) && defined(UNICODE)
- int run( int argc, wchar_t* const argv[] );
- #endif
- int run();
-
- clara::Parser const& cli() const;
- void cli( clara::Parser const& newParser );
- ConfigData& configData();
- Config& config();
- private:
- int runInternal();
-
- clara::Parser m_cli;
- ConfigData m_configData;
- std::shared_ptr<Config> m_config;
- bool m_startupExceptions = false;
- };
-
-} // end namespace Catch
-
-// end catch_session.h
-// start catch_version.h
-
-#include <iosfwd>
-
-namespace Catch {
-
- // Versioning information
- struct Version {
- Version( Version const& ) = delete;
- Version& operator=( Version const& ) = delete;
- Version( unsigned int _majorVersion,
- unsigned int _minorVersion,
- unsigned int _patchNumber,
- char const * const _branchName,
- unsigned int _buildNumber );
-
- unsigned int const majorVersion;
- unsigned int const minorVersion;
- unsigned int const patchNumber;
-
- // buildNumber is only used if branchName is not null
- char const * const branchName;
- unsigned int const buildNumber;
-
- friend std::ostream& operator << ( std::ostream& os, Version const& version );
- };
-
- Version const& libraryVersion();
-}
-
-// end catch_version.h
-#include <cstdlib>
-#include <iomanip>
-
-namespace {
- const int MaxExitCode = 255;
- using Catch::IStreamingReporterPtr;
- using Catch::IConfigPtr;
- using Catch::Config;
-
- IStreamingReporterPtr createReporter(std::string const& reporterName, IConfigPtr const& config) {
- auto reporter = Catch::getRegistryHub().getReporterRegistry().create(reporterName, config);
- CATCH_ENFORCE(reporter, "No reporter registered with name: '" << reporterName << "'");
-
- return reporter;
- }
-
-#ifndef CATCH_CONFIG_DEFAULT_REPORTER
-#define CATCH_CONFIG_DEFAULT_REPORTER "console"
-#endif
-
- IStreamingReporterPtr makeReporter(std::shared_ptr<Config> const& config) {
- auto const& reporterNames = config->getReporterNames();
- if (reporterNames.empty())
- return createReporter(CATCH_CONFIG_DEFAULT_REPORTER, config);
-
- IStreamingReporterPtr reporter;
- for (auto const& name : reporterNames)
- addReporter(reporter, createReporter(name, config));
- return reporter;
- }
-
-#undef CATCH_CONFIG_DEFAULT_REPORTER
-
- void addListeners(IStreamingReporterPtr& reporters, IConfigPtr const& config) {
- auto const& listeners = Catch::getRegistryHub().getReporterRegistry().getListeners();
- for (auto const& listener : listeners)
- addReporter(reporters, listener->create(Catch::ReporterConfig(config)));
- }
-
- Catch::Totals runTests(std::shared_ptr<Config> const& config) {
- using namespace Catch;
- IStreamingReporterPtr reporter = makeReporter(config);
- addListeners(reporter, config);
-
- RunContext context(config, std::move(reporter));
-
- Totals totals;
-
- context.testGroupStarting(config->name(), 1, 1);
-
- TestSpec testSpec = config->testSpec();
- if (!testSpec.hasFilters())
- testSpec = TestSpecParser(ITagAliasRegistry::get()).parse("~[.]").testSpec(); // All not hidden tests
-
- auto const& allTestCases = getAllTestCasesSorted(*config);
- for (auto const& testCase : allTestCases) {
- if (!context.aborting() && matchTest(testCase, testSpec, *config))
- totals += context.runTest(testCase);
- else
- context.reporter().skipTest(testCase);
- }
-
- context.testGroupEnded(config->name(), totals, 1, 1);
- return totals;
- }
-
- void applyFilenamesAsTags(Catch::IConfig const& config) {
- using namespace Catch;
- auto& tests = const_cast<std::vector<TestCase>&>(getAllTestCasesSorted(config));
- for (auto& testCase : tests) {
- auto tags = testCase.tags;
-
- std::string filename = testCase.lineInfo.file;
- auto lastSlash = filename.find_last_of("\\/");
- if (lastSlash != std::string::npos) {
- filename.erase(0, lastSlash);
- filename[0] = '#';
- }
-
- auto lastDot = filename.find_last_of('.');
- if (lastDot != std::string::npos) {
- filename.erase(lastDot);
- }
-
- tags.push_back(std::move(filename));
- setTags(testCase, tags);
- }
- }
-
-}
-
-namespace Catch {
-
- Session::Session() {
- static bool alreadyInstantiated = false;
- if( alreadyInstantiated ) {
- try { CATCH_INTERNAL_ERROR( "Only one instance of Catch::Session can ever be used" ); }
- catch(...) { getMutableRegistryHub().registerStartupException(); }
- }
-
- const auto& exceptions = getRegistryHub().getStartupExceptionRegistry().getExceptions();
- if ( !exceptions.empty() ) {
- m_startupExceptions = true;
- Colour colourGuard( Colour::Red );
- Catch::cerr() << "Errors occured during startup!" << '\n';
- // iterate over all exceptions and notify user
- for ( const auto& ex_ptr : exceptions ) {
- try {
- std::rethrow_exception(ex_ptr);
- } catch ( std::exception const& ex ) {
- Catch::cerr() << Column( ex.what() ).indent(2) << '\n';
- }
- }
- }
-
- alreadyInstantiated = true;
- m_cli = makeCommandLineParser( m_configData );
- }
- Session::~Session() {
- Catch::cleanUp();
- }
-
- void Session::showHelp() const {
- Catch::cout()
- << "\nCatch v" << libraryVersion() << "\n"
- << m_cli << std::endl
- << "For more detailed usage please see the project docs\n" << std::endl;
- }
- void Session::libIdentify() {
- Catch::cout()
- << std::left << std::setw(16) << "description: " << "A Catch test executable\n"
- << std::left << std::setw(16) << "category: " << "testframework\n"
- << std::left << std::setw(16) << "framework: " << "Catch Test\n"
- << std::left << std::setw(16) << "version: " << libraryVersion() << std::endl;
- }
-
- int Session::applyCommandLine( int argc, char* argv[] ) {
- if( m_startupExceptions )
- return 1;
-
- auto result = m_cli.parse( clara::Args( argc, argv ) );
- if( !result ) {
- Catch::cerr()
- << Colour( Colour::Red )
- << "\nError(s) in input:\n"
- << Column( result.errorMessage() ).indent( 2 )
- << "\n\n";
- Catch::cerr() << "Run with -? for usage\n" << std::endl;
- return MaxExitCode;
- }
-
- if( m_configData.showHelp )
- showHelp();
- if( m_configData.libIdentify )
- libIdentify();
- m_config.reset();
- return 0;
- }
-
- void Session::useConfigData( ConfigData const& configData ) {
- m_configData = configData;
- m_config.reset();
- }
-
- int Session::run( int argc, char* argv[] ) {
- if( m_startupExceptions )
- return 1;
- int returnCode = applyCommandLine( argc, argv );
- if( returnCode == 0 )
- returnCode = run();
- return returnCode;
- }
-
-#if defined(WIN32) && defined(UNICODE)
- int Session::run( int argc, wchar_t* const argv[] ) {
-
- char **utf8Argv = new char *[ argc ];
-
- for ( int i = 0; i < argc; ++i ) {
- int bufSize = WideCharToMultiByte( CP_UTF8, 0, argv[i], -1, NULL, 0, NULL, NULL );
-
- utf8Argv[ i ] = new char[ bufSize ];
-
- WideCharToMultiByte( CP_UTF8, 0, argv[i], -1, utf8Argv[i], bufSize, NULL, NULL );
- }
-
- int returnCode = run( argc, utf8Argv );
-
- for ( int i = 0; i < argc; ++i )
- delete [] utf8Argv[ i ];
-
- delete [] utf8Argv;
-
- return returnCode;
- }
-#endif
- int Session::run() {
- if( ( m_configData.waitForKeypress & WaitForKeypress::BeforeStart ) != 0 ) {
- Catch::cout() << "...waiting for enter/ return before starting" << std::endl;
- static_cast<void>(std::getchar());
- }
- int exitCode = runInternal();
- if( ( m_configData.waitForKeypress & WaitForKeypress::BeforeExit ) != 0 ) {
- Catch::cout() << "...waiting for enter/ return before exiting, with code: " << exitCode << std::endl;
- static_cast<void>(std::getchar());
- }
- return exitCode;
- }
-
- clara::Parser const& Session::cli() const {
- return m_cli;
- }
- void Session::cli( clara::Parser const& newParser ) {
- m_cli = newParser;
- }
- ConfigData& Session::configData() {
- return m_configData;
- }
- Config& Session::config() {
- if( !m_config )
- m_config = std::make_shared<Config>( m_configData );
- return *m_config;
- }
-
- int Session::runInternal() {
- if( m_startupExceptions )
- return 1;
-
- if( m_configData.showHelp || m_configData.libIdentify )
- return 0;
-
- try
- {
- config(); // Force config to be constructed
-
- seedRng( *m_config );
-
- if( m_configData.filenamesAsTags )
- applyFilenamesAsTags( *m_config );
-
- // Handle list request
- if( Option<std::size_t> listed = list( config() ) )
- return static_cast<int>( *listed );
-
- return (std::min)( MaxExitCode, static_cast<int>( runTests( m_config ).assertions.failed ) );
- }
- catch( std::exception& ex ) {
- Catch::cerr() << ex.what() << std::endl;
- return MaxExitCode;
- }
- }
-
-} // end namespace Catch
-// end catch_session.cpp
-// start catch_startup_exception_registry.cpp
-
-namespace Catch {
- void StartupExceptionRegistry::add( std::exception_ptr const& exception ) noexcept {
- try {
- m_exceptions.push_back(exception);
- }
- catch(...) {
- // If we run out of memory during start-up there's really not a lot more we can do about it
- std::terminate();
- }
- }
-
- std::vector<std::exception_ptr> const& StartupExceptionRegistry::getExceptions() const noexcept {
- return m_exceptions;
- }
-
-} // end namespace Catch
-// end catch_startup_exception_registry.cpp
-// start catch_stream.cpp
-
-#include <stdexcept>
-#include <cstdio>
-#include <iostream>
-
-namespace Catch {
-
- template<typename WriterF, std::size_t bufferSize=256>
- class StreamBufImpl : public StreamBufBase {
- char data[bufferSize];
- WriterF m_writer;
-
- public:
- StreamBufImpl() {
- setp( data, data + sizeof(data) );
- }
-
- ~StreamBufImpl() noexcept {
- StreamBufImpl::sync();
- }
-
- private:
- int overflow( int c ) override {
- sync();
-
- if( c != EOF ) {
- if( pbase() == epptr() )
- m_writer( std::string( 1, static_cast<char>( c ) ) );
- else
- sputc( static_cast<char>( c ) );
- }
- return 0;
- }
-
- int sync() override {
- if( pbase() != pptr() ) {
- m_writer( std::string( pbase(), static_cast<std::string::size_type>( pptr() - pbase() ) ) );
- setp( pbase(), epptr() );
- }
- return 0;
- }
- };
-
- ///////////////////////////////////////////////////////////////////////////
-
- Catch::IStream::~IStream() = default;
-
- FileStream::FileStream( std::string const& filename ) {
- m_ofs.open( filename.c_str() );
- CATCH_ENFORCE( !m_ofs.fail(), "Unable to open file: '" << filename << "'" );
- }
-
- std::ostream& FileStream::stream() const {
- return m_ofs;
- }
-
- struct OutputDebugWriter {
-
- void operator()( std::string const&str ) {
- writeToDebugConsole( str );
- }
- };
-
- DebugOutStream::DebugOutStream()
- : m_streamBuf( new StreamBufImpl<OutputDebugWriter>() ),
- m_os( m_streamBuf.get() )
- {}
-
- std::ostream& DebugOutStream::stream() const {
- return m_os;
- }
-
- // Store the streambuf from cout up-front because
- // cout may get redirected when running tests
- CoutStream::CoutStream()
- : m_os( Catch::cout().rdbuf() )
- {}
-
- std::ostream& CoutStream::stream() const {
- return m_os;
- }
-
-#ifndef CATCH_CONFIG_NOSTDOUT // If you #define this you must implement these functions
- std::ostream& cout() {
- return std::cout;
- }
- std::ostream& cerr() {
- return std::cerr;
- }
- std::ostream& clog() {
- return std::clog;
- }
-#endif
-}
-// end catch_stream.cpp
-// start catch_streambuf.cpp
-
-namespace Catch {
- StreamBufBase::~StreamBufBase() = default;
-}
-// end catch_streambuf.cpp
-// start catch_string_manip.cpp
-
-#include <algorithm>
-#include <ostream>
-#include <cstring>
-#include <cctype>
-
-namespace Catch {
-
- bool startsWith( std::string const& s, std::string const& prefix ) {
- return s.size() >= prefix.size() && std::equal(prefix.begin(), prefix.end(), s.begin());
- }
- bool startsWith( std::string const& s, char prefix ) {
- return !s.empty() && s[0] == prefix;
- }
- bool endsWith( std::string const& s, std::string const& suffix ) {
- return s.size() >= suffix.size() && std::equal(suffix.rbegin(), suffix.rend(), s.rbegin());
- }
- bool endsWith( std::string const& s, char suffix ) {
- return !s.empty() && s[s.size()-1] == suffix;
- }
- bool contains( std::string const& s, std::string const& infix ) {
- return s.find( infix ) != std::string::npos;
- }
- char toLowerCh(char c) {
- return static_cast<char>( std::tolower( c ) );
- }
- void toLowerInPlace( std::string& s ) {
- std::transform( s.begin(), s.end(), s.begin(), toLowerCh );
- }
- std::string toLower( std::string const& s ) {
- std::string lc = s;
- toLowerInPlace( lc );
- return lc;
- }
- std::string trim( std::string const& str ) {
- static char const* whitespaceChars = "\n\r\t ";
- std::string::size_type start = str.find_first_not_of( whitespaceChars );
- std::string::size_type end = str.find_last_not_of( whitespaceChars );
-
- return start != std::string::npos ? str.substr( start, 1+end-start ) : std::string();
- }
-
- bool replaceInPlace( std::string& str, std::string const& replaceThis, std::string const& withThis ) {
- bool replaced = false;
- std::size_t i = str.find( replaceThis );
- while( i != std::string::npos ) {
- replaced = true;
- str = str.substr( 0, i ) + withThis + str.substr( i+replaceThis.size() );
- if( i < str.size()-withThis.size() )
- i = str.find( replaceThis, i+withThis.size() );
- else
- i = std::string::npos;
- }
- return replaced;
- }
-
- pluralise::pluralise( std::size_t count, std::string const& label )
- : m_count( count ),
- m_label( label )
- {}
-
- std::ostream& operator << ( std::ostream& os, pluralise const& pluraliser ) {
- os << pluraliser.m_count << ' ' << pluraliser.m_label;
- if( pluraliser.m_count != 1 )
- os << 's';
- return os;
- }
-
-}
-// end catch_string_manip.cpp
-// start catch_stringref.cpp
-
-#if defined(__clang__)
-# pragma clang diagnostic push
-# pragma clang diagnostic ignored "-Wexit-time-destructors"
-#endif
-
-#include <ostream>
-#include <cassert>
-#include <cstring>
-
-namespace Catch {
-
- auto getEmptyStringRef() -> StringRef {
- static StringRef s_emptyStringRef("");
- return s_emptyStringRef;
- }
-
- StringRef::StringRef() noexcept
- : StringRef( getEmptyStringRef() )
- {}
-
- StringRef::StringRef( StringRef const& other ) noexcept
- : m_start( other.m_start ),
- m_size( other.m_size )
- {}
-
- StringRef::StringRef( StringRef&& other ) noexcept
- : m_start( other.m_start ),
- m_size( other.m_size ),
- m_data( other.m_data )
- {
- other.m_data = nullptr;
- }
-
- StringRef::StringRef( char const* rawChars ) noexcept
- : m_start( rawChars ),
- m_size( static_cast<size_type>( std::strlen( rawChars ) ) )
- {
- assert( rawChars != nullptr );
- }
-
- StringRef::StringRef( char const* rawChars, size_type size ) noexcept
- : m_start( rawChars ),
- m_size( size )
- {
- size_type rawSize = rawChars == nullptr ? 0 : static_cast<size_type>( std::strlen( rawChars ) );
- if( rawSize < size )
- m_size = rawSize;
- }
-
- StringRef::StringRef( std::string const& stdString ) noexcept
- : m_start( stdString.c_str() ),
- m_size( stdString.size() )
- {}
-
- StringRef::~StringRef() noexcept {
- delete[] m_data;
- }
-
- auto StringRef::operator = ( StringRef other ) noexcept -> StringRef& {
- swap( other );
- return *this;
- }
- StringRef::operator std::string() const {
- return std::string( m_start, m_size );
- }
-
- void StringRef::swap( StringRef& other ) noexcept {
- std::swap( m_start, other.m_start );
- std::swap( m_size, other.m_size );
- std::swap( m_data, other.m_data );
- }
-
- auto StringRef::c_str() const -> char const* {
- if( isSubstring() )
- const_cast<StringRef*>( this )->takeOwnership();
- return m_start;
- }
- auto StringRef::data() const noexcept -> char const* {
- return m_start;
- }
-
- auto StringRef::isOwned() const noexcept -> bool {
- return m_data != nullptr;
- }
- auto StringRef::isSubstring() const noexcept -> bool {
- return m_start[m_size] != '\0';
- }
-
- void StringRef::takeOwnership() {
- if( !isOwned() ) {
- m_data = new char[m_size+1];
- memcpy( m_data, m_start, m_size );
- m_data[m_size] = '\0';
- m_start = m_data;
- }
- }
- auto StringRef::substr( size_type start, size_type size ) const noexcept -> StringRef {
- if( start < m_size )
- return StringRef( m_start+start, size );
- else
- return StringRef();
- }
- auto StringRef::operator == ( StringRef const& other ) const noexcept -> bool {
- return
- size() == other.size() &&
- (std::strncmp( m_start, other.m_start, size() ) == 0);
- }
- auto StringRef::operator != ( StringRef const& other ) const noexcept -> bool {
- return !operator==( other );
- }
-
- auto StringRef::operator[](size_type index) const noexcept -> char {
- return m_start[index];
- }
-
- auto StringRef::empty() const noexcept -> bool {
- return m_size == 0;
- }
-
- auto StringRef::size() const noexcept -> size_type {
- return m_size;
- }
- auto StringRef::numberOfCharacters() const noexcept -> size_type {
- size_type noChars = m_size;
- // Make adjustments for uft encodings
- for( size_type i=0; i < m_size; ++i ) {
- char c = m_start[i];
- if( ( c & 0b11000000 ) == 0b11000000 ) {
- if( ( c & 0b11100000 ) == 0b11000000 )
- noChars--;
- else if( ( c & 0b11110000 ) == 0b11100000 )
- noChars-=2;
- else if( ( c & 0b11111000 ) == 0b11110000 )
- noChars-=3;
- }
- }
- return noChars;
- }
-
- auto operator + ( StringRef const& lhs, StringRef const& rhs ) -> std::string {
- std::string str;
- str.reserve( lhs.size() + rhs.size() );
- str += lhs;
- str += rhs;
- return str;
- }
- auto operator + ( StringRef const& lhs, const char* rhs ) -> std::string {
- return std::string( lhs ) + std::string( rhs );
- }
- auto operator + ( char const* lhs, StringRef const& rhs ) -> std::string {
- return std::string( lhs ) + std::string( rhs );
- }
-
- auto operator << ( std::ostream& os, StringRef const& str ) -> std::ostream& {
- return os << str.c_str();
- }
-
-} // namespace Catch
-
-#if defined(__clang__)
-# pragma clang diagnostic pop
-#endif
-// end catch_stringref.cpp
-// start catch_tag_alias.cpp
-
-namespace Catch {
- TagAlias::TagAlias(std::string const & _tag, SourceLineInfo _lineInfo): tag(_tag), lineInfo(_lineInfo) {}
-}
-// end catch_tag_alias.cpp
-// start catch_tag_alias_autoregistrar.cpp
-
-namespace Catch {
-
- RegistrarForTagAliases::RegistrarForTagAliases(char const* alias, char const* tag, SourceLineInfo const& lineInfo) {
- try {
- getMutableRegistryHub().registerTagAlias(alias, tag, lineInfo);
- } catch (...) {
- // Do not throw when constructing global objects, instead register the exception to be processed later
- getMutableRegistryHub().registerStartupException();
- }
- }
-
-}
-// end catch_tag_alias_autoregistrar.cpp
-// start catch_tag_alias_registry.cpp
-
-namespace Catch {
-
- TagAliasRegistry::~TagAliasRegistry() {}
-
- TagAlias const* TagAliasRegistry::find( std::string const& alias ) const {
- auto it = m_registry.find( alias );
- if( it != m_registry.end() )
- return &(it->second);
- else
- return nullptr;
- }
-
- std::string TagAliasRegistry::expandAliases( std::string const& unexpandedTestSpec ) const {
- std::string expandedTestSpec = unexpandedTestSpec;
- for( auto const& registryKvp : m_registry ) {
- std::size_t pos = expandedTestSpec.find( registryKvp.first );
- if( pos != std::string::npos ) {
- expandedTestSpec = expandedTestSpec.substr( 0, pos ) +
- registryKvp.second.tag +
- expandedTestSpec.substr( pos + registryKvp.first.size() );
- }
- }
- return expandedTestSpec;
- }
-
- void TagAliasRegistry::add( std::string const& alias, std::string const& tag, SourceLineInfo const& lineInfo ) {
- CATCH_ENFORCE( startsWith(alias, "[@") && endsWith(alias, ']'),
- "error: tag alias, '" << alias << "' is not of the form [@alias name].\n" << lineInfo );
-
- CATCH_ENFORCE( m_registry.insert(std::make_pair(alias, TagAlias(tag, lineInfo))).second,
- "error: tag alias, '" << alias << "' already registered.\n"
- << "\tFirst seen at: " << find(alias)->lineInfo << "\n"
- << "\tRedefined at: " << lineInfo );
- }
-
- ITagAliasRegistry::~ITagAliasRegistry() {}
-
- ITagAliasRegistry const& ITagAliasRegistry::get() {
- return getRegistryHub().getTagAliasRegistry();
- }
-
-} // end namespace Catch
-// end catch_tag_alias_registry.cpp
-// start catch_test_case_info.cpp
-
-#include <cctype>
-#include <exception>
-#include <algorithm>
-
-namespace Catch {
-
- TestCaseInfo::SpecialProperties parseSpecialTag( std::string const& tag ) {
- if( startsWith( tag, '.' ) ||
- tag == "!hide" )
- return TestCaseInfo::IsHidden;
- else if( tag == "!throws" )
- return TestCaseInfo::Throws;
- else if( tag == "!shouldfail" )
- return TestCaseInfo::ShouldFail;
- else if( tag == "!mayfail" )
- return TestCaseInfo::MayFail;
- else if( tag == "!nonportable" )
- return TestCaseInfo::NonPortable;
- else if( tag == "!benchmark" )
- return static_cast<TestCaseInfo::SpecialProperties>( TestCaseInfo::Benchmark | TestCaseInfo::IsHidden );
- else
- return TestCaseInfo::None;
- }
- bool isReservedTag( std::string const& tag ) {
- return parseSpecialTag( tag ) == TestCaseInfo::None && tag.size() > 0 && !std::isalnum( tag[0] );
- }
- void enforceNotReservedTag( std::string const& tag, SourceLineInfo const& _lineInfo ) {
- CATCH_ENFORCE( !isReservedTag(tag),
- "Tag name: [" << tag << "] is not allowed.\n"
- << "Tag names starting with non alpha-numeric characters are reserved\n"
- << _lineInfo );
- }
-
- TestCase makeTestCase( ITestInvoker* _testCase,
- std::string const& _className,
- std::string const& _name,
- std::string const& _descOrTags,
- SourceLineInfo const& _lineInfo )
- {
- bool isHidden = false;
-
- // Parse out tags
- std::vector<std::string> tags;
- std::string desc, tag;
- bool inTag = false;
- for (char c : _descOrTags) {
- if( !inTag ) {
- if( c == '[' )
- inTag = true;
- else
- desc += c;
- }
- else {
- if( c == ']' ) {
- TestCaseInfo::SpecialProperties prop = parseSpecialTag( tag );
- if( ( prop & TestCaseInfo::IsHidden ) != 0 )
- isHidden = true;
- else if( prop == TestCaseInfo::None )
- enforceNotReservedTag( tag, _lineInfo );
-
- tags.push_back( tag );
- tag.clear();
- inTag = false;
- }
- else
- tag += c;
- }
- }
- if( isHidden ) {
- tags.push_back( "." );
- }
-
- TestCaseInfo info( _name, _className, desc, tags, _lineInfo );
- return TestCase( _testCase, info );
- }
-
- void setTags( TestCaseInfo& testCaseInfo, std::vector<std::string> tags ) {
- std::sort(begin(tags), end(tags));
- tags.erase(std::unique(begin(tags), end(tags)), end(tags));
- testCaseInfo.lcaseTags.clear();
-
- for( auto const& tag : tags ) {
- std::string lcaseTag = toLower( tag );
- testCaseInfo.properties = static_cast<TestCaseInfo::SpecialProperties>( testCaseInfo.properties | parseSpecialTag( lcaseTag ) );
- testCaseInfo.lcaseTags.push_back( lcaseTag );
- }
- testCaseInfo.tags = std::move(tags);
- }
-
- TestCaseInfo::TestCaseInfo( std::string const& _name,
- std::string const& _className,
- std::string const& _description,
- std::vector<std::string> const& _tags,
- SourceLineInfo const& _lineInfo )
- : name( _name ),
- className( _className ),
- description( _description ),
- lineInfo( _lineInfo ),
- properties( None )
- {
- setTags( *this, _tags );
- }
-
- bool TestCaseInfo::isHidden() const {
- return ( properties & IsHidden ) != 0;
- }
- bool TestCaseInfo::throws() const {
- return ( properties & Throws ) != 0;
- }
- bool TestCaseInfo::okToFail() const {
- return ( properties & (ShouldFail | MayFail ) ) != 0;
- }
- bool TestCaseInfo::expectedToFail() const {
- return ( properties & (ShouldFail ) ) != 0;
- }
-
- std::string TestCaseInfo::tagsAsString() const {
- std::string ret;
- // '[' and ']' per tag
- std::size_t full_size = 2 * tags.size();
- for (const auto& tag : tags) {
- full_size += tag.size();
- }
- ret.reserve(full_size);
- for (const auto& tag : tags) {
- ret.push_back('[');
- ret.append(tag);
- ret.push_back(']');
- }
-
- return ret;
- }
-
- TestCase::TestCase( ITestInvoker* testCase, TestCaseInfo const& info ) : TestCaseInfo( info ), test( testCase ) {}
-
- TestCase TestCase::withName( std::string const& _newName ) const {
- TestCase other( *this );
- other.name = _newName;
- return other;
- }
-
- void TestCase::invoke() const {
- test->invoke();
- }
-
- bool TestCase::operator == ( TestCase const& other ) const {
- return test.get() == other.test.get() &&
- name == other.name &&
- className == other.className;
- }
-
- bool TestCase::operator < ( TestCase const& other ) const {
- return name < other.name;
- }
-
- TestCaseInfo const& TestCase::getTestCaseInfo() const
- {
- return *this;
- }
-
-} // end namespace Catch
-// end catch_test_case_info.cpp
-// start catch_test_case_registry_impl.cpp
-
-#include <sstream>
-
-namespace Catch {
-
- std::vector<TestCase> sortTests( IConfig const& config, std::vector<TestCase> const& unsortedTestCases ) {
-
- std::vector<TestCase> sorted = unsortedTestCases;
-
- switch( config.runOrder() ) {
- case RunTests::InLexicographicalOrder:
- std::sort( sorted.begin(), sorted.end() );
- break;
- case RunTests::InRandomOrder:
- seedRng( config );
- RandomNumberGenerator::shuffle( sorted );
- break;
- case RunTests::InDeclarationOrder:
- // already in declaration order
- break;
- }
- return sorted;
- }
- bool matchTest( TestCase const& testCase, TestSpec const& testSpec, IConfig const& config ) {
- return testSpec.matches( testCase ) && ( config.allowThrows() || !testCase.throws() );
- }
-
- void enforceNoDuplicateTestCases( std::vector<TestCase> const& functions ) {
- std::set<TestCase> seenFunctions;
- for( auto const& function : functions ) {
- auto prev = seenFunctions.insert( function );
- CATCH_ENFORCE( prev.second,
- "error: TEST_CASE( \"" << function.name << "\" ) already defined.\n"
- << "\tFirst seen at " << prev.first->getTestCaseInfo().lineInfo << "\n"
- << "\tRedefined at " << function.getTestCaseInfo().lineInfo );
- }
- }
-
- std::vector<TestCase> filterTests( std::vector<TestCase> const& testCases, TestSpec const& testSpec, IConfig const& config ) {
- std::vector<TestCase> filtered;
- filtered.reserve( testCases.size() );
- for( auto const& testCase : testCases )
- if( matchTest( testCase, testSpec, config ) )
- filtered.push_back( testCase );
- return filtered;
- }
- std::vector<TestCase> const& getAllTestCasesSorted( IConfig const& config ) {
- return getRegistryHub().getTestCaseRegistry().getAllTestsSorted( config );
- }
-
- void TestRegistry::registerTest( TestCase const& testCase ) {
- std::string name = testCase.getTestCaseInfo().name;
- if( name.empty() ) {
- std::ostringstream oss;
- oss << "Anonymous test case " << ++m_unnamedCount;
- return registerTest( testCase.withName( oss.str() ) );
- }
- m_functions.push_back( testCase );
- }
-
- std::vector<TestCase> const& TestRegistry::getAllTests() const {
- return m_functions;
- }
- std::vector<TestCase> const& TestRegistry::getAllTestsSorted( IConfig const& config ) const {
- if( m_sortedFunctions.empty() )
- enforceNoDuplicateTestCases( m_functions );
-
- if( m_currentSortOrder != config.runOrder() || m_sortedFunctions.empty() ) {
- m_sortedFunctions = sortTests( config, m_functions );
- m_currentSortOrder = config.runOrder();
- }
- return m_sortedFunctions;
- }
-
- ///////////////////////////////////////////////////////////////////////////
- TestInvokerAsFunction::TestInvokerAsFunction( void(*testAsFunction)() ) noexcept : m_testAsFunction( testAsFunction ) {}
-
- void TestInvokerAsFunction::invoke() const {
- m_testAsFunction();
- }
-
- std::string extractClassName( std::string const& classOrQualifiedMethodName ) {
- std::string className = classOrQualifiedMethodName;
- if( startsWith( className, '&' ) )
- {
- std::size_t lastColons = className.rfind( "::" );
- std::size_t penultimateColons = className.rfind( "::", lastColons-1 );
- if( penultimateColons == std::string::npos )
- penultimateColons = 1;
- className = className.substr( penultimateColons, lastColons-penultimateColons );
- }
- return className;
- }
-
-} // end namespace Catch
-// end catch_test_case_registry_impl.cpp
-// start catch_test_case_tracker.cpp
-
-#include <algorithm>
-#include <assert.h>
-#include <stdexcept>
-#include <memory>
-
-#if defined(__clang__)
-# pragma clang diagnostic push
-# pragma clang diagnostic ignored "-Wexit-time-destructors"
-#endif
-
-namespace Catch {
-namespace TestCaseTracking {
-
- NameAndLocation::NameAndLocation( std::string const& _name, SourceLineInfo const& _location )
- : name( _name ),
- location( _location )
- {}
-
- ITracker::~ITracker() = default;
-
- TrackerContext& TrackerContext::instance() {
- static TrackerContext s_instance;
- return s_instance;
- }
-
- ITracker& TrackerContext::startRun() {
- m_rootTracker = std::make_shared<SectionTracker>( NameAndLocation( "{root}", CATCH_INTERNAL_LINEINFO ), *this, nullptr );
- m_currentTracker = nullptr;
- m_runState = Executing;
- return *m_rootTracker;
- }
-
- void TrackerContext::endRun() {
- m_rootTracker.reset();
- m_currentTracker = nullptr;
- m_runState = NotStarted;
- }
-
- void TrackerContext::startCycle() {
- m_currentTracker = m_rootTracker.get();
- m_runState = Executing;
- }
- void TrackerContext::completeCycle() {
- m_runState = CompletedCycle;
- }
-
- bool TrackerContext::completedCycle() const {
- return m_runState == CompletedCycle;
- }
- ITracker& TrackerContext::currentTracker() {
- return *m_currentTracker;
- }
- void TrackerContext::setCurrentTracker( ITracker* tracker ) {
- m_currentTracker = tracker;
- }
-
- TrackerBase::TrackerHasName::TrackerHasName( NameAndLocation const& nameAndLocation ) : m_nameAndLocation( nameAndLocation ) {}
- bool TrackerBase::TrackerHasName::operator ()( ITrackerPtr const& tracker ) const {
- return
- tracker->nameAndLocation().name == m_nameAndLocation.name &&
- tracker->nameAndLocation().location == m_nameAndLocation.location;
- }
-
- TrackerBase::TrackerBase( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent )
- : m_nameAndLocation( nameAndLocation ),
- m_ctx( ctx ),
- m_parent( parent )
- {}
-
- NameAndLocation const& TrackerBase::nameAndLocation() const {
- return m_nameAndLocation;
- }
- bool TrackerBase::isComplete() const {
- return m_runState == CompletedSuccessfully || m_runState == Failed;
- }
- bool TrackerBase::isSuccessfullyCompleted() const {
- return m_runState == CompletedSuccessfully;
- }
- bool TrackerBase::isOpen() const {
- return m_runState != NotStarted && !isComplete();
- }
- bool TrackerBase::hasChildren() const {
- return !m_children.empty();
- }
-
- void TrackerBase::addChild( ITrackerPtr const& child ) {
- m_children.push_back( child );
- }
-
- ITrackerPtr TrackerBase::findChild( NameAndLocation const& nameAndLocation ) {
- auto it = std::find_if( m_children.begin(), m_children.end(), TrackerHasName( nameAndLocation ) );
- return( it != m_children.end() )
- ? *it
- : nullptr;
- }
- ITracker& TrackerBase::parent() {
- assert( m_parent ); // Should always be non-null except for root
- return *m_parent;
- }
-
- void TrackerBase::openChild() {
- if( m_runState != ExecutingChildren ) {
- m_runState = ExecutingChildren;
- if( m_parent )
- m_parent->openChild();
- }
- }
-
- bool TrackerBase::isSectionTracker() const { return false; }
- bool TrackerBase::isIndexTracker() const { return false; }
-
- void TrackerBase::open() {
- m_runState = Executing;
- moveToThis();
- if( m_parent )
- m_parent->openChild();
- }
-
- void TrackerBase::close() {
-
- // Close any still open children (e.g. generators)
- while( &m_ctx.currentTracker() != this )
- m_ctx.currentTracker().close();
-
- switch( m_runState ) {
- case NeedsAnotherRun:
- break;
-
- case Executing:
- m_runState = CompletedSuccessfully;
- break;
- case ExecutingChildren:
- if( m_children.empty() || m_children.back()->isComplete() )
- m_runState = CompletedSuccessfully;
- break;
-
- case NotStarted:
- case CompletedSuccessfully:
- case Failed:
- CATCH_INTERNAL_ERROR( "Illogical state: " << m_runState );
-
- default:
- CATCH_INTERNAL_ERROR( "Unknown state: " << m_runState );
- }
- moveToParent();
- m_ctx.completeCycle();
- }
- void TrackerBase::fail() {
- m_runState = Failed;
- if( m_parent )
- m_parent->markAsNeedingAnotherRun();
- moveToParent();
- m_ctx.completeCycle();
- }
- void TrackerBase::markAsNeedingAnotherRun() {
- m_runState = NeedsAnotherRun;
- }
-
- void TrackerBase::moveToParent() {
- assert( m_parent );
- m_ctx.setCurrentTracker( m_parent );
- }
- void TrackerBase::moveToThis() {
- m_ctx.setCurrentTracker( this );
- }
-
- SectionTracker::SectionTracker( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent )
- : TrackerBase( nameAndLocation, ctx, parent )
- {
- if( parent ) {
- while( !parent->isSectionTracker() )
- parent = &parent->parent();
-
- SectionTracker& parentSection = static_cast<SectionTracker&>( *parent );
- addNextFilters( parentSection.m_filters );
- }
- }
-
- bool SectionTracker::isSectionTracker() const { return true; }
-
- SectionTracker& SectionTracker::acquire( TrackerContext& ctx, NameAndLocation const& nameAndLocation ) {
- std::shared_ptr<SectionTracker> section;
-
- ITracker& currentTracker = ctx.currentTracker();
- if( ITrackerPtr childTracker = currentTracker.findChild( nameAndLocation ) ) {
- assert( childTracker );
- assert( childTracker->isSectionTracker() );
- section = std::static_pointer_cast<SectionTracker>( childTracker );
- }
- else {
- section = std::make_shared<SectionTracker>( nameAndLocation, ctx, ¤tTracker );
- currentTracker.addChild( section );
- }
- if( !ctx.completedCycle() )
- section->tryOpen();
- return *section;
- }
-
- void SectionTracker::tryOpen() {
- if( !isComplete() && (m_filters.empty() || m_filters[0].empty() || m_filters[0] == m_nameAndLocation.name ) )
- open();
- }
-
- void SectionTracker::addInitialFilters( std::vector<std::string> const& filters ) {
- if( !filters.empty() ) {
- m_filters.push_back(""); // Root - should never be consulted
- m_filters.push_back(""); // Test Case - not a section filter
- m_filters.insert( m_filters.end(), filters.begin(), filters.end() );
- }
- }
- void SectionTracker::addNextFilters( std::vector<std::string> const& filters ) {
- if( filters.size() > 1 )
- m_filters.insert( m_filters.end(), ++filters.begin(), filters.end() );
- }
-
- IndexTracker::IndexTracker( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent, int size )
- : TrackerBase( nameAndLocation, ctx, parent ),
- m_size( size )
- {}
-
- bool IndexTracker::isIndexTracker() const { return true; }
-
- IndexTracker& IndexTracker::acquire( TrackerContext& ctx, NameAndLocation const& nameAndLocation, int size ) {
- std::shared_ptr<IndexTracker> tracker;
-
- ITracker& currentTracker = ctx.currentTracker();
- if( ITrackerPtr childTracker = currentTracker.findChild( nameAndLocation ) ) {
- assert( childTracker );
- assert( childTracker->isIndexTracker() );
- tracker = std::static_pointer_cast<IndexTracker>( childTracker );
- }
- else {
- tracker = std::make_shared<IndexTracker>( nameAndLocation, ctx, ¤tTracker, size );
- currentTracker.addChild( tracker );
- }
-
- if( !ctx.completedCycle() && !tracker->isComplete() ) {
- if( tracker->m_runState != ExecutingChildren && tracker->m_runState != NeedsAnotherRun )
- tracker->moveNext();
- tracker->open();
- }
-
- return *tracker;
- }
-
- int IndexTracker::index() const { return m_index; }
-
- void IndexTracker::moveNext() {
- m_index++;
- m_children.clear();
- }
-
- void IndexTracker::close() {
- TrackerBase::close();
- if( m_runState == CompletedSuccessfully && m_index < m_size-1 )
- m_runState = Executing;
- }
-
-} // namespace TestCaseTracking
-
-using TestCaseTracking::ITracker;
-using TestCaseTracking::TrackerContext;
-using TestCaseTracking::SectionTracker;
-using TestCaseTracking::IndexTracker;
-
-} // namespace Catch
-
-#if defined(__clang__)
-# pragma clang diagnostic pop
-#endif
-// end catch_test_case_tracker.cpp
-// start catch_test_registry.cpp
-
-namespace Catch {
-
- auto makeTestInvoker( void(*testAsFunction)() ) noexcept -> ITestInvoker* {
- return new(std::nothrow) TestInvokerAsFunction( testAsFunction );
- }
-
- NameAndTags::NameAndTags( StringRef name_ , StringRef tags_ ) noexcept : name( name_ ), tags( tags_ ) {}
-
- AutoReg::AutoReg( ITestInvoker* invoker, SourceLineInfo const& lineInfo, StringRef classOrMethod, NameAndTags const& nameAndTags ) noexcept {
- try {
- getMutableRegistryHub()
- .registerTest(
- makeTestCase(
- invoker,
- extractClassName( classOrMethod ),
- nameAndTags.name,
- nameAndTags.tags,
- lineInfo));
- } catch (...) {
- // Do not throw when constructing global objects, instead register the exception to be processed later
- getMutableRegistryHub().registerStartupException();
- }
- }
-
- AutoReg::~AutoReg() = default;
-}
-// end catch_test_registry.cpp
-// start catch_test_spec.cpp
-
-#include <algorithm>
-#include <string>
-#include <vector>
-#include <memory>
-
-namespace Catch {
-
- TestSpec::Pattern::~Pattern() = default;
- TestSpec::NamePattern::~NamePattern() = default;
- TestSpec::TagPattern::~TagPattern() = default;
- TestSpec::ExcludedPattern::~ExcludedPattern() = default;
-
- TestSpec::NamePattern::NamePattern( std::string const& name )
- : m_wildcardPattern( toLower( name ), CaseSensitive::No )
- {}
- bool TestSpec::NamePattern::matches( TestCaseInfo const& testCase ) const {
- return m_wildcardPattern.matches( toLower( testCase.name ) );
- }
-
- TestSpec::TagPattern::TagPattern( std::string const& tag ) : m_tag( toLower( tag ) ) {}
- bool TestSpec::TagPattern::matches( TestCaseInfo const& testCase ) const {
- return std::find(begin(testCase.lcaseTags),
- end(testCase.lcaseTags),
- m_tag) != end(testCase.lcaseTags);
- }
-
- TestSpec::ExcludedPattern::ExcludedPattern( PatternPtr const& underlyingPattern ) : m_underlyingPattern( underlyingPattern ) {}
- bool TestSpec::ExcludedPattern::matches( TestCaseInfo const& testCase ) const { return !m_underlyingPattern->matches( testCase ); }
-
- bool TestSpec::Filter::matches( TestCaseInfo const& testCase ) const {
- // All patterns in a filter must match for the filter to be a match
- for( auto const& pattern : m_patterns ) {
- if( !pattern->matches( testCase ) )
- return false;
- }
- return true;
- }
-
- bool TestSpec::hasFilters() const {
- return !m_filters.empty();
- }
- bool TestSpec::matches( TestCaseInfo const& testCase ) const {
- // A TestSpec matches if any filter matches
- for( auto const& filter : m_filters )
- if( filter.matches( testCase ) )
- return true;
- return false;
- }
-}
-// end catch_test_spec.cpp
-// start catch_test_spec_parser.cpp
-
-namespace Catch {
-
- TestSpecParser::TestSpecParser( ITagAliasRegistry const& tagAliases ) : m_tagAliases( &tagAliases ) {}
-
- TestSpecParser& TestSpecParser::parse( std::string const& arg ) {
- m_mode = None;
- m_exclusion = false;
- m_start = std::string::npos;
- m_arg = m_tagAliases->expandAliases( arg );
- m_escapeChars.clear();
- for( m_pos = 0; m_pos < m_arg.size(); ++m_pos )
- visitChar( m_arg[m_pos] );
- if( m_mode == Name )
- addPattern<TestSpec::NamePattern>();
- return *this;
- }
- TestSpec TestSpecParser::testSpec() {
- addFilter();
- return m_testSpec;
- }
-
- void TestSpecParser::visitChar( char c ) {
- if( m_mode == None ) {
- switch( c ) {
- case ' ': return;
- case '~': m_exclusion = true; return;
- case '[': return startNewMode( Tag, ++m_pos );
- case '"': return startNewMode( QuotedName, ++m_pos );
- case '\\': return escape();
- default: startNewMode( Name, m_pos ); break;
- }
- }
- if( m_mode == Name ) {
- if( c == ',' ) {
- addPattern<TestSpec::NamePattern>();
- addFilter();
- }
- else if( c == '[' ) {
- if( subString() == "exclude:" )
- m_exclusion = true;
- else
- addPattern<TestSpec::NamePattern>();
- startNewMode( Tag, ++m_pos );
- }
- else if( c == '\\' )
- escape();
- }
- else if( m_mode == EscapedName )
- m_mode = Name;
- else if( m_mode == QuotedName && c == '"' )
- addPattern<TestSpec::NamePattern>();
- else if( m_mode == Tag && c == ']' )
- addPattern<TestSpec::TagPattern>();
- }
- void TestSpecParser::startNewMode( Mode mode, std::size_t start ) {
- m_mode = mode;
- m_start = start;
- }
- void TestSpecParser::escape() {
- if( m_mode == None )
- m_start = m_pos;
- m_mode = EscapedName;
- m_escapeChars.push_back( m_pos );
- }
- std::string TestSpecParser::subString() const { return m_arg.substr( m_start, m_pos - m_start ); }
-
- void TestSpecParser::addFilter() {
- if( !m_currentFilter.m_patterns.empty() ) {
- m_testSpec.m_filters.push_back( m_currentFilter );
- m_currentFilter = TestSpec::Filter();
- }
- }
-
- TestSpec parseTestSpec( std::string const& arg ) {
- return TestSpecParser( ITagAliasRegistry::get() ).parse( arg ).testSpec();
- }
-
-} // namespace Catch
-// end catch_test_spec_parser.cpp
-// start catch_timer.cpp
-
-#include <chrono>
-
-namespace Catch {
-
- auto getCurrentNanosecondsSinceEpoch() -> uint64_t {
- return std::chrono::duration_cast<std::chrono::nanoseconds>( std::chrono::high_resolution_clock::now().time_since_epoch() ).count();
- }
-
- auto estimateClockResolution() -> uint64_t {
- uint64_t sum = 0;
- static const uint64_t iterations = 1000000;
-
- for( std::size_t i = 0; i < iterations; ++i ) {
-
- uint64_t ticks;
- uint64_t baseTicks = getCurrentNanosecondsSinceEpoch();
- do {
- ticks = getCurrentNanosecondsSinceEpoch();
- }
- while( ticks == baseTicks );
-
- auto delta = ticks - baseTicks;
- sum += delta;
- }
-
- // We're just taking the mean, here. To do better we could take the std. dev and exclude outliers
- // - and potentially do more iterations if there's a high variance.
- return sum/iterations;
- }
- auto getEstimatedClockResolution() -> uint64_t {
- static auto s_resolution = estimateClockResolution();
- return s_resolution;
- }
-
- void Timer::start() {
- m_nanoseconds = getCurrentNanosecondsSinceEpoch();
- }
- auto Timer::getElapsedNanoseconds() const -> unsigned int {
- return static_cast<unsigned int>(getCurrentNanosecondsSinceEpoch() - m_nanoseconds);
- }
- auto Timer::getElapsedMicroseconds() const -> unsigned int {
- return static_cast<unsigned int>(getElapsedNanoseconds()/1000);
- }
- auto Timer::getElapsedMilliseconds() const -> unsigned int {
- return static_cast<unsigned int>(getElapsedMicroseconds()/1000);
- }
- auto Timer::getElapsedSeconds() const -> double {
- return getElapsedMicroseconds()/1000000.0;
- }
-
-} // namespace Catch
-// end catch_timer.cpp
-// start catch_tostring.cpp
-
-#if defined(__clang__)
-# pragma clang diagnostic push
-# pragma clang diagnostic ignored "-Wexit-time-destructors"
-# pragma clang diagnostic ignored "-Wglobal-constructors"
-#endif
-
-#include <iomanip>
-
-namespace Catch {
-
-namespace Detail {
-
- const std::string unprintableString = "{?}";
-
- namespace {
- const int hexThreshold = 255;
-
- struct Endianness {
- enum Arch { Big, Little };
-
- static Arch which() {
- union _{
- int asInt;
- char asChar[sizeof (int)];
- } u;
-
- u.asInt = 1;
- return ( u.asChar[sizeof(int)-1] == 1 ) ? Big : Little;
- }
- };
- }
-
- std::string rawMemoryToString( const void *object, std::size_t size ) {
- // Reverse order for little endian architectures
- int i = 0, end = static_cast<int>( size ), inc = 1;
- if( Endianness::which() == Endianness::Little ) {
- i = end-1;
- end = inc = -1;
- }
-
- unsigned char const *bytes = static_cast<unsigned char const *>(object);
- std::ostringstream os;
- os << "0x" << std::setfill('0') << std::hex;
- for( ; i != end; i += inc )
- os << std::setw(2) << static_cast<unsigned>(bytes[i]);
- return os.str();
- }
-}
-
-template<typename T>
-std::string fpToString( T value, int precision ) {
- std::ostringstream oss;
- oss << std::setprecision( precision )
- << std::fixed
- << value;
- std::string d = oss.str();
- std::size_t i = d.find_last_not_of( '0' );
- if( i != std::string::npos && i != d.size()-1 ) {
- if( d[i] == '.' )
- i++;
- d = d.substr( 0, i+1 );
- }
- return d;
-}
-
-//// ======================================================= ////
-//
-// Out-of-line defs for full specialization of StringMaker
-//
-//// ======================================================= ////
-
-std::string StringMaker<std::string>::convert(const std::string& str) {
- if (!getCurrentContext().getConfig()->showInvisibles()) {
- return '"' + str + '"';
- }
-
- std::string s("\"");
- for (char c : str) {
- switch (c) {
- case '\n':
- s.append("\\n");
- break;
- case '\t':
- s.append("\\t");
- break;
- default:
- s.push_back(c);
- break;
- }
- }
- s.append("\"");
- return s;
-}
-
-std::string StringMaker<std::wstring>::convert(const std::wstring& wstr) {
- std::string s;
- s.reserve(wstr.size());
- for (auto c : wstr) {
- s += (c <= 0xff) ? static_cast<char>(c) : '?';
- }
- return ::Catch::Detail::stringify(s);
-}
-
-std::string StringMaker<char const*>::convert(char const* str) {
- if (str) {
- return ::Catch::Detail::stringify(std::string{ str });
- } else {
- return{ "{null string}" };
- }
-}
-std::string StringMaker<char*>::convert(char* str) {
- if (str) {
- return ::Catch::Detail::stringify(std::string{ str });
- } else {
- return{ "{null string}" };
- }
-}
-std::string StringMaker<wchar_t const*>::convert(wchar_t const * str) {
- if (str) {
- return ::Catch::Detail::stringify(std::wstring{ str });
- } else {
- return{ "{null string}" };
- }
-}
-std::string StringMaker<wchar_t *>::convert(wchar_t * str) {
- if (str) {
- return ::Catch::Detail::stringify(std::wstring{ str });
- } else {
- return{ "{null string}" };
- }
-}
-
-std::string StringMaker<int>::convert(int value) {
- return ::Catch::Detail::stringify(static_cast<long long>(value));
-}
-std::string StringMaker<long>::convert(long value) {
- return ::Catch::Detail::stringify(static_cast<long long>(value));
-}
-std::string StringMaker<long long>::convert(long long value) {
- std::ostringstream oss;
- oss << value;
- if (value > Detail::hexThreshold) {
- oss << " (0x" << std::hex << value << ')';
- }
- return oss.str();
-}
-
-std::string StringMaker<unsigned int>::convert(unsigned int value) {
- return ::Catch::Detail::stringify(static_cast<unsigned long long>(value));
-}
-std::string StringMaker<unsigned long>::convert(unsigned long value) {
- return ::Catch::Detail::stringify(static_cast<unsigned long long>(value));
-}
-std::string StringMaker<unsigned long long>::convert(unsigned long long value) {
- std::ostringstream oss;
- oss << value;
- if (value > Detail::hexThreshold) {
- oss << " (0x" << std::hex << value << ')';
- }
- return oss.str();
-}
-
-std::string StringMaker<bool>::convert(bool b) {
- return b ? "true" : "false";
-}
-
-std::string StringMaker<char>::convert(char value) {
- if (value == '\r') {
- return "'\\r'";
- } else if (value == '\f') {
- return "'\\f'";
- } else if (value == '\n') {
- return "'\\n'";
- } else if (value == '\t') {
- return "'\\t'";
- } else if ('\0' <= value && value < ' ') {
- return ::Catch::Detail::stringify(static_cast<unsigned int>(value));
- } else {
- char chstr[] = "' '";
- chstr[1] = value;
- return chstr;
- }
-}
-std::string StringMaker<signed char>::convert(signed char c) {
- return ::Catch::Detail::stringify(static_cast<char>(c));
-}
-std::string StringMaker<unsigned char>::convert(unsigned char c) {
- return ::Catch::Detail::stringify(static_cast<char>(c));
-}
-
-std::string StringMaker<std::nullptr_t>::convert(std::nullptr_t) {
- return "nullptr";
-}
-
-std::string StringMaker<float>::convert(float value) {
- return fpToString(value, 5) + 'f';
-}
-std::string StringMaker<double>::convert(double value) {
- return fpToString(value, 10);
-}
-
-} // end namespace Catch
-
-#if defined(__clang__)
-# pragma clang diagnostic pop
-#endif
-
-// end catch_tostring.cpp
-// start catch_totals.cpp
-
-namespace Catch {
-
- Counts Counts::operator - ( Counts const& other ) const {
- Counts diff;
- diff.passed = passed - other.passed;
- diff.failed = failed - other.failed;
- diff.failedButOk = failedButOk - other.failedButOk;
- return diff;
- }
-
- Counts& Counts::operator += ( Counts const& other ) {
- passed += other.passed;
- failed += other.failed;
- failedButOk += other.failedButOk;
- return *this;
- }
-
- std::size_t Counts::total() const {
- return passed + failed + failedButOk;
- }
- bool Counts::allPassed() const {
- return failed == 0 && failedButOk == 0;
- }
- bool Counts::allOk() const {
- return failed == 0;
- }
-
- Totals Totals::operator - ( Totals const& other ) const {
- Totals diff;
- diff.assertions = assertions - other.assertions;
- diff.testCases = testCases - other.testCases;
- return diff;
- }
-
- Totals& Totals::operator += ( Totals const& other ) {
- assertions += other.assertions;
- testCases += other.testCases;
- return *this;
- }
-
- Totals Totals::delta( Totals const& prevTotals ) const {
- Totals diff = *this - prevTotals;
- if( diff.assertions.failed > 0 )
- ++diff.testCases.failed;
- else if( diff.assertions.failedButOk > 0 )
- ++diff.testCases.failedButOk;
- else
- ++diff.testCases.passed;
- return diff;
- }
-
-}
-// end catch_totals.cpp
-// start catch_version.cpp
-
-#include <ostream>
-
-namespace Catch {
-
- Version::Version
- ( unsigned int _majorVersion,
- unsigned int _minorVersion,
- unsigned int _patchNumber,
- char const * const _branchName,
- unsigned int _buildNumber )
- : majorVersion( _majorVersion ),
- minorVersion( _minorVersion ),
- patchNumber( _patchNumber ),
- branchName( _branchName ),
- buildNumber( _buildNumber )
- {}
-
- std::ostream& operator << ( std::ostream& os, Version const& version ) {
- os << version.majorVersion << '.'
- << version.minorVersion << '.'
- << version.patchNumber;
- // branchName is never null -> 0th char is \0 if it is empty
- if (version.branchName[0]) {
- os << '-' << version.branchName
- << '.' << version.buildNumber;
- }
- return os;
- }
-
- Version const& libraryVersion() {
- static Version version( 2, 0, 1, "", 0 );
- return version;
- }
-
-}
-// end catch_version.cpp
-// start catch_wildcard_pattern.cpp
-
-namespace Catch {
-
- WildcardPattern::WildcardPattern( std::string const& pattern,
- CaseSensitive::Choice caseSensitivity )
- : m_caseSensitivity( caseSensitivity ),
- m_pattern( adjustCase( pattern ) )
- {
- if( startsWith( m_pattern, '*' ) ) {
- m_pattern = m_pattern.substr( 1 );
- m_wildcard = WildcardAtStart;
- }
- if( endsWith( m_pattern, '*' ) ) {
- m_pattern = m_pattern.substr( 0, m_pattern.size()-1 );
- m_wildcard = static_cast<WildcardPosition>( m_wildcard | WildcardAtEnd );
- }
- }
-
- bool WildcardPattern::matches( std::string const& str ) const {
- switch( m_wildcard ) {
- case NoWildcard:
- return m_pattern == adjustCase( str );
- case WildcardAtStart:
- return endsWith( adjustCase( str ), m_pattern );
- case WildcardAtEnd:
- return startsWith( adjustCase( str ), m_pattern );
- case WildcardAtBothEnds:
- return contains( adjustCase( str ), m_pattern );
- default:
- CATCH_INTERNAL_ERROR( "Unknown enum" );
- }
- }
-
- std::string WildcardPattern::adjustCase( std::string const& str ) const {
- return m_caseSensitivity == CaseSensitive::No ? toLower( str ) : str;
- }
-}
-// end catch_wildcard_pattern.cpp
-// start catch_xmlwriter.cpp
-
-// start catch_xmlwriter.h
-
-#include <sstream>
-#include <vector>
-
-namespace Catch {
-
- class XmlEncode {
- public:
- enum ForWhat { ForTextNodes, ForAttributes };
-
- XmlEncode( std::string const& str, ForWhat forWhat = ForTextNodes );
-
- void encodeTo( std::ostream& os ) const;
-
- friend std::ostream& operator << ( std::ostream& os, XmlEncode const& xmlEncode );
-
- private:
- std::string m_str;
- ForWhat m_forWhat;
- };
-
- class XmlWriter {
- public:
-
- class ScopedElement {
- public:
- ScopedElement( XmlWriter* writer );
-
- ScopedElement( ScopedElement&& other ) noexcept;
- ScopedElement& operator=( ScopedElement&& other ) noexcept;
-
- ~ScopedElement();
-
- ScopedElement& writeText( std::string const& text, bool indent = true );
-
- template<typename T>
- ScopedElement& writeAttribute( std::string const& name, T const& attribute ) {
- m_writer->writeAttribute( name, attribute );
- return *this;
- }
-
- private:
- mutable XmlWriter* m_writer = nullptr;
- };
-
- XmlWriter( std::ostream& os = Catch::cout() );
- ~XmlWriter();
-
- XmlWriter( XmlWriter const& ) = delete;
- XmlWriter& operator=( XmlWriter const& ) = delete;
-
- XmlWriter& startElement( std::string const& name );
-
- ScopedElement scopedElement( std::string const& name );
-
- XmlWriter& endElement();
-
- XmlWriter& writeAttribute( std::string const& name, std::string const& attribute );
-
- XmlWriter& writeAttribute( std::string const& name, bool attribute );
-
- template<typename T>
- XmlWriter& writeAttribute( std::string const& name, T const& attribute ) {
- m_oss.clear();
- m_oss.str(std::string());
- m_oss << attribute;
- return writeAttribute( name, m_oss.str() );
- }
-
- XmlWriter& writeText( std::string const& text, bool indent = true );
-
- XmlWriter& writeComment( std::string const& text );
-
- void writeStylesheetRef( std::string const& url );
-
- XmlWriter& writeBlankLine();
-
- void ensureTagClosed();
-
- private:
-
- void writeDeclaration();
-
- void newlineIfNecessary();
-
- bool m_tagIsOpen = false;
- bool m_needsNewline = false;
- std::vector<std::string> m_tags;
- std::string m_indent;
- std::ostream& m_os;
- std::ostringstream m_oss;
- };
-
-}
-
-// end catch_xmlwriter.h
-#include <iomanip>
-
-namespace Catch {
-
- XmlEncode::XmlEncode( std::string const& str, ForWhat forWhat )
- : m_str( str ),
- m_forWhat( forWhat )
- {}
-
- void XmlEncode::encodeTo( std::ostream& os ) const {
-
- // Apostrophe escaping not necessary if we always use " to write attributes
- // (see: http://www.w3.org/TR/xml/#syntax)
-
- for( std::size_t i = 0; i < m_str.size(); ++ i ) {
- char c = m_str[i];
- switch( c ) {
- case '<': os << "<"; break;
- case '&': os << "&"; break;
-
- case '>':
- // See: http://www.w3.org/TR/xml/#syntax
- if( i > 2 && m_str[i-1] == ']' && m_str[i-2] == ']' )
- os << ">";
- else
- os << c;
- break;
-
- case '\"':
- if( m_forWhat == ForAttributes )
- os << """;
- else
- os << c;
- break;
-
- default:
- // Escape control chars - based on contribution by @espenalb in PR #465 and
- // by @mrpi PR #588
- if ( ( c >= 0 && c < '\x09' ) || ( c > '\x0D' && c < '\x20') || c=='\x7F' ) {
- // see http://stackoverflow.com/questions/404107/why-are-control-characters-illegal-in-xml-1-0
- os << "\\x" << std::uppercase << std::hex << std::setfill('0') << std::setw(2)
- << static_cast<int>( c );
- }
- else
- os << c;
- }
- }
- }
-
- std::ostream& operator << ( std::ostream& os, XmlEncode const& xmlEncode ) {
- xmlEncode.encodeTo( os );
- return os;
- }
-
- XmlWriter::ScopedElement::ScopedElement( XmlWriter* writer )
- : m_writer( writer )
- {}
-
- XmlWriter::ScopedElement::ScopedElement( ScopedElement&& other ) noexcept
- : m_writer( other.m_writer ){
- other.m_writer = nullptr;
- }
- XmlWriter::ScopedElement& XmlWriter::ScopedElement::operator=( ScopedElement&& other ) noexcept {
- if ( m_writer ) {
- m_writer->endElement();
- }
- m_writer = other.m_writer;
- other.m_writer = nullptr;
- return *this;
- }
-
- XmlWriter::ScopedElement::~ScopedElement() {
- if( m_writer )
- m_writer->endElement();
- }
-
- XmlWriter::ScopedElement& XmlWriter::ScopedElement::writeText( std::string const& text, bool indent ) {
- m_writer->writeText( text, indent );
- return *this;
- }
-
- XmlWriter::XmlWriter( std::ostream& os ) : m_os( os )
- {
- writeDeclaration();
- }
-
- XmlWriter::~XmlWriter() {
- while( !m_tags.empty() )
- endElement();
- }
-
- XmlWriter& XmlWriter::startElement( std::string const& name ) {
- ensureTagClosed();
- newlineIfNecessary();
- m_os << m_indent << '<' << name;
- m_tags.push_back( name );
- m_indent += " ";
- m_tagIsOpen = true;
- return *this;
- }
-
- XmlWriter::ScopedElement XmlWriter::scopedElement( std::string const& name ) {
- ScopedElement scoped( this );
- startElement( name );
- return scoped;
- }
-
- XmlWriter& XmlWriter::endElement() {
- newlineIfNecessary();
- m_indent = m_indent.substr( 0, m_indent.size()-2 );
- if( m_tagIsOpen ) {
- m_os << "/>";
- m_tagIsOpen = false;
- }
- else {
- m_os << m_indent << "</" << m_tags.back() << ">";
- }
- m_os << std::endl;
- m_tags.pop_back();
- return *this;
- }
-
- XmlWriter& XmlWriter::writeAttribute( std::string const& name, std::string const& attribute ) {
- if( !name.empty() && !attribute.empty() )
- m_os << ' ' << name << "=\"" << XmlEncode( attribute, XmlEncode::ForAttributes ) << '"';
- return *this;
- }
-
- XmlWriter& XmlWriter::writeAttribute( std::string const& name, bool attribute ) {
- m_os << ' ' << name << "=\"" << ( attribute ? "true" : "false" ) << '"';
- return *this;
- }
-
- XmlWriter& XmlWriter::writeText( std::string const& text, bool indent ) {
- if( !text.empty() ){
- bool tagWasOpen = m_tagIsOpen;
- ensureTagClosed();
- if( tagWasOpen && indent )
- m_os << m_indent;
- m_os << XmlEncode( text );
- m_needsNewline = true;
- }
- return *this;
- }
-
- XmlWriter& XmlWriter::writeComment( std::string const& text ) {
- ensureTagClosed();
- m_os << m_indent << "<!--" << text << "-->";
- m_needsNewline = true;
- return *this;
- }
-
- void XmlWriter::writeStylesheetRef( std::string const& url ) {
- m_os << "<?xml-stylesheet type=\"text/xsl\" href=\"" << url << "\"?>\n";
- }
-
- XmlWriter& XmlWriter::writeBlankLine() {
- ensureTagClosed();
- m_os << '\n';
- return *this;
- }
-
- void XmlWriter::ensureTagClosed() {
- if( m_tagIsOpen ) {
- m_os << ">" << std::endl;
- m_tagIsOpen = false;
- }
- }
-
- void XmlWriter::writeDeclaration() {
- m_os << "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n";
- }
-
- void XmlWriter::newlineIfNecessary() {
- if( m_needsNewline ) {
- m_os << std::endl;
- m_needsNewline = false;
- }
- }
-}
-// end catch_xmlwriter.cpp
-// start catch_reporter_bases.cpp
-
-#include <cstring>
-#include <cfloat>
-#include <cstdio>
-#include <assert.h>
-#include <memory>
-
-namespace Catch {
- void prepareExpandedExpression(AssertionResult& result) {
- result.getExpandedExpression();
- }
-
- // Because formatting using c++ streams is stateful, drop down to C is required
- // Alternatively we could use stringstream, but its performance is... not good.
- std::string getFormattedDuration( double duration ) {
- // Max exponent + 1 is required to represent the whole part
- // + 1 for decimal point
- // + 3 for the 3 decimal places
- // + 1 for null terminator
- const std::size_t maxDoubleSize = DBL_MAX_10_EXP + 1 + 1 + 3 + 1;
- char buffer[maxDoubleSize];
-
- // Save previous errno, to prevent sprintf from overwriting it
- ErrnoGuard guard;
-#ifdef _MSC_VER
- sprintf_s(buffer, "%.3f", duration);
-#else
- sprintf(buffer, "%.3f", duration);
-#endif
- return std::string(buffer);
- }
-
- TestEventListenerBase::TestEventListenerBase(ReporterConfig const & _config)
- :StreamingReporterBase(_config) {}
-
- void TestEventListenerBase::assertionStarting(AssertionInfo const &) {}
-
- bool TestEventListenerBase::assertionEnded(AssertionStats const &) {
- return false;
- }
-
-} // end namespace Catch
-// end catch_reporter_bases.cpp
-// start catch_reporter_compact.cpp
-
-namespace {
-
-#ifdef CATCH_PLATFORM_MAC
- const char* failedString() { return "FAILED"; }
- const char* passedString() { return "PASSED"; }
-#else
- const char* failedString() { return "failed"; }
- const char* passedString() { return "passed"; }
-#endif
-
- // Colour::LightGrey
- Catch::Colour::Code dimColour() { return Catch::Colour::FileName; }
-
- std::string bothOrAll( std::size_t count ) {
- return count == 1 ? std::string() :
- count == 2 ? "both " : "all " ;
- }
-}
-
-namespace Catch {
-
- struct CompactReporter : StreamingReporterBase<CompactReporter> {
-
- using StreamingReporterBase::StreamingReporterBase;
-
- ~CompactReporter() override;
-
- static std::string getDescription() {
- return "Reports test results on a single line, suitable for IDEs";
- }
-
- ReporterPreferences getPreferences() const override {
- ReporterPreferences prefs;
- prefs.shouldRedirectStdOut = false;
- return prefs;
- }
-
- void noMatchingTestCases( std::string const& spec ) override {
- stream << "No test cases matched '" << spec << '\'' << std::endl;
- }
-
- void assertionStarting( AssertionInfo const& ) override {}
-
- bool assertionEnded( AssertionStats const& _assertionStats ) override {
- AssertionResult const& result = _assertionStats.assertionResult;
-
- bool printInfoMessages = true;
-
- // Drop out if result was successful and we're not printing those
- if( !m_config->includeSuccessfulResults() && result.isOk() ) {
- if( result.getResultType() != ResultWas::Warning )
- return false;
- printInfoMessages = false;
- }
-
- AssertionPrinter printer( stream, _assertionStats, printInfoMessages );
- printer.print();
-
- stream << std::endl;
- return true;
- }
-
- void sectionEnded(SectionStats const& _sectionStats) override {
- if (m_config->showDurations() == ShowDurations::Always) {
- stream << getFormattedDuration(_sectionStats.durationInSeconds) << " s: " << _sectionStats.sectionInfo.name << std::endl;
- }
- }
-
- void testRunEnded( TestRunStats const& _testRunStats ) override {
- printTotals( _testRunStats.totals );
- stream << '\n' << std::endl;
- StreamingReporterBase::testRunEnded( _testRunStats );
- }
-
- private:
- class AssertionPrinter {
- public:
- AssertionPrinter& operator= ( AssertionPrinter const& ) = delete;
- AssertionPrinter( AssertionPrinter const& ) = delete;
- AssertionPrinter( std::ostream& _stream, AssertionStats const& _stats, bool _printInfoMessages )
- : stream( _stream )
- , result( _stats.assertionResult )
- , messages( _stats.infoMessages )
- , itMessage( _stats.infoMessages.begin() )
- , printInfoMessages( _printInfoMessages )
- {}
-
- void print() {
- printSourceInfo();
-
- itMessage = messages.begin();
-
- switch( result.getResultType() ) {
- case ResultWas::Ok:
- printResultType( Colour::ResultSuccess, passedString() );
- printOriginalExpression();
- printReconstructedExpression();
- if ( ! result.hasExpression() )
- printRemainingMessages( Colour::None );
- else
- printRemainingMessages();
- break;
- case ResultWas::ExpressionFailed:
- if( result.isOk() )
- printResultType( Colour::ResultSuccess, failedString() + std::string( " - but was ok" ) );
- else
- printResultType( Colour::Error, failedString() );
- printOriginalExpression();
- printReconstructedExpression();
- printRemainingMessages();
- break;
- case ResultWas::ThrewException:
- printResultType( Colour::Error, failedString() );
- printIssue( "unexpected exception with message:" );
- printMessage();
- printExpressionWas();
- printRemainingMessages();
- break;
- case ResultWas::FatalErrorCondition:
- printResultType( Colour::Error, failedString() );
- printIssue( "fatal error condition with message:" );
- printMessage();
- printExpressionWas();
- printRemainingMessages();
- break;
- case ResultWas::DidntThrowException:
- printResultType( Colour::Error, failedString() );
- printIssue( "expected exception, got none" );
- printExpressionWas();
- printRemainingMessages();
- break;
- case ResultWas::Info:
- printResultType( Colour::None, "info" );
- printMessage();
- printRemainingMessages();
- break;
- case ResultWas::Warning:
- printResultType( Colour::None, "warning" );
- printMessage();
- printRemainingMessages();
- break;
- case ResultWas::ExplicitFailure:
- printResultType( Colour::Error, failedString() );
- printIssue( "explicitly" );
- printRemainingMessages( Colour::None );
- break;
- // These cases are here to prevent compiler warnings
- case ResultWas::Unknown:
- case ResultWas::FailureBit:
- case ResultWas::Exception:
- printResultType( Colour::Error, "** internal error **" );
- break;
- }
- }
-
- private:
- void printSourceInfo() const {
- Colour colourGuard( Colour::FileName );
- stream << result.getSourceInfo() << ':';
- }
-
- void printResultType( Colour::Code colour, std::string const& passOrFail ) const {
- if( !passOrFail.empty() ) {
- {
- Colour colourGuard( colour );
- stream << ' ' << passOrFail;
- }
- stream << ':';
- }
- }
-
- void printIssue( std::string const& issue ) const {
- stream << ' ' << issue;
- }
-
- void printExpressionWas() {
- if( result.hasExpression() ) {
- stream << ';';
- {
- Colour colour( dimColour() );
- stream << " expression was:";
- }
- printOriginalExpression();
- }
- }
-
- void printOriginalExpression() const {
- if( result.hasExpression() ) {
- stream << ' ' << result.getExpression();
- }
- }
-
- void printReconstructedExpression() const {
- if( result.hasExpandedExpression() ) {
- {
- Colour colour( dimColour() );
- stream << " for: ";
- }
- stream << result.getExpandedExpression();
- }
- }
-
- void printMessage() {
- if ( itMessage != messages.end() ) {
- stream << " '" << itMessage->message << '\'';
- ++itMessage;
- }
- }
-
- void printRemainingMessages( Colour::Code colour = dimColour() ) {
- if ( itMessage == messages.end() )
- return;
-
- // using messages.end() directly yields (or auto) compilation error:
- std::vector<MessageInfo>::const_iterator itEnd = messages.end();
- const std::size_t N = static_cast<std::size_t>( std::distance( itMessage, itEnd ) );
-
- {
- Colour colourGuard( colour );
- stream << " with " << pluralise( N, "message" ) << ':';
- }
-
- for(; itMessage != itEnd; ) {
- // If this assertion is a warning ignore any INFO messages
- if( printInfoMessages || itMessage->type != ResultWas::Info ) {
- stream << " '" << itMessage->message << '\'';
- if ( ++itMessage != itEnd ) {
- Colour colourGuard( dimColour() );
- stream << " and";
- }
- }
- }
- }
-
- private:
- std::ostream& stream;
- AssertionResult const& result;
- std::vector<MessageInfo> messages;
- std::vector<MessageInfo>::const_iterator itMessage;
- bool printInfoMessages;
- };
-
- // Colour, message variants:
- // - white: No tests ran.
- // - red: Failed [both/all] N test cases, failed [both/all] M assertions.
- // - white: Passed [both/all] N test cases (no assertions).
- // - red: Failed N tests cases, failed M assertions.
- // - green: Passed [both/all] N tests cases with M assertions.
-
- void printTotals( const Totals& totals ) const {
- if( totals.testCases.total() == 0 ) {
- stream << "No tests ran.";
- }
- else if( totals.testCases.failed == totals.testCases.total() ) {
- Colour colour( Colour::ResultError );
- const std::string qualify_assertions_failed =
- totals.assertions.failed == totals.assertions.total() ?
- bothOrAll( totals.assertions.failed ) : std::string();
- stream <<
- "Failed " << bothOrAll( totals.testCases.failed )
- << pluralise( totals.testCases.failed, "test case" ) << ", "
- "failed " << qualify_assertions_failed <<
- pluralise( totals.assertions.failed, "assertion" ) << '.';
- }
- else if( totals.assertions.total() == 0 ) {
- stream <<
- "Passed " << bothOrAll( totals.testCases.total() )
- << pluralise( totals.testCases.total(), "test case" )
- << " (no assertions).";
- }
- else if( totals.assertions.failed ) {
- Colour colour( Colour::ResultError );
- stream <<
- "Failed " << pluralise( totals.testCases.failed, "test case" ) << ", "
- "failed " << pluralise( totals.assertions.failed, "assertion" ) << '.';
- }
- else {
- Colour colour( Colour::ResultSuccess );
- stream <<
- "Passed " << bothOrAll( totals.testCases.passed )
- << pluralise( totals.testCases.passed, "test case" ) <<
- " with " << pluralise( totals.assertions.passed, "assertion" ) << '.';
- }
- }
- };
-
- CompactReporter::~CompactReporter() {}
-
- CATCH_REGISTER_REPORTER( "compact", CompactReporter )
-
-} // end namespace Catch
-// end catch_reporter_compact.cpp
-// start catch_reporter_console.cpp
-
-#include <cfloat>
-#include <cstdio>
-
-#if defined(_MSC_VER)
-#pragma warning(push)
-#pragma warning(disable:4061) // Not all labels are EXPLICITLY handled in switch
- // Note that 4062 (not all labels are handled
- // and default is missing) is enabled
-#endif
-
-namespace Catch {
-
- namespace {
- std::size_t makeRatio( std::size_t number, std::size_t total ) {
- std::size_t ratio = total > 0 ? CATCH_CONFIG_CONSOLE_WIDTH * number/ total : 0;
- return ( ratio == 0 && number > 0 ) ? 1 : ratio;
- }
-
- std::size_t& findMax( std::size_t& i, std::size_t& j, std::size_t& k ) {
- if( i > j && i > k )
- return i;
- else if( j > k )
- return j;
- else
- return k;
- }
-
- struct ColumnInfo {
- enum Justification { Left, Right };
- std::string name;
- int width;
- Justification justification;
- };
- struct ColumnBreak {};
- struct RowBreak {};
-
- class TablePrinter {
- std::ostream& m_os;
- std::vector<ColumnInfo> m_columnInfos;
- std::ostringstream m_oss;
- int m_currentColumn = -1;
- bool m_isOpen = false;
-
- public:
- TablePrinter( std::ostream& os, std::vector<ColumnInfo> const& columnInfos )
- : m_os( os ),
- m_columnInfos( columnInfos )
- {}
-
- auto columnInfos() const -> std::vector<ColumnInfo> const& {
- return m_columnInfos;
- }
-
- void open() {
- if( !m_isOpen ) {
- m_isOpen = true;
- *this << RowBreak();
- for( auto const& info : m_columnInfos )
- *this << info.name << ColumnBreak();
- *this << RowBreak();
- m_os << Catch::getLineOfChars<'-'>() << "\n";
- }
- }
- void close() {
- if( m_isOpen ) {
- *this << RowBreak();
- m_os << std::endl;
- m_isOpen = false;
- }
- }
-
- template<typename T>
- friend TablePrinter& operator << ( TablePrinter& tp, T const& value ) {
- tp.m_oss << value;
- return tp;
- }
-
- friend TablePrinter& operator << ( TablePrinter& tp, ColumnBreak ) {
- auto colStr = tp.m_oss.str();
- // This takes account of utf8 encodings
- auto strSize = Catch::StringRef( colStr ).numberOfCharacters();
- tp.m_oss.str("");
- tp.open();
- if( tp.m_currentColumn == static_cast<int>(tp.m_columnInfos.size()-1) ) {
- tp.m_currentColumn = -1;
- tp.m_os << "\n";
- }
- tp.m_currentColumn++;
-
- auto colInfo = tp.m_columnInfos[tp.m_currentColumn];
- auto padding = ( strSize+2 < static_cast<std::size_t>( colInfo.width ) )
- ? std::string( colInfo.width-(strSize+2), ' ' )
- : std::string();
- if( colInfo.justification == ColumnInfo::Left )
- tp.m_os << colStr << padding << " ";
- else
- tp.m_os << padding << colStr << " ";
- return tp;
- }
-
- friend TablePrinter& operator << ( TablePrinter& tp, RowBreak ) {
- if( tp.m_currentColumn > 0 ) {
- tp.m_os << "\n";
- tp.m_currentColumn = -1;
- }
- return tp;
- }
- };
-
- class Duration {
- enum class Unit {
- Auto,
- Nanoseconds,
- Microseconds,
- Milliseconds,
- Seconds,
- Minutes
- };
- static const uint64_t s_nanosecondsInAMicrosecond = 1000;
- static const uint64_t s_nanosecondsInAMillisecond = 1000*s_nanosecondsInAMicrosecond;
- static const uint64_t s_nanosecondsInASecond = 1000*s_nanosecondsInAMillisecond;
- static const uint64_t s_nanosecondsInAMinute = 60*s_nanosecondsInASecond;
-
- uint64_t m_inNanoseconds;
- Unit m_units;
-
- public:
- Duration( uint64_t inNanoseconds, Unit units = Unit::Auto )
- : m_inNanoseconds( inNanoseconds ),
- m_units( units )
- {
- if( m_units == Unit::Auto ) {
- if( m_inNanoseconds < s_nanosecondsInAMicrosecond )
- m_units = Unit::Nanoseconds;
- else if( m_inNanoseconds < s_nanosecondsInAMillisecond )
- m_units = Unit::Microseconds;
- else if( m_inNanoseconds < s_nanosecondsInASecond )
- m_units = Unit::Milliseconds;
- else if( m_inNanoseconds < s_nanosecondsInAMinute )
- m_units = Unit::Seconds;
- else
- m_units = Unit::Minutes;
- }
-
- }
-
- auto value() const -> double {
- switch( m_units ) {
- case Unit::Microseconds:
- return m_inNanoseconds / static_cast<double>( s_nanosecondsInAMicrosecond );
- case Unit::Milliseconds:
- return m_inNanoseconds / static_cast<double>( s_nanosecondsInAMillisecond );
- case Unit::Seconds:
- return m_inNanoseconds / static_cast<double>( s_nanosecondsInASecond );
- case Unit::Minutes:
- return m_inNanoseconds / static_cast<double>( s_nanosecondsInAMinute );
- default:
- return static_cast<double>( m_inNanoseconds );
- }
- }
- auto unitsAsString() const -> std::string {
- switch( m_units ) {
- case Unit::Nanoseconds:
- return "ns";
- case Unit::Microseconds:
- return "µs";
- case Unit::Milliseconds:
- return "ms";
- case Unit::Seconds:
- return "s";
- case Unit::Minutes:
- return "m";
- default:
- return "** internal error **";
- }
-
- }
- friend auto operator << ( std::ostream& os, Duration const& duration ) -> std::ostream& {
- return os << duration.value() << " " << duration.unitsAsString();
- }
- };
- } // end anon namespace
-
- struct ConsoleReporter : StreamingReporterBase<ConsoleReporter> {
- TablePrinter m_tablePrinter;
-
- ConsoleReporter( ReporterConfig const& config )
- : StreamingReporterBase( config ),
- m_tablePrinter( config.stream(),
- {
- { "benchmark name", CATCH_CONFIG_CONSOLE_WIDTH-32, ColumnInfo::Left },
- { "iters", 8, ColumnInfo::Right },
- { "elapsed ns", 14, ColumnInfo::Right },
- { "average", 14, ColumnInfo::Right }
- } )
- {}
- ~ConsoleReporter() override;
- static std::string getDescription() {
- return "Reports test results as plain lines of text";
- }
-
- void noMatchingTestCases( std::string const& spec ) override {
- stream << "No test cases matched '" << spec << '\'' << std::endl;
- }
-
- void assertionStarting( AssertionInfo const& ) override {
- }
-
- bool assertionEnded( AssertionStats const& _assertionStats ) override {
- AssertionResult const& result = _assertionStats.assertionResult;
-
- bool includeResults = m_config->includeSuccessfulResults() || !result.isOk();
-
- // Drop out if result was successful but we're not printing them.
- if( !includeResults && result.getResultType() != ResultWas::Warning )
- return false;
-
- lazyPrint();
-
- AssertionPrinter printer( stream, _assertionStats, includeResults );
- printer.print();
- stream << std::endl;
- return true;
- }
-
- void sectionStarting( SectionInfo const& _sectionInfo ) override {
- m_headerPrinted = false;
- StreamingReporterBase::sectionStarting( _sectionInfo );
- }
- void sectionEnded( SectionStats const& _sectionStats ) override {
- m_tablePrinter.close();
- if( _sectionStats.missingAssertions ) {
- lazyPrint();
- Colour colour( Colour::ResultError );
- if( m_sectionStack.size() > 1 )
- stream << "\nNo assertions in section";
- else
- stream << "\nNo assertions in test case";
- stream << " '" << _sectionStats.sectionInfo.name << "'\n" << std::endl;
- }
- if( m_config->showDurations() == ShowDurations::Always ) {
- stream << getFormattedDuration(_sectionStats.durationInSeconds) << " s: " << _sectionStats.sectionInfo.name << std::endl;
- }
- if( m_headerPrinted ) {
- m_headerPrinted = false;
- }
- StreamingReporterBase::sectionEnded( _sectionStats );
- }
-
- void benchmarkStarting( BenchmarkInfo const& info ) override {
- lazyPrintWithoutClosingBenchmarkTable();
-
- auto nameCol = Column( info.name ).width( m_tablePrinter.columnInfos()[0].width-2 );
-
- bool firstLine = true;
- for( auto line : nameCol ) {
- if( !firstLine )
- m_tablePrinter << ColumnBreak() << ColumnBreak() << ColumnBreak();
- else
- firstLine = false;
-
- m_tablePrinter << line << ColumnBreak();
- }
- }
- void benchmarkEnded( BenchmarkStats const& stats ) override {
- Duration average( stats.elapsedTimeInNanoseconds/stats.iterations );
- m_tablePrinter
- << stats.iterations << ColumnBreak()
- << stats.elapsedTimeInNanoseconds << ColumnBreak()
- << average << ColumnBreak();
- }
-
- void testCaseEnded( TestCaseStats const& _testCaseStats ) override {
- m_tablePrinter.close();
- StreamingReporterBase::testCaseEnded( _testCaseStats );
- m_headerPrinted = false;
- }
- void testGroupEnded( TestGroupStats const& _testGroupStats ) override {
- if( currentGroupInfo.used ) {
- printSummaryDivider();
- stream << "Summary for group '" << _testGroupStats.groupInfo.name << "':\n";
- printTotals( _testGroupStats.totals );
- stream << '\n' << std::endl;
- }
- StreamingReporterBase::testGroupEnded( _testGroupStats );
- }
- void testRunEnded( TestRunStats const& _testRunStats ) override {
- printTotalsDivider( _testRunStats.totals );
- printTotals( _testRunStats.totals );
- stream << std::endl;
- StreamingReporterBase::testRunEnded( _testRunStats );
- }
-
- private:
-
- class AssertionPrinter {
- public:
- AssertionPrinter& operator= ( AssertionPrinter const& ) = delete;
- AssertionPrinter( AssertionPrinter const& ) = delete;
- AssertionPrinter( std::ostream& _stream, AssertionStats const& _stats, bool _printInfoMessages )
- : stream( _stream ),
- stats( _stats ),
- result( _stats.assertionResult ),
- colour( Colour::None ),
- message( result.getMessage() ),
- messages( _stats.infoMessages ),
- printInfoMessages( _printInfoMessages )
- {
- switch( result.getResultType() ) {
- case ResultWas::Ok:
- colour = Colour::Success;
- passOrFail = "PASSED";
- //if( result.hasMessage() )
- if( _stats.infoMessages.size() == 1 )
- messageLabel = "with message";
- if( _stats.infoMessages.size() > 1 )
- messageLabel = "with messages";
- break;
- case ResultWas::ExpressionFailed:
- if( result.isOk() ) {
- colour = Colour::Success;
- passOrFail = "FAILED - but was ok";
- }
- else {
- colour = Colour::Error;
- passOrFail = "FAILED";
- }
- if( _stats.infoMessages.size() == 1 )
- messageLabel = "with message";
- if( _stats.infoMessages.size() > 1 )
- messageLabel = "with messages";
- break;
- case ResultWas::ThrewException:
- colour = Colour::Error;
- passOrFail = "FAILED";
- messageLabel = "due to unexpected exception with ";
- if (_stats.infoMessages.size() == 1)
- messageLabel += "message";
- if (_stats.infoMessages.size() > 1)
- messageLabel += "messages";
- break;
- case ResultWas::FatalErrorCondition:
- colour = Colour::Error;
- passOrFail = "FAILED";
- messageLabel = "due to a fatal error condition";
- break;
- case ResultWas::DidntThrowException:
- colour = Colour::Error;
- passOrFail = "FAILED";
- messageLabel = "because no exception was thrown where one was expected";
- break;
- case ResultWas::Info:
- messageLabel = "info";
- break;
- case ResultWas::Warning:
- messageLabel = "warning";
- break;
- case ResultWas::ExplicitFailure:
- passOrFail = "FAILED";
- colour = Colour::Error;
- if( _stats.infoMessages.size() == 1 )
- messageLabel = "explicitly with message";
- if( _stats.infoMessages.size() > 1 )
- messageLabel = "explicitly with messages";
- break;
- // These cases are here to prevent compiler warnings
- case ResultWas::Unknown:
- case ResultWas::FailureBit:
- case ResultWas::Exception:
- passOrFail = "** internal error **";
- colour = Colour::Error;
- break;
- }
- }
-
- void print() const {
- printSourceInfo();
- if( stats.totals.assertions.total() > 0 ) {
- if( result.isOk() )
- stream << '\n';
- printResultType();
- printOriginalExpression();
- printReconstructedExpression();
- }
- else {
- stream << '\n';
- }
- printMessage();
- }
-
- private:
- void printResultType() const {
- if( !passOrFail.empty() ) {
- Colour colourGuard( colour );
- stream << passOrFail << ":\n";
- }
- }
- void printOriginalExpression() const {
- if( result.hasExpression() ) {
- Colour colourGuard( Colour::OriginalExpression );
- stream << " ";
- stream << result.getExpressionInMacro();
- stream << '\n';
- }
- }
- void printReconstructedExpression() const {
- if( result.hasExpandedExpression() ) {
- stream << "with expansion:\n";
- Colour colourGuard( Colour::ReconstructedExpression );
- stream << Column( result.getExpandedExpression() ).indent(2) << '\n';
- }
- }
- void printMessage() const {
- if( !messageLabel.empty() )
- stream << messageLabel << ':' << '\n';
- for( auto const& msg : messages ) {
- // If this assertion is a warning ignore any INFO messages
- if( printInfoMessages || msg.type != ResultWas::Info )
- stream << Column( msg.message ).indent(2) << '\n';
- }
- }
- void printSourceInfo() const {
- Colour colourGuard( Colour::FileName );
- stream << result.getSourceInfo() << ": ";
- }
-
- std::ostream& stream;
- AssertionStats const& stats;
- AssertionResult const& result;
- Colour::Code colour;
- std::string passOrFail;
- std::string messageLabel;
- std::string message;
- std::vector<MessageInfo> messages;
- bool printInfoMessages;
- };
-
- void lazyPrint() {
-
- m_tablePrinter.close();
- lazyPrintWithoutClosingBenchmarkTable();
- }
-
- void lazyPrintWithoutClosingBenchmarkTable() {
-
- if( !currentTestRunInfo.used )
- lazyPrintRunInfo();
- if( !currentGroupInfo.used )
- lazyPrintGroupInfo();
-
- if( !m_headerPrinted ) {
- printTestCaseAndSectionHeader();
- m_headerPrinted = true;
- }
- }
- void lazyPrintRunInfo() {
- stream << '\n' << getLineOfChars<'~'>() << '\n';
- Colour colour( Colour::SecondaryText );
- stream << currentTestRunInfo->name
- << " is a Catch v" << libraryVersion() << " host application.\n"
- << "Run with -? for options\n\n";
-
- if( m_config->rngSeed() != 0 )
- stream << "Randomness seeded to: " << m_config->rngSeed() << "\n\n";
-
- currentTestRunInfo.used = true;
- }
- void lazyPrintGroupInfo() {
- if( !currentGroupInfo->name.empty() && currentGroupInfo->groupsCounts > 1 ) {
- printClosedHeader( "Group: " + currentGroupInfo->name );
- currentGroupInfo.used = true;
- }
- }
- void printTestCaseAndSectionHeader() {
- assert( !m_sectionStack.empty() );
- printOpenHeader( currentTestCaseInfo->name );
-
- if( m_sectionStack.size() > 1 ) {
- Colour colourGuard( Colour::Headers );
-
- auto
- it = m_sectionStack.begin()+1, // Skip first section (test case)
- itEnd = m_sectionStack.end();
- for( ; it != itEnd; ++it )
- printHeaderString( it->name, 2 );
- }
-
- SourceLineInfo lineInfo = m_sectionStack.back().lineInfo;
-
- if( !lineInfo.empty() ){
- stream << getLineOfChars<'-'>() << '\n';
- Colour colourGuard( Colour::FileName );
- stream << lineInfo << '\n';
- }
- stream << getLineOfChars<'.'>() << '\n' << std::endl;
- }
-
- void printClosedHeader( std::string const& _name ) {
- printOpenHeader( _name );
- stream << getLineOfChars<'.'>() << '\n';
- }
- void printOpenHeader( std::string const& _name ) {
- stream << getLineOfChars<'-'>() << '\n';
- {
- Colour colourGuard( Colour::Headers );
- printHeaderString( _name );
- }
- }
-
- // if string has a : in first line will set indent to follow it on
- // subsequent lines
- void printHeaderString( std::string const& _string, std::size_t indent = 0 ) {
- std::size_t i = _string.find( ": " );
- if( i != std::string::npos )
- i+=2;
- else
- i = 0;
- stream << Column( _string ).indent( indent+i ).initialIndent( indent ) << '\n';
- }
-
- struct SummaryColumn {
-
- SummaryColumn( std::string const& _label, Colour::Code _colour )
- : label( _label ),
- colour( _colour )
- {}
- SummaryColumn addRow( std::size_t count ) {
- std::ostringstream oss;
- oss << count;
- std::string row = oss.str();
- for( auto& oldRow : rows ) {
- while( oldRow.size() < row.size() )
- oldRow = ' ' + oldRow;
- while( oldRow.size() > row.size() )
- row = ' ' + row;
- }
- rows.push_back( row );
- return *this;
- }
-
- std::string label;
- Colour::Code colour;
- std::vector<std::string> rows;
-
- };
-
- void printTotals( Totals const& totals ) {
- if( totals.testCases.total() == 0 ) {
- stream << Colour( Colour::Warning ) << "No tests ran\n";
- }
- else if( totals.assertions.total() > 0 && totals.testCases.allPassed() ) {
- stream << Colour( Colour::ResultSuccess ) << "All tests passed";
- stream << " ("
- << pluralise( totals.assertions.passed, "assertion" ) << " in "
- << pluralise( totals.testCases.passed, "test case" ) << ')'
- << '\n';
- }
- else {
-
- std::vector<SummaryColumn> columns;
- columns.push_back( SummaryColumn( "", Colour::None )
- .addRow( totals.testCases.total() )
- .addRow( totals.assertions.total() ) );
- columns.push_back( SummaryColumn( "passed", Colour::Success )
- .addRow( totals.testCases.passed )
- .addRow( totals.assertions.passed ) );
- columns.push_back( SummaryColumn( "failed", Colour::ResultError )
- .addRow( totals.testCases.failed )
- .addRow( totals.assertions.failed ) );
- columns.push_back( SummaryColumn( "failed as expected", Colour::ResultExpectedFailure )
- .addRow( totals.testCases.failedButOk )
- .addRow( totals.assertions.failedButOk ) );
-
- printSummaryRow( "test cases", columns, 0 );
- printSummaryRow( "assertions", columns, 1 );
- }
- }
- void printSummaryRow( std::string const& label, std::vector<SummaryColumn> const& cols, std::size_t row ) {
- for( auto col : cols ) {
- std::string value = col.rows[row];
- if( col.label.empty() ) {
- stream << label << ": ";
- if( value != "0" )
- stream << value;
- else
- stream << Colour( Colour::Warning ) << "- none -";
- }
- else if( value != "0" ) {
- stream << Colour( Colour::LightGrey ) << " | ";
- stream << Colour( col.colour )
- << value << ' ' << col.label;
- }
- }
- stream << '\n';
- }
-
- void printTotalsDivider( Totals const& totals ) {
- if( totals.testCases.total() > 0 ) {
- std::size_t failedRatio = makeRatio( totals.testCases.failed, totals.testCases.total() );
- std::size_t failedButOkRatio = makeRatio( totals.testCases.failedButOk, totals.testCases.total() );
- std::size_t passedRatio = makeRatio( totals.testCases.passed, totals.testCases.total() );
- while( failedRatio + failedButOkRatio + passedRatio < CATCH_CONFIG_CONSOLE_WIDTH-1 )
- findMax( failedRatio, failedButOkRatio, passedRatio )++;
- while( failedRatio + failedButOkRatio + passedRatio > CATCH_CONFIG_CONSOLE_WIDTH-1 )
- findMax( failedRatio, failedButOkRatio, passedRatio )--;
-
- stream << Colour( Colour::Error ) << std::string( failedRatio, '=' );
- stream << Colour( Colour::ResultExpectedFailure ) << std::string( failedButOkRatio, '=' );
- if( totals.testCases.allPassed() )
- stream << Colour( Colour::ResultSuccess ) << std::string( passedRatio, '=' );
- else
- stream << Colour( Colour::Success ) << std::string( passedRatio, '=' );
- }
- else {
- stream << Colour( Colour::Warning ) << std::string( CATCH_CONFIG_CONSOLE_WIDTH-1, '=' );
- }
- stream << '\n';
- }
- void printSummaryDivider() {
- stream << getLineOfChars<'-'>() << '\n';
- }
-
- private:
- bool m_headerPrinted = false;
- };
-
- CATCH_REGISTER_REPORTER( "console", ConsoleReporter )
-
- ConsoleReporter::~ConsoleReporter() {}
-
-} // end namespace Catch
-
-#if defined(_MSC_VER)
-#pragma warning(pop)
-#endif
-// end catch_reporter_console.cpp
-// start catch_reporter_junit.cpp
-
-#include <assert.h>
-
-#include <ctime>
-#include <algorithm>
-
-namespace Catch {
-
- namespace {
- std::string getCurrentTimestamp() {
- // Beware, this is not reentrant because of backward compatibility issues
- // Also, UTC only, again because of backward compatibility (%z is C++11)
- time_t rawtime;
- std::time(&rawtime);
- auto const timeStampSize = sizeof("2017-01-16T17:06:45Z");
-
-#ifdef _MSC_VER
- std::tm timeInfo = {};
- gmtime_s(&timeInfo, &rawtime);
-#else
- std::tm* timeInfo;
- timeInfo = std::gmtime(&rawtime);
-#endif
-
- char timeStamp[timeStampSize];
- const char * const fmt = "%Y-%m-%dT%H:%M:%SZ";
-
-#ifdef _MSC_VER
- std::strftime(timeStamp, timeStampSize, fmt, &timeInfo);
-#else
- std::strftime(timeStamp, timeStampSize, fmt, timeInfo);
-#endif
- return std::string(timeStamp);
- }
-
- std::string fileNameTag(const std::vector<std::string> &tags) {
- auto it = std::find_if(begin(tags),
- end(tags),
- [] (std::string const& tag) {return tag.front() == '#'; });
- if (it != tags.end())
- return it->substr(1);
- return std::string();
- }
- }
-
- class JunitReporter : public CumulativeReporterBase<JunitReporter> {
- public:
- JunitReporter( ReporterConfig const& _config )
- : CumulativeReporterBase( _config ),
- xml( _config.stream() )
- {
- m_reporterPrefs.shouldRedirectStdOut = true;
- }
-
- ~JunitReporter() override;
-
- static std::string getDescription() {
- return "Reports test results in an XML format that looks like Ant's junitreport target";
- }
-
- void noMatchingTestCases( std::string const& /*spec*/ ) override {}
-
- void testRunStarting( TestRunInfo const& runInfo ) override {
- CumulativeReporterBase::testRunStarting( runInfo );
- xml.startElement( "testsuites" );
- }
-
- void testGroupStarting( GroupInfo const& groupInfo ) override {
- suiteTimer.start();
- stdOutForSuite.str("");
- stdErrForSuite.str("");
- unexpectedExceptions = 0;
- CumulativeReporterBase::testGroupStarting( groupInfo );
- }
-
- void testCaseStarting( TestCaseInfo const& testCaseInfo ) override {
- m_okToFail = testCaseInfo.okToFail();
- }
- bool assertionEnded( AssertionStats const& assertionStats ) override {
- if( assertionStats.assertionResult.getResultType() == ResultWas::ThrewException && !m_okToFail )
- unexpectedExceptions++;
- return CumulativeReporterBase::assertionEnded( assertionStats );
- }
-
- void testCaseEnded( TestCaseStats const& testCaseStats ) override {
- stdOutForSuite << testCaseStats.stdOut;
- stdErrForSuite << testCaseStats.stdErr;
- CumulativeReporterBase::testCaseEnded( testCaseStats );
- }
-
- void testGroupEnded( TestGroupStats const& testGroupStats ) override {
- double suiteTime = suiteTimer.getElapsedSeconds();
- CumulativeReporterBase::testGroupEnded( testGroupStats );
- writeGroup( *m_testGroups.back(), suiteTime );
- }
-
- void testRunEndedCumulative() override {
- xml.endElement();
- }
-
- void writeGroup( TestGroupNode const& groupNode, double suiteTime ) {
- XmlWriter::ScopedElement e = xml.scopedElement( "testsuite" );
- TestGroupStats const& stats = groupNode.value;
- xml.writeAttribute( "name", stats.groupInfo.name );
- xml.writeAttribute( "errors", unexpectedExceptions );
- xml.writeAttribute( "failures", stats.totals.assertions.failed-unexpectedExceptions );
- xml.writeAttribute( "tests", stats.totals.assertions.total() );
- xml.writeAttribute( "hostname", "tbd" ); // !TBD
- if( m_config->showDurations() == ShowDurations::Never )
- xml.writeAttribute( "time", "" );
- else
- xml.writeAttribute( "time", suiteTime );
- xml.writeAttribute( "timestamp", getCurrentTimestamp() );
-
- // Write test cases
- for( auto const& child : groupNode.children )
- writeTestCase( *child );
-
- xml.scopedElement( "system-out" ).writeText( trim( stdOutForSuite.str() ), false );
- xml.scopedElement( "system-err" ).writeText( trim( stdErrForSuite.str() ), false );
- }
-
- void writeTestCase( TestCaseNode const& testCaseNode ) {
- TestCaseStats const& stats = testCaseNode.value;
-
- // All test cases have exactly one section - which represents the
- // test case itself. That section may have 0-n nested sections
- assert( testCaseNode.children.size() == 1 );
- SectionNode const& rootSection = *testCaseNode.children.front();
-
- std::string className = stats.testInfo.className;
-
- if( className.empty() ) {
- className = fileNameTag(stats.testInfo.tags);
- if ( className.empty() )
- className = "global";
- }
-
- if ( !m_config->name().empty() )
- className = m_config->name() + "." + className;
-
- writeSection( className, "", rootSection );
- }
-
- void writeSection( std::string const& className,
- std::string const& rootName,
- SectionNode const& sectionNode ) {
- std::string name = trim( sectionNode.stats.sectionInfo.name );
- if( !rootName.empty() )
- name = rootName + '/' + name;
-
- if( !sectionNode.assertions.empty() ||
- !sectionNode.stdOut.empty() ||
- !sectionNode.stdErr.empty() ) {
- XmlWriter::ScopedElement e = xml.scopedElement( "testcase" );
- if( className.empty() ) {
- xml.writeAttribute( "classname", name );
- xml.writeAttribute( "name", "root" );
- }
- else {
- xml.writeAttribute( "classname", className );
- xml.writeAttribute( "name", name );
- }
- xml.writeAttribute( "time", ::Catch::Detail::stringify( sectionNode.stats.durationInSeconds ) );
-
- writeAssertions( sectionNode );
-
- if( !sectionNode.stdOut.empty() )
- xml.scopedElement( "system-out" ).writeText( trim( sectionNode.stdOut ), false );
- if( !sectionNode.stdErr.empty() )
- xml.scopedElement( "system-err" ).writeText( trim( sectionNode.stdErr ), false );
- }
- for( auto const& childNode : sectionNode.childSections )
- if( className.empty() )
- writeSection( name, "", *childNode );
- else
- writeSection( className, name, *childNode );
- }
-
- void writeAssertions( SectionNode const& sectionNode ) {
- for( auto const& assertion : sectionNode.assertions )
- writeAssertion( assertion );
- }
- void writeAssertion( AssertionStats const& stats ) {
- AssertionResult const& result = stats.assertionResult;
- if( !result.isOk() ) {
- std::string elementName;
- switch( result.getResultType() ) {
- case ResultWas::ThrewException:
- case ResultWas::FatalErrorCondition:
- elementName = "error";
- break;
- case ResultWas::ExplicitFailure:
- elementName = "failure";
- break;
- case ResultWas::ExpressionFailed:
- elementName = "failure";
- break;
- case ResultWas::DidntThrowException:
- elementName = "failure";
- break;
-
- // We should never see these here:
- case ResultWas::Info:
- case ResultWas::Warning:
- case ResultWas::Ok:
- case ResultWas::Unknown:
- case ResultWas::FailureBit:
- case ResultWas::Exception:
- elementName = "internalError";
- break;
- }
-
- XmlWriter::ScopedElement e = xml.scopedElement( elementName );
-
- xml.writeAttribute( "message", result.getExpandedExpression() );
- xml.writeAttribute( "type", result.getTestMacroName() );
-
- std::ostringstream oss;
- if( !result.getMessage().empty() )
- oss << result.getMessage() << '\n';
- for( auto const& msg : stats.infoMessages )
- if( msg.type == ResultWas::Info )
- oss << msg.message << '\n';
-
- oss << "at " << result.getSourceInfo();
- xml.writeText( oss.str(), false );
- }
- }
-
- XmlWriter xml;
- Timer suiteTimer;
- std::ostringstream stdOutForSuite;
- std::ostringstream stdErrForSuite;
- unsigned int unexpectedExceptions = 0;
- bool m_okToFail = false;
- };
-
- JunitReporter::~JunitReporter() {}
- CATCH_REGISTER_REPORTER( "junit", JunitReporter )
-
-} // end namespace Catch
-// end catch_reporter_junit.cpp
-// start catch_reporter_multi.cpp
-
-namespace Catch {
-
- void MultipleReporters::add( IStreamingReporterPtr&& reporter ) {
- m_reporters.push_back( std::move( reporter ) );
- }
-
- ReporterPreferences MultipleReporters::getPreferences() const {
- return m_reporters[0]->getPreferences();
- }
-
- std::set<Verbosity> MultipleReporters::getSupportedVerbosities() {
- return std::set<Verbosity>{ };
- }
-
- void MultipleReporters::noMatchingTestCases( std::string const& spec ) {
- for( auto const& reporter : m_reporters )
- reporter->noMatchingTestCases( spec );
- }
-
- void MultipleReporters::benchmarkStarting( BenchmarkInfo const& benchmarkInfo ) {
- for( auto const& reporter : m_reporters )
- reporter->benchmarkStarting( benchmarkInfo );
- }
- void MultipleReporters::benchmarkEnded( BenchmarkStats const& benchmarkStats ) {
- for( auto const& reporter : m_reporters )
- reporter->benchmarkEnded( benchmarkStats );
- }
-
- void MultipleReporters::testRunStarting( TestRunInfo const& testRunInfo ) {
- for( auto const& reporter : m_reporters )
- reporter->testRunStarting( testRunInfo );
- }
-
- void MultipleReporters::testGroupStarting( GroupInfo const& groupInfo ) {
- for( auto const& reporter : m_reporters )
- reporter->testGroupStarting( groupInfo );
- }
-
- void MultipleReporters::testCaseStarting( TestCaseInfo const& testInfo ) {
- for( auto const& reporter : m_reporters )
- reporter->testCaseStarting( testInfo );
- }
-
- void MultipleReporters::sectionStarting( SectionInfo const& sectionInfo ) {
- for( auto const& reporter : m_reporters )
- reporter->sectionStarting( sectionInfo );
- }
-
- void MultipleReporters::assertionStarting( AssertionInfo const& assertionInfo ) {
- for( auto const& reporter : m_reporters )
- reporter->assertionStarting( assertionInfo );
- }
-
- // The return value indicates if the messages buffer should be cleared:
- bool MultipleReporters::assertionEnded( AssertionStats const& assertionStats ) {
- bool clearBuffer = false;
- for( auto const& reporter : m_reporters )
- clearBuffer |= reporter->assertionEnded( assertionStats );
- return clearBuffer;
- }
-
- void MultipleReporters::sectionEnded( SectionStats const& sectionStats ) {
- for( auto const& reporter : m_reporters )
- reporter->sectionEnded( sectionStats );
- }
-
- void MultipleReporters::testCaseEnded( TestCaseStats const& testCaseStats ) {
- for( auto const& reporter : m_reporters )
- reporter->testCaseEnded( testCaseStats );
- }
-
- void MultipleReporters::testGroupEnded( TestGroupStats const& testGroupStats ) {
- for( auto const& reporter : m_reporters )
- reporter->testGroupEnded( testGroupStats );
- }
-
- void MultipleReporters::testRunEnded( TestRunStats const& testRunStats ) {
- for( auto const& reporter : m_reporters )
- reporter->testRunEnded( testRunStats );
- }
-
- void MultipleReporters::skipTest( TestCaseInfo const& testInfo ) {
- for( auto const& reporter : m_reporters )
- reporter->skipTest( testInfo );
- }
-
- bool MultipleReporters::isMulti() const {
- return true;
- }
-
-} // end namespace Catch
-// end catch_reporter_multi.cpp
-// start catch_reporter_xml.cpp
-
-#if defined(_MSC_VER)
-#pragma warning(push)
-#pragma warning(disable:4061) // Not all labels are EXPLICITLY handled in switch
- // Note that 4062 (not all labels are handled
- // and default is missing) is enabled
-#endif
-
-namespace Catch {
- class XmlReporter : public StreamingReporterBase<XmlReporter> {
- public:
- XmlReporter( ReporterConfig const& _config )
- : StreamingReporterBase( _config ),
- m_xml(_config.stream())
- {
- m_reporterPrefs.shouldRedirectStdOut = true;
- }
-
- ~XmlReporter() override;
-
- static std::string getDescription() {
- return "Reports test results as an XML document";
- }
-
- virtual std::string getStylesheetRef() const {
- return std::string();
- }
-
- void writeSourceInfo( SourceLineInfo const& sourceInfo ) {
- m_xml
- .writeAttribute( "filename", sourceInfo.file )
- .writeAttribute( "line", sourceInfo.line );
- }
-
- public: // StreamingReporterBase
-
- void noMatchingTestCases( std::string const& s ) override {
- StreamingReporterBase::noMatchingTestCases( s );
- }
-
- void testRunStarting( TestRunInfo const& testInfo ) override {
- StreamingReporterBase::testRunStarting( testInfo );
- std::string stylesheetRef = getStylesheetRef();
- if( !stylesheetRef.empty() )
- m_xml.writeStylesheetRef( stylesheetRef );
- m_xml.startElement( "Catch" );
- if( !m_config->name().empty() )
- m_xml.writeAttribute( "name", m_config->name() );
- }
-
- void testGroupStarting( GroupInfo const& groupInfo ) override {
- StreamingReporterBase::testGroupStarting( groupInfo );
- m_xml.startElement( "Group" )
- .writeAttribute( "name", groupInfo.name );
- }
-
- void testCaseStarting( TestCaseInfo const& testInfo ) override {
- StreamingReporterBase::testCaseStarting(testInfo);
- m_xml.startElement( "TestCase" )
- .writeAttribute( "name", trim( testInfo.name ) )
- .writeAttribute( "description", testInfo.description )
- .writeAttribute( "tags", testInfo.tagsAsString() );
-
- writeSourceInfo( testInfo.lineInfo );
-
- if ( m_config->showDurations() == ShowDurations::Always )
- m_testCaseTimer.start();
- m_xml.ensureTagClosed();
- }
-
- void sectionStarting( SectionInfo const& sectionInfo ) override {
- StreamingReporterBase::sectionStarting( sectionInfo );
- if( m_sectionDepth++ > 0 ) {
- m_xml.startElement( "Section" )
- .writeAttribute( "name", trim( sectionInfo.name ) )
- .writeAttribute( "description", sectionInfo.description );
- writeSourceInfo( sectionInfo.lineInfo );
- m_xml.ensureTagClosed();
- }
- }
-
- void assertionStarting( AssertionInfo const& ) override { }
-
- bool assertionEnded( AssertionStats const& assertionStats ) override {
-
- AssertionResult const& result = assertionStats.assertionResult;
-
- bool includeResults = m_config->includeSuccessfulResults() || !result.isOk();
-
- if( includeResults ) {
- // Print any info messages in <Info> tags.
- for( auto const& msg : assertionStats.infoMessages ) {
- if( msg.type == ResultWas::Info ) {
- m_xml.scopedElement( "Info" )
- .writeText( msg.message );
- } else if ( msg.type == ResultWas::Warning ) {
- m_xml.scopedElement( "Warning" )
- .writeText( msg.message );
- }
- }
- }
-
- // Drop out if result was successful but we're not printing them.
- if( !includeResults && result.getResultType() != ResultWas::Warning )
- return true;
-
- // Print the expression if there is one.
- if( result.hasExpression() ) {
- m_xml.startElement( "Expression" )
- .writeAttribute( "success", result.succeeded() )
- .writeAttribute( "type", result.getTestMacroName() );
-
- writeSourceInfo( result.getSourceInfo() );
-
- m_xml.scopedElement( "Original" )
- .writeText( result.getExpression() );
- m_xml.scopedElement( "Expanded" )
- .writeText( result.getExpandedExpression() );
- }
-
- // And... Print a result applicable to each result type.
- switch( result.getResultType() ) {
- case ResultWas::ThrewException:
- m_xml.startElement( "Exception" );
- writeSourceInfo( result.getSourceInfo() );
- m_xml.writeText( result.getMessage() );
- m_xml.endElement();
- break;
- case ResultWas::FatalErrorCondition:
- m_xml.startElement( "FatalErrorCondition" );
- writeSourceInfo( result.getSourceInfo() );
- m_xml.writeText( result.getMessage() );
- m_xml.endElement();
- break;
- case ResultWas::Info:
- m_xml.scopedElement( "Info" )
- .writeText( result.getMessage() );
- break;
- case ResultWas::Warning:
- // Warning will already have been written
- break;
- case ResultWas::ExplicitFailure:
- m_xml.startElement( "Failure" );
- writeSourceInfo( result.getSourceInfo() );
- m_xml.writeText( result.getMessage() );
- m_xml.endElement();
- break;
- default:
- break;
- }
-
- if( result.hasExpression() )
- m_xml.endElement();
-
- return true;
- }
-
- void sectionEnded( SectionStats const& sectionStats ) override {
- StreamingReporterBase::sectionEnded( sectionStats );
- if( --m_sectionDepth > 0 ) {
- XmlWriter::ScopedElement e = m_xml.scopedElement( "OverallResults" );
- e.writeAttribute( "successes", sectionStats.assertions.passed );
- e.writeAttribute( "failures", sectionStats.assertions.failed );
- e.writeAttribute( "expectedFailures", sectionStats.assertions.failedButOk );
-
- if ( m_config->showDurations() == ShowDurations::Always )
- e.writeAttribute( "durationInSeconds", sectionStats.durationInSeconds );
-
- m_xml.endElement();
- }
- }
-
- void testCaseEnded( TestCaseStats const& testCaseStats ) override {
- StreamingReporterBase::testCaseEnded( testCaseStats );
- XmlWriter::ScopedElement e = m_xml.scopedElement( "OverallResult" );
- e.writeAttribute( "success", testCaseStats.totals.assertions.allOk() );
-
- if ( m_config->showDurations() == ShowDurations::Always )
- e.writeAttribute( "durationInSeconds", m_testCaseTimer.getElapsedSeconds() );
-
- if( !testCaseStats.stdOut.empty() )
- m_xml.scopedElement( "StdOut" ).writeText( trim( testCaseStats.stdOut ), false );
- if( !testCaseStats.stdErr.empty() )
- m_xml.scopedElement( "StdErr" ).writeText( trim( testCaseStats.stdErr ), false );
-
- m_xml.endElement();
- }
-
- void testGroupEnded( TestGroupStats const& testGroupStats ) override {
- StreamingReporterBase::testGroupEnded( testGroupStats );
- // TODO: Check testGroupStats.aborting and act accordingly.
- m_xml.scopedElement( "OverallResults" )
- .writeAttribute( "successes", testGroupStats.totals.assertions.passed )
- .writeAttribute( "failures", testGroupStats.totals.assertions.failed )
- .writeAttribute( "expectedFailures", testGroupStats.totals.assertions.failedButOk );
- m_xml.endElement();
- }
-
- void testRunEnded( TestRunStats const& testRunStats ) override {
- StreamingReporterBase::testRunEnded( testRunStats );
- m_xml.scopedElement( "OverallResults" )
- .writeAttribute( "successes", testRunStats.totals.assertions.passed )
- .writeAttribute( "failures", testRunStats.totals.assertions.failed )
- .writeAttribute( "expectedFailures", testRunStats.totals.assertions.failedButOk );
- m_xml.endElement();
- }
-
- private:
- Timer m_testCaseTimer;
- XmlWriter m_xml;
- int m_sectionDepth = 0;
- };
-
- XmlReporter::~XmlReporter() {}
- CATCH_REGISTER_REPORTER( "xml", XmlReporter )
-
-} // end namespace Catch
-
-#if defined(_MSC_VER)
-#pragma warning(pop)
-#endif
-// end catch_reporter_xml.cpp
-
-namespace Catch {
- LeakDetector leakDetector;
-}
-
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
-
-// end catch_impl.hpp
-#endif
-
-#ifdef CATCH_CONFIG_MAIN
-// start catch_default_main.hpp
-
-#ifndef __OBJC__
-
-#if defined(WIN32) && defined(_UNICODE) && !defined(DO_NOT_USE_WMAIN)
-// Standard C/C++ Win32 Unicode wmain entry point
-extern "C" int wmain (int argc, wchar_t * argv[], wchar_t * []) {
-#else
-// Standard C/C++ main entry point
-int main (int argc, char * argv[]) {
-#endif
-
- return Catch::Session().run( argc, argv );
-}
-
-#else // __OBJC__
-
-// Objective-C entry point
-int main (int argc, char * const argv[]) {
-#if !CATCH_ARC_ENABLED
- NSAutoreleasePool * pool = [[NSAutoreleasePool alloc] init];
-#endif
-
- Catch::registerTestMethods();
- int result = Catch::Session().run( argc, (char**)argv );
-
-#if !CATCH_ARC_ENABLED
- [pool drain];
-#endif
-
- return result;
-}
-
-#endif // __OBJC__
-
-// end catch_default_main.hpp
-#endif
-
-#ifdef CLARA_CONFIG_MAIN_NOT_DEFINED
-# undef CLARA_CONFIG_MAIN
-#endif
-
-#if !defined(CATCH_CONFIG_DISABLE)
-//////
-// If this config identifier is defined then all CATCH macros are prefixed with CATCH_
-#ifdef CATCH_CONFIG_PREFIX_ALL
-
-#define CATCH_REQUIRE( ... ) INTERNAL_CATCH_TEST( "CATCH_REQUIRE", Catch::ResultDisposition::Normal, __VA_ARGS__ )
-#define CATCH_REQUIRE_FALSE( ... ) INTERNAL_CATCH_TEST( "CATCH_REQUIRE_FALSE", Catch::ResultDisposition::Normal | Catch::ResultDisposition::FalseTest, __VA_ARGS__ )
-
-#define CATCH_REQUIRE_THROWS( ... ) INTERNAL_CATCH_THROWS( "CATCH_REQUIRE_THROWS", Catch::ResultDisposition::Normal, "", __VA_ARGS__ )
-#define CATCH_REQUIRE_THROWS_AS( expr, exceptionType ) INTERNAL_CATCH_THROWS_AS( "CATCH_REQUIRE_THROWS_AS", exceptionType, Catch::ResultDisposition::Normal, expr )
-#define CATCH_REQUIRE_THROWS_WITH( expr, matcher ) INTERNAL_CATCH_THROWS_STR_MATCHES( "CATCH_REQUIRE_THROWS_WITH", Catch::ResultDisposition::Normal, matcher, expr )
-#if !defined(CATCH_CONFIG_DISABLE_MATCHERS)
-#define CATCH_REQUIRE_THROWS_MATCHES( expr, exceptionType, matcher ) INTERNAL_CATCH_THROWS_MATCHES( "CATCH_REQUIRE_THROWS_MATCHES", exceptionType, Catch::ResultDisposition::Normal, matcher, expr )
-#endif// CATCH_CONFIG_DISABLE_MATCHERS
-#define CATCH_REQUIRE_NOTHROW( ... ) INTERNAL_CATCH_NO_THROW( "CATCH_REQUIRE_NOTHROW", Catch::ResultDisposition::Normal, __VA_ARGS__ )
-
-#define CATCH_CHECK( ... ) INTERNAL_CATCH_TEST( "CATCH_CHECK", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-#define CATCH_CHECK_FALSE( ... ) INTERNAL_CATCH_TEST( "CATCH_CHECK_FALSE", Catch::ResultDisposition::ContinueOnFailure | Catch::ResultDisposition::FalseTest, __VA_ARGS__ )
-#define CATCH_CHECKED_IF( ... ) INTERNAL_CATCH_IF( "CATCH_CHECKED_IF", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-#define CATCH_CHECKED_ELSE( ... ) INTERNAL_CATCH_ELSE( "CATCH_CHECKED_ELSE", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-#define CATCH_CHECK_NOFAIL( ... ) INTERNAL_CATCH_TEST( "CATCH_CHECK_NOFAIL", Catch::ResultDisposition::ContinueOnFailure | Catch::ResultDisposition::SuppressFail, __VA_ARGS__ )
-
-#define CATCH_CHECK_THROWS( ... ) INTERNAL_CATCH_THROWS( "CATCH_CHECK_THROWS", Catch::ResultDisposition::ContinueOnFailure, "", __VA_ARGS__ )
-#define CATCH_CHECK_THROWS_AS( expr, exceptionType ) INTERNAL_CATCH_THROWS_AS( "CATCH_CHECK_THROWS_AS", exceptionType, Catch::ResultDisposition::ContinueOnFailure, expr )
-#define CATCH_CHECK_THROWS_WITH( expr, matcher ) INTERNAL_CATCH_THROWS_STR_MATCHES( "CATCH_CHECK_THROWS_WITH", Catch::ResultDisposition::ContinueOnFailure, matcher, expr )
-#if !defined(CATCH_CONFIG_DISABLE_MATCHERS)
-#define CATCH_CHECK_THROWS_MATCHES( expr, exceptionType, matcher ) INTERNAL_CATCH_THROWS_MATCHES( "CATCH_CHECK_THROWS_MATCHES", exceptionType, Catch::ResultDisposition::ContinueOnFailure, matcher, expr )
-#endif // CATCH_CONFIG_DISABLE_MATCHERS
-#define CATCH_CHECK_NOTHROW( ... ) INTERNAL_CATCH_NO_THROW( "CATCH_CHECK_NOTHROW", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-
-#if !defined(CATCH_CONFIG_DISABLE_MATCHERS)
-#define CATCH_CHECK_THAT( arg, matcher ) INTERNAL_CHECK_THAT( "CATCH_CHECK_THAT", matcher, Catch::ResultDisposition::ContinueOnFailure, arg )
-
-#define CATCH_REQUIRE_THAT( arg, matcher ) INTERNAL_CHECK_THAT( "CATCH_REQUIRE_THAT", matcher, Catch::ResultDisposition::Normal, arg )
-#endif // CATCH_CONFIG_DISABLE_MATCHERS
-
-#define CATCH_INFO( msg ) INTERNAL_CATCH_INFO( "CATCH_INFO", msg )
-#define CATCH_WARN( msg ) INTERNAL_CATCH_MSG( "CATCH_WARN", Catch::ResultWas::Warning, Catch::ResultDisposition::ContinueOnFailure, msg )
-#define CATCH_CAPTURE( msg ) INTERNAL_CATCH_INFO( "CATCH_CAPTURE", #msg " := " << ::Catch::Detail::stringify(msg) )
-
-#define CATCH_TEST_CASE( ... ) INTERNAL_CATCH_TESTCASE( __VA_ARGS__ )
-#define CATCH_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TEST_CASE_METHOD( className, __VA_ARGS__ )
-#define CATCH_METHOD_AS_TEST_CASE( method, ... ) INTERNAL_CATCH_METHOD_AS_TEST_CASE( method, __VA_ARGS__ )
-#define CATCH_REGISTER_TEST_CASE( Function, ... ) INTERNAL_CATCH_REGISTER_TESTCASE( Function, __VA_ARGS__ )
-#define CATCH_SECTION( ... ) INTERNAL_CATCH_SECTION( __VA_ARGS__ )
-#define CATCH_FAIL( ... ) INTERNAL_CATCH_MSG( "CATCH_FAIL", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::Normal, __VA_ARGS__ )
-#define CATCH_FAIL_CHECK( ... ) INTERNAL_CATCH_MSG( "CATCH_FAIL_CHECK", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-#define CATCH_SUCCEED( ... ) INTERNAL_CATCH_MSG( "CATCH_SUCCEED", Catch::ResultWas::Ok, Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-
-#define CATCH_ANON_TEST_CASE() INTERNAL_CATCH_TESTCASE()
-
-// "BDD-style" convenience wrappers
-#define CATCH_SCENARIO( ... ) CATCH_TEST_CASE( "Scenario: " __VA_ARGS__ )
-#define CATCH_SCENARIO_METHOD( className, ... ) INTERNAL_CATCH_TEST_CASE_METHOD( className, "Scenario: " __VA_ARGS__ )
-#define CATCH_GIVEN( desc ) CATCH_SECTION( std::string( "Given: ") + desc )
-#define CATCH_WHEN( desc ) CATCH_SECTION( std::string( " When: ") + desc )
-#define CATCH_AND_WHEN( desc ) CATCH_SECTION( std::string( " And: ") + desc )
-#define CATCH_THEN( desc ) CATCH_SECTION( std::string( " Then: ") + desc )
-#define CATCH_AND_THEN( desc ) CATCH_SECTION( std::string( " And: ") + desc )
-
-// If CATCH_CONFIG_PREFIX_ALL is not defined then the CATCH_ prefix is not required
-#else
-
-#define REQUIRE( ... ) INTERNAL_CATCH_TEST( "REQUIRE", Catch::ResultDisposition::Normal, __VA_ARGS__ )
-#define REQUIRE_FALSE( ... ) INTERNAL_CATCH_TEST( "REQUIRE_FALSE", Catch::ResultDisposition::Normal | Catch::ResultDisposition::FalseTest, __VA_ARGS__ )
-
-#define REQUIRE_THROWS( ... ) INTERNAL_CATCH_THROWS( "REQUIRE_THROWS", Catch::ResultDisposition::Normal, __VA_ARGS__ )
-#define REQUIRE_THROWS_AS( expr, exceptionType ) INTERNAL_CATCH_THROWS_AS( "REQUIRE_THROWS_AS", exceptionType, Catch::ResultDisposition::Normal, expr )
-#define REQUIRE_THROWS_WITH( expr, matcher ) INTERNAL_CATCH_THROWS_STR_MATCHES( "REQUIRE_THROWS_WITH", Catch::ResultDisposition::Normal, matcher, expr )
-#if !defined(CATCH_CONFIG_DISABLE_MATCHERS)
-#define REQUIRE_THROWS_MATCHES( expr, exceptionType, matcher ) INTERNAL_CATCH_THROWS_MATCHES( "REQUIRE_THROWS_MATCHES", exceptionType, Catch::ResultDisposition::Normal, matcher, expr )
-#endif // CATCH_CONFIG_DISABLE_MATCHERS
-#define REQUIRE_NOTHROW( ... ) INTERNAL_CATCH_NO_THROW( "REQUIRE_NOTHROW", Catch::ResultDisposition::Normal, __VA_ARGS__ )
-
-#define CHECK( ... ) INTERNAL_CATCH_TEST( "CHECK", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-#define CHECK_FALSE( ... ) INTERNAL_CATCH_TEST( "CHECK_FALSE", Catch::ResultDisposition::ContinueOnFailure | Catch::ResultDisposition::FalseTest, __VA_ARGS__ )
-#define CHECKED_IF( ... ) INTERNAL_CATCH_IF( "CHECKED_IF", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-#define CHECKED_ELSE( ... ) INTERNAL_CATCH_ELSE( "CHECKED_ELSE", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-#define CHECK_NOFAIL( ... ) INTERNAL_CATCH_TEST( "CHECK_NOFAIL", Catch::ResultDisposition::ContinueOnFailure | Catch::ResultDisposition::SuppressFail, __VA_ARGS__ )
-
-#define CHECK_THROWS( ... ) INTERNAL_CATCH_THROWS( "CHECK_THROWS", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-#define CHECK_THROWS_AS( expr, exceptionType ) INTERNAL_CATCH_THROWS_AS( "CHECK_THROWS_AS", exceptionType, Catch::ResultDisposition::ContinueOnFailure, expr )
-#define CHECK_THROWS_WITH( expr, matcher ) INTERNAL_CATCH_THROWS_STR_MATCHES( "CHECK_THROWS_WITH", Catch::ResultDisposition::ContinueOnFailure, matcher, expr )
-#if !defined(CATCH_CONFIG_DISABLE_MATCHERS)
-#define CHECK_THROWS_MATCHES( expr, exceptionType, matcher ) INTERNAL_CATCH_THROWS_MATCHES( "CHECK_THROWS_MATCHES", exceptionType, Catch::ResultDisposition::ContinueOnFailure, matcher, expr )
-#endif // CATCH_CONFIG_DISABLE_MATCHERS
-#define CHECK_NOTHROW( ... ) INTERNAL_CATCH_NO_THROW( "CHECK_NOTHROW", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-
-#if !defined(CATCH_CONFIG_DISABLE_MATCHERS)
-#define CHECK_THAT( arg, matcher ) INTERNAL_CHECK_THAT( "CHECK_THAT", matcher, Catch::ResultDisposition::ContinueOnFailure, arg )
-
-#define REQUIRE_THAT( arg, matcher ) INTERNAL_CHECK_THAT( "REQUIRE_THAT", matcher, Catch::ResultDisposition::Normal, arg )
-#endif // CATCH_CONFIG_DISABLE_MATCHERS
-
-#define INFO( msg ) INTERNAL_CATCH_INFO( "INFO", msg )
-#define WARN( msg ) INTERNAL_CATCH_MSG( "WARN", Catch::ResultWas::Warning, Catch::ResultDisposition::ContinueOnFailure, msg )
-#define CAPTURE( msg ) INTERNAL_CATCH_INFO( "CAPTURE", #msg " := " << ::Catch::Detail::stringify(msg) )
-
-#define TEST_CASE( ... ) INTERNAL_CATCH_TESTCASE( __VA_ARGS__ )
-#define TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TEST_CASE_METHOD( className, __VA_ARGS__ )
-#define METHOD_AS_TEST_CASE( method, ... ) INTERNAL_CATCH_METHOD_AS_TEST_CASE( method, __VA_ARGS__ )
-#define REGISTER_TEST_CASE( Function, ... ) INTERNAL_CATCH_REGISTER_TESTCASE( Function, __VA_ARGS__ )
-#define SECTION( ... ) INTERNAL_CATCH_SECTION( __VA_ARGS__ )
-#define FAIL( ... ) INTERNAL_CATCH_MSG( "FAIL", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::Normal, __VA_ARGS__ )
-#define FAIL_CHECK( ... ) INTERNAL_CATCH_MSG( "FAIL_CHECK", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-#define SUCCEED( ... ) INTERNAL_CATCH_MSG( "SUCCEED", Catch::ResultWas::Ok, Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-#define ANON_TEST_CASE() INTERNAL_CATCH_TESTCASE()
-
-#endif
-
-#define CATCH_TRANSLATE_EXCEPTION( signature ) INTERNAL_CATCH_TRANSLATE_EXCEPTION( signature )
-
-// "BDD-style" convenience wrappers
-#define SCENARIO( ... ) TEST_CASE( "Scenario: " __VA_ARGS__ )
-#define SCENARIO_METHOD( className, ... ) INTERNAL_CATCH_TEST_CASE_METHOD( className, "Scenario: " __VA_ARGS__ )
-
-#define GIVEN( desc ) SECTION( std::string(" Given: ") + desc )
-#define WHEN( desc ) SECTION( std::string(" When: ") + desc )
-#define AND_WHEN( desc ) SECTION( std::string("And when: ") + desc )
-#define THEN( desc ) SECTION( std::string(" Then: ") + desc )
-#define AND_THEN( desc ) SECTION( std::string(" And: ") + desc )
-
-using Catch::Detail::Approx;
-
-#else
-//////
-// If this config identifier is defined then all CATCH macros are prefixed with CATCH_
-#ifdef CATCH_CONFIG_PREFIX_ALL
-
-#define CATCH_REQUIRE( ... ) (void)(0)
-#define CATCH_REQUIRE_FALSE( ... ) (void)(0)
-
-#define CATCH_REQUIRE_THROWS( ... ) (void)(0)
-#define CATCH_REQUIRE_THROWS_AS( expr, exceptionType ) (void)(0)
-#define CATCH_REQUIRE_THROWS_WITH( expr, matcher ) (void)(0)
-#if !defined(CATCH_CONFIG_DISABLE_MATCHERS)
-#define CATCH_REQUIRE_THROWS_MATCHES( expr, exceptionType, matcher ) (void)(0)
-#endif// CATCH_CONFIG_DISABLE_MATCHERS
-#define CATCH_REQUIRE_NOTHROW( ... ) (void)(0)
-
-#define CATCH_CHECK( ... ) (void)(0)
-#define CATCH_CHECK_FALSE( ... ) (void)(0)
-#define CATCH_CHECKED_IF( ... ) if (__VA_ARGS__)
-#define CATCH_CHECKED_ELSE( ... ) if (!(__VA_ARGS__))
-#define CATCH_CHECK_NOFAIL( ... ) (void)(0)
-
-#define CATCH_CHECK_THROWS( ... ) (void)(0)
-#define CATCH_CHECK_THROWS_AS( expr, exceptionType ) (void)(0)
-#define CATCH_CHECK_THROWS_WITH( expr, matcher ) (void)(0)
-#if !defined(CATCH_CONFIG_DISABLE_MATCHERS)
-#define CATCH_CHECK_THROWS_MATCHES( expr, exceptionType, matcher ) (void)(0)
-#endif // CATCH_CONFIG_DISABLE_MATCHERS
-#define CATCH_CHECK_NOTHROW( ... ) (void)(0)
-
-#if !defined(CATCH_CONFIG_DISABLE_MATCHERS)
-#define CATCH_CHECK_THAT( arg, matcher ) (void)(0)
-
-#define CATCH_REQUIRE_THAT( arg, matcher ) (void)(0)
-#endif // CATCH_CONFIG_DISABLE_MATCHERS
-
-#define CATCH_INFO( msg ) (void)(0)
-#define CATCH_WARN( msg ) (void)(0)
-#define CATCH_CAPTURE( msg ) (void)(0)
-
-#define CATCH_TEST_CASE( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ))
-#define CATCH_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ))
-#define CATCH_METHOD_AS_TEST_CASE( method, ... )
-#define CATCH_REGISTER_TEST_CASE( Function, ... ) (void)(0)
-#define CATCH_SECTION( ... )
-#define CATCH_FAIL( ... ) (void)(0)
-#define CATCH_FAIL_CHECK( ... ) (void)(0)
-#define CATCH_SUCCEED( ... ) (void)(0)
-
-#define CATCH_ANON_TEST_CASE() INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ))
-
-// "BDD-style" convenience wrappers
-#define CATCH_SCENARIO( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ))
-#define CATCH_SCENARIO_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_METHOD_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), className )
-#define CATCH_GIVEN( desc )
-#define CATCH_WHEN( desc )
-#define CATCH_AND_WHEN( desc )
-#define CATCH_THEN( desc )
-#define CATCH_AND_THEN( desc )
-
-// If CATCH_CONFIG_PREFIX_ALL is not defined then the CATCH_ prefix is not required
-#else
-
-#define REQUIRE( ... ) (void)(0)
-#define REQUIRE_FALSE( ... ) (void)(0)
-
-#define REQUIRE_THROWS( ... ) (void)(0)
-#define REQUIRE_THROWS_AS( expr, exceptionType ) (void)(0)
-#define REQUIRE_THROWS_WITH( expr, matcher ) (void)(0)
-#if !defined(CATCH_CONFIG_DISABLE_MATCHERS)
-#define REQUIRE_THROWS_MATCHES( expr, exceptionType, matcher ) (void)(0)
-#endif // CATCH_CONFIG_DISABLE_MATCHERS
-#define REQUIRE_NOTHROW( ... ) (void)(0)
-
-#define CHECK( ... ) (void)(0)
-#define CHECK_FALSE( ... ) (void)(0)
-#define CHECKED_IF( ... ) if (__VA_ARGS__)
-#define CHECKED_ELSE( ... ) if (!(__VA_ARGS__))
-#define CHECK_NOFAIL( ... ) (void)(0)
-
-#define CHECK_THROWS( ... ) (void)(0)
-#define CHECK_THROWS_AS( expr, exceptionType ) (void)(0)
-#define CHECK_THROWS_WITH( expr, matcher ) (void)(0)
-#if !defined(CATCH_CONFIG_DISABLE_MATCHERS)
-#define CHECK_THROWS_MATCHES( expr, exceptionType, matcher ) (void)(0)
-#endif // CATCH_CONFIG_DISABLE_MATCHERS
-#define CHECK_NOTHROW( ... ) (void)(0)
-
-#if !defined(CATCH_CONFIG_DISABLE_MATCHERS)
-#define CHECK_THAT( arg, matcher ) (void)(0)
-
-#define REQUIRE_THAT( arg, matcher ) (void)(0)
-#endif // CATCH_CONFIG_DISABLE_MATCHERS
-
-#define INFO( msg ) (void)(0)
-#define WARN( msg ) (void)(0)
-#define CAPTURE( msg ) (void)(0)
-
-#define TEST_CASE( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ))
-#define TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ))
-#define METHOD_AS_TEST_CASE( method, ... )
-#define REGISTER_TEST_CASE( Function, ... ) (void)(0)
-#define SECTION( ... )
-#define FAIL( ... ) (void)(0)
-#define FAIL_CHECK( ... ) (void)(0)
-#define SUCCEED( ... ) (void)(0)
-#define ANON_TEST_CASE() INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ))
-
-#endif
-
-#define CATCH_TRANSLATE_EXCEPTION( signature ) INTERNAL_CATCH_TRANSLATE_EXCEPTION_NO_REG( INTERNAL_CATCH_UNIQUE_NAME( catch_internal_ExceptionTranslator ), signature )
-
-// "BDD-style" convenience wrappers
-#define SCENARIO( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ) )
-#define SCENARIO_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_METHOD_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), className )
-
-#define GIVEN( desc )
-#define WHEN( desc )
-#define AND_WHEN( desc )
-#define THEN( desc )
-#define AND_THEN( desc )
-
-using Catch::Detail::Approx;
-
-#endif
-
-// start catch_reenable_warnings.h
-
-
-#ifdef __clang__
-# ifdef __ICC // icpc defines the __clang__ macro
-# pragma warning(pop)
-# else
-# pragma clang diagnostic pop
-# endif
-#elif defined __GNUC__
-# pragma GCC diagnostic pop
-#endif
-
-// end catch_reenable_warnings.h
-// end catch.hpp
-#endif // TWOBLUECUBES_SINGLE_INCLUDE_CATCH_HPP_INCLUDED
-
diff --git a/third_party/optional/tests/constexpr.cpp b/third_party/optional/tests/constexpr.cpp
deleted file mode 100644
index dc4db43..0000000
--- a/third_party/optional/tests/constexpr.cpp
+++ /dev/null
@@ -1,47 +0,0 @@
-#include "catch.hpp"
-#include "optional.hpp"
-
-#define TOKENPASTE(x, y) x##y
-#define TOKENPASTE2(x, y) TOKENPASTE(x, y)
-#define STATIC_REQUIRE(e) \
- constexpr bool TOKENPASTE2(rqure, __LINE__) = e; \
- REQUIRE(e);
-
-TEST_CASE("Constexpr", "[constexpr]") {
-#if !defined(TL_OPTIONAL_MSVC2015) && defined(TL_OPTIONAL_CXX14)
- SECTION("empty construct") {
- constexpr tl::optional<int> o2{};
- constexpr tl::optional<int> o3 = {};
- constexpr tl::optional<int> o4 = tl::nullopt;
- constexpr tl::optional<int> o5 = {tl::nullopt};
- constexpr tl::optional<int> o6(tl::nullopt);
-
- STATIC_REQUIRE(!o2);
- STATIC_REQUIRE(!o3);
- STATIC_REQUIRE(!o4);
- STATIC_REQUIRE(!o5);
- STATIC_REQUIRE(!o6);
- }
-
- SECTION("value construct") {
- constexpr tl::optional<int> o1 = 42;
- constexpr tl::optional<int> o2{42};
- constexpr tl::optional<int> o3(42);
- constexpr tl::optional<int> o4 = {42};
- constexpr int i = 42;
- constexpr tl::optional<int> o5 = std::move(i);
- constexpr tl::optional<int> o6{std::move(i)};
- constexpr tl::optional<int> o7(std::move(i));
- constexpr tl::optional<int> o8 = {std::move(i)};
-
- STATIC_REQUIRE(*o1 == 42);
- STATIC_REQUIRE(*o2 == 42);
- STATIC_REQUIRE(*o3 == 42);
- STATIC_REQUIRE(*o4 == 42);
- STATIC_REQUIRE(*o5 == 42);
- STATIC_REQUIRE(*o6 == 42);
- STATIC_REQUIRE(*o7 == 42);
- STATIC_REQUIRE(*o8 == 42);
- }
- #endif
-}
diff --git a/third_party/optional/tests/constructors.cpp b/third_party/optional/tests/constructors.cpp
deleted file mode 100644
index fc87a97..0000000
--- a/third_party/optional/tests/constructors.cpp
+++ /dev/null
@@ -1,62 +0,0 @@
-#include "catch.hpp"
-#include "optional.hpp"
-#include <vector>
-
-struct foo {
- foo() = default;
- foo(foo&) = delete;
- foo(foo&&) {};
-};
-
-TEST_CASE("Constructors", "[constructors]") {
- tl::optional<int> o1;
- REQUIRE(!o1);
-
- tl::optional<int> o2 = tl::nullopt;
- REQUIRE(!o2);
-
- tl::optional<int> o3 = 42;
- REQUIRE(*o3 == 42);
-
- tl::optional<int> o4 = o3;
- REQUIRE(*o4 == 42);
-
- tl::optional<int> o5 = o1;
- REQUIRE(!o5);
-
- tl::optional<int> o6 = std::move(o3);
- REQUIRE(*o6 == 42);
-
- tl::optional<short> o7 = 42;
- REQUIRE(*o7 == 42);
-
- tl::optional<int> o8 = o7;
- REQUIRE(*o8 == 42);
-
- tl::optional<int> o9 = std::move(o7);
- REQUIRE(*o9 == 42);
-
- {
- tl::optional<int &> o;
- REQUIRE(!o);
-
- tl::optional<int &> oo = o;
- REQUIRE(!oo);
- }
-
- {
- auto i = 42;
- tl::optional<int &> o = i;
- REQUIRE(o);
- REQUIRE(*o == 42);
-
- tl::optional<int &> oo = o;
- REQUIRE(oo);
- REQUIRE(*oo == 42);
- }
-
- std::vector<foo> v;
- v.emplace_back();
- tl::optional<std::vector<foo>> ov = std::move(v);
- REQUIRE(ov->size() == 1);
-}
diff --git a/third_party/optional/tests/emplace.cpp b/third_party/optional/tests/emplace.cpp
deleted file mode 100644
index 0a87983..0000000
--- a/third_party/optional/tests/emplace.cpp
+++ /dev/null
@@ -1,13 +0,0 @@
-#include "catch.hpp"
-#include "optional.hpp"
-#include <utility>
-#include <tuple>
-
-TEST_CASE("Emplace", "[emplace]") {
- tl::optional<std::pair<std::pair<int,int>, std::pair<double, double>>> i;
- i.emplace(std::piecewise_construct, std::make_tuple(0,2), std::make_tuple(3,4));
- REQUIRE(i->first.first == 0);
- REQUIRE(i->first.second == 2);
- REQUIRE(i->second.first == 3);
- REQUIRE(i->second.second == 4);
-}
diff --git a/third_party/optional/tests/extensions.cpp b/third_party/optional/tests/extensions.cpp
deleted file mode 100644
index 55ca613..0000000
--- a/third_party/optional/tests/extensions.cpp
+++ /dev/null
@@ -1,352 +0,0 @@
-#include "catch.hpp"
-#include "optional.hpp"
-#include <string>
-
-#define TOKENPASTE(x, y) x##y
-#define TOKENPASTE2(x, y) TOKENPASTE(x, y)
-#define STATIC_REQUIRE(e) \
- constexpr bool TOKENPASTE2(rqure, __LINE__) = e; \
- REQUIRE(e);
-
-constexpr int get_int(int) { return 42; }
-TL_OPTIONAL_11_CONSTEXPR tl::optional<int> get_opt_int(int) { return 42; }
-
-// What is Clang Format up to?!
-TEST_CASE("Monadic operations", "[monadic]") {
- SECTION("map") { // lhs is empty
- tl::optional<int> o1;
- auto o1r = o1.map([](int i) { return i + 2; });
- STATIC_REQUIRE((std::is_same<decltype(o1r), tl::optional<int>>::value));
- REQUIRE(!o1r);
-
- // lhs has value
- tl::optional<int> o2 = 40;
- auto o2r = o2.map([](int i) { return i + 2; });
- STATIC_REQUIRE((std::is_same<decltype(o2r), tl::optional<int>>::value));
- REQUIRE(o2r.value() == 42);
-
- struct rval_call_map {
- double operator()(int) && { return 42.0; };
- };
-
- // ensure that function object is forwarded
- tl::optional<int> o3 = 42;
- auto o3r = o3.map(rval_call_map{});
- STATIC_REQUIRE((std::is_same<decltype(o3r), tl::optional<double>>::value));
- REQUIRE(o3r.value() == 42);
-
- // ensure that lhs is forwarded
- tl::optional<int> o4 = 40;
- auto o4r = std::move(o4).map([](int &&i) { return i + 2; });
- STATIC_REQUIRE((std::is_same<decltype(o4r), tl::optional<int>>::value));
- REQUIRE(o4r.value() == 42);
-
- // ensure that lhs is const-propagated
- const tl::optional<int> o5 = 40;
- auto o5r = o5.map([](const int &i) { return i + 2; });
- STATIC_REQUIRE((std::is_same<decltype(o5r), tl::optional<int>>::value));
- REQUIRE(o5r.value() == 42);
-
- // test void return
- tl::optional<int> o7 = 40;
- auto f7 = [](const int &i) { return; };
- auto o7r = o7.map(f7);
- STATIC_REQUIRE(
- (std::is_same<decltype(o7r), tl::optional<tl::monostate>>::value));
- REQUIRE(o7r.has_value());
-
- // test each overload in turn
- tl::optional<int> o8 = 42;
- auto o8r = o8.map([](int) { return 42; });
- REQUIRE(*o8r == 42);
-
- tl::optional<int> o9 = 42;
- auto o9r = o9.map([](int) { return; });
- REQUIRE(o9r);
-
- tl::optional<int> o12 = 42;
- auto o12r = std::move(o12).map([](int) { return 42; });
- REQUIRE(*o12r == 42);
-
- tl::optional<int> o13 = 42;
- auto o13r = std::move(o13).map([](int) { return; });
- REQUIRE(o13r);
-
- const tl::optional<int> o16 = 42;
- auto o16r = o16.map([](int) { return 42; });
- REQUIRE(*o16r == 42);
-
- const tl::optional<int> o17 = 42;
- auto o17r = o17.map([](int) { return; });
- REQUIRE(o17r);
-
- const tl::optional<int> o20 = 42;
- auto o20r = std::move(o20).map([](int) { return 42; });
- REQUIRE(*o20r == 42);
-
- const tl::optional<int> o21 = 42;
- auto o21r = std::move(o21).map([](int) { return; });
- REQUIRE(o21r);
-
- tl::optional<int> o24 = tl::nullopt;
- auto o24r = o24.map([](int) { return 42; });
- REQUIRE(!o24r);
-
- tl::optional<int> o25 = tl::nullopt;
- auto o25r = o25.map([](int) { return; });
- REQUIRE(!o25r);
-
- tl::optional<int> o28 = tl::nullopt;
- auto o28r = std::move(o28).map([](int) { return 42; });
- REQUIRE(!o28r);
-
- tl::optional<int> o29 = tl::nullopt;
- auto o29r = std::move(o29).map([](int) { return; });
- REQUIRE(!o29r);
-
- const tl::optional<int> o32 = tl::nullopt;
- auto o32r = o32.map([](int) { return 42; });
- REQUIRE(!o32r);
-
- const tl::optional<int> o33 = tl::nullopt;
- auto o33r = o33.map([](int) { return; });
- REQUIRE(!o33r);
-
- const tl::optional<int> o36 = tl::nullopt;
- auto o36r = std::move(o36).map([](int) { return 42; });
- REQUIRE(!o36r);
-
- const tl::optional<int> o37 = tl::nullopt;
- auto o37r = std::move(o37).map([](int) { return; });
- REQUIRE(!o37r);
-
- // callable which returns a reference
- tl::optional<int> o38 = 42;
- auto o38r = o38.map([](int &i) -> const int & { return i; });
- REQUIRE(o38r);
- REQUIRE(*o38r == 42);
-
- int i = 42;
- tl::optional<int&> o39 = i;
- o39.map([](int& x){x = 12;});
- REQUIRE(i == 12);
- }
-
- SECTION("map constexpr") {
-#if !defined(_MSC_VER) && defined(TL_OPTIONAL_CXX14)
- // test each overload in turn
- constexpr tl::optional<int> o16 = 42;
- constexpr auto o16r = o16.map(get_int);
- STATIC_REQUIRE(*o16r == 42);
-
- constexpr tl::optional<int> o20 = 42;
- constexpr auto o20r = std::move(o20).map(get_int);
- STATIC_REQUIRE(*o20r == 42);
-
- constexpr tl::optional<int> o32 = tl::nullopt;
- constexpr auto o32r = o32.map(get_int);
- STATIC_REQUIRE(!o32r);
- constexpr tl::optional<int> o36 = tl::nullopt;
- constexpr auto o36r = std::move(o36).map(get_int);
- STATIC_REQUIRE(!o36r);
-#endif
- }
-
- SECTION("and_then") {
-
- // lhs is empty
- tl::optional<int> o1;
- auto o1r = o1.and_then([](int i) { return tl::optional<float>{42}; });
- STATIC_REQUIRE((std::is_same<decltype(o1r), tl::optional<float>>::value));
- REQUIRE(!o1r);
-
- // lhs has value
- tl::optional<int> o2 = 12;
- auto o2r = o2.and_then([](int i) { return tl::optional<float>{42}; });
- STATIC_REQUIRE((std::is_same<decltype(o2r), tl::optional<float>>::value));
- REQUIRE(o2r.value() == 42.f);
-
- // lhs is empty, rhs returns empty
- tl::optional<int> o3;
- auto o3r = o3.and_then([](int i) { return tl::optional<float>{}; });
- STATIC_REQUIRE((std::is_same<decltype(o3r), tl::optional<float>>::value));
- REQUIRE(!o3r);
-
- // rhs returns empty
- tl::optional<int> o4 = 12;
- auto o4r = o4.and_then([](int i) { return tl::optional<float>{}; });
- STATIC_REQUIRE((std::is_same<decltype(o4r), tl::optional<float>>::value));
- REQUIRE(!o4r);
-
- struct rval_call_and_then {
- tl::optional<double> operator()(int) && {
- return tl::optional<double>(42.0);
- };
- };
-
- // ensure that function object is forwarded
- tl::optional<int> o5 = 42;
- auto o5r = o5.and_then(rval_call_and_then{});
- STATIC_REQUIRE((std::is_same<decltype(o5r), tl::optional<double>>::value));
- REQUIRE(o5r.value() == 42);
-
- // ensure that lhs is forwarded
- tl::optional<int> o6 = 42;
- auto o6r =
- std::move(o6).and_then([](int &&i) { return tl::optional<double>(i); });
- STATIC_REQUIRE((std::is_same<decltype(o6r), tl::optional<double>>::value));
- REQUIRE(o6r.value() == 42);
-
- // ensure that function object is const-propagated
- const tl::optional<int> o7 = 42;
- auto o7r =
- o7.and_then([](const int &i) { return tl::optional<double>(i); });
- STATIC_REQUIRE((std::is_same<decltype(o7r), tl::optional<double>>::value));
- REQUIRE(o7r.value() == 42);
-
- // test each overload in turn
- tl::optional<int> o8 = 42;
- auto o8r = o8.and_then([](int i) { return tl::make_optional(42); });
- REQUIRE(*o8r == 42);
-
- tl::optional<int> o9 = 42;
- auto o9r =
- std::move(o9).and_then([](int i) { return tl::make_optional(42); });
- REQUIRE(*o9r == 42);
-
- const tl::optional<int> o10 = 42;
- auto o10r = o10.and_then([](int i) { return tl::make_optional(42); });
- REQUIRE(*o10r == 42);
-
- const tl::optional<int> o11 = 42;
- auto o11r =
- std::move(o11).and_then([](int i) { return tl::make_optional(42); });
- REQUIRE(*o11r == 42);
-
- tl::optional<int> o16 = tl::nullopt;
- auto o16r = o16.and_then([](int i) { return tl::make_optional(42); });
- REQUIRE(!o16r);
-
- tl::optional<int> o17 = tl::nullopt;
- auto o17r =
- std::move(o17).and_then([](int i) { return tl::make_optional(42); });
- REQUIRE(!o17r);
-
- const tl::optional<int> o18 = tl::nullopt;
- auto o18r = o18.and_then([](int i) { return tl::make_optional(42); });
- REQUIRE(!o18r);
-
- const tl::optional<int> o19 = tl::nullopt;
- auto o19r = std::move(o19).and_then([](int i) { return tl::make_optional(42); });
- REQUIRE(!o19r);
-
- int i = 3;
- tl::optional<int&> o20{i};
- std::move(o20).and_then([](int& r){return tl::optional<int&>{++r};});
- REQUIRE(o20);
- REQUIRE(i == 4);
- }
-
- SECTION("constexpr and_then") {
-#if !defined(_MSC_VER) && defined(TL_OPTIONAL_CXX14)
-
- constexpr tl::optional<int> o10 = 42;
- constexpr auto o10r = o10.and_then(get_opt_int);
- REQUIRE(*o10r == 42);
-
- constexpr tl::optional<int> o11 = 42;
- constexpr auto o11r = std::move(o11).and_then(get_opt_int);
- REQUIRE(*o11r == 42);
-
- constexpr tl::optional<int> o18 = tl::nullopt;
- constexpr auto o18r = o18.and_then(get_opt_int);
- REQUIRE(!o18r);
-
- constexpr tl::optional<int> o19 = tl::nullopt;
- constexpr auto o19r = std::move(o19).and_then(get_opt_int);
- REQUIRE(!o19r);
-#endif
- }
-
- SECTION("or else") {
- tl::optional<int> o1 = 42;
- REQUIRE(*(o1.or_else([] { return tl::make_optional(13); })) == 42);
-
- tl::optional<int> o2;
- REQUIRE(*(o2.or_else([] { return tl::make_optional(13); })) == 13);
- }
-
- SECTION("disjunction") {
- tl::optional<int> o1 = 42;
- tl::optional<int> o2 = 12;
- tl::optional<int> o3;
-
- REQUIRE(*o1.disjunction(o2) == 42);
- REQUIRE(*o1.disjunction(o3) == 42);
- REQUIRE(*o2.disjunction(o1) == 12);
- REQUIRE(*o2.disjunction(o3) == 12);
- REQUIRE(*o3.disjunction(o1) == 42);
- REQUIRE(*o3.disjunction(o2) == 12);
- }
-
- SECTION("conjunction") {
- tl::optional<int> o1 = 42;
- REQUIRE(*o1.conjunction(42.0) == 42.0);
- REQUIRE(*o1.conjunction(std::string{"hello"}) == std::string{"hello"});
-
- tl::optional<int> o2;
- REQUIRE(!o2.conjunction(42.0));
- REQUIRE(!o2.conjunction(std::string{"hello"}));
- }
-
- SECTION("map_or") {
- tl::optional<int> o1 = 21;
- REQUIRE((o1.map_or([](int x) { return x * 2; }, 13)) == 42);
-
- tl::optional<int> o2;
- REQUIRE((o2.map_or([](int x) { return x * 2; }, 13)) == 13);
- }
-
- SECTION("map_or_else") {
- tl::optional<int> o1 = 21;
- REQUIRE((o1.map_or_else([](int x) { return x * 2; }, [] { return 13; })) ==
- 42);
-
- tl::optional<int> o2;
- REQUIRE((o2.map_or_else([](int x) { return x * 2; }, [] { return 13; })) ==
- 13);
- }
-
- SECTION("take") {
- tl::optional<int> o1 = 42;
- REQUIRE(*o1.take() == 42);
- REQUIRE(!o1);
-
- tl::optional<int> o2;
- REQUIRE(!o2.take());
- REQUIRE(!o2);
- }
-
- struct foo {
- void non_const() {}
- };
-
-#if defined(TL_OPTIONAL_CXX14) && !defined(TL_OPTIONAL_GCC49) && \
- !defined(TL_OPTIONAL_GCC54) && !defined(TL_OPTIONAL_GCC55)
- SECTION("Issue #1") {
- tl::optional<foo> f = foo{};
- auto l = [](auto &&x) { x.non_const(); };
- f.map(l);
- }
-#endif
-
- struct overloaded {
- tl::optional<int> operator()(foo &) { return 0; }
- tl::optional<std::string> operator()(const foo &) { return ""; }
- };
-
- SECTION("Issue #2") {
- tl::optional<foo> f = foo{};
- auto x = f.and_then(overloaded{});
- }
-};
diff --git a/third_party/optional/tests/hash.cpp b/third_party/optional/tests/hash.cpp
deleted file mode 100644
index 16437da..0000000
--- a/third_party/optional/tests/hash.cpp
+++ /dev/null
@@ -1,4 +0,0 @@
-#include "catch.hpp"
-#include "optional.hpp"
-
-TEST_CASE("Hashing", "[hash]") {}
diff --git a/third_party/optional/tests/in_place.cpp b/third_party/optional/tests/in_place.cpp
deleted file mode 100644
index 07254e4..0000000
--- a/third_party/optional/tests/in_place.cpp
+++ /dev/null
@@ -1,41 +0,0 @@
-#include "catch.hpp"
-#include "optional.hpp"
-
-#include <tuple>
-#include <vector>
-
-struct takes_init_and_variadic {
- std::vector<int> v;
- std::tuple<int, int> t;
- template <class... Args>
- takes_init_and_variadic(std::initializer_list<int> l, Args &&... args)
- : v(l), t(std::forward<Args>(args)...) {}
-};
-
-TEST_CASE("In place", "[in_place]") {
- tl::optional<int> o1{tl::in_place};
- tl::optional<int> o2(tl::in_place);
- REQUIRE(o1);
- REQUIRE(o1 == 0);
- REQUIRE(o2);
- REQUIRE(o2 == 0);
-
- tl::optional<int> o3(tl::in_place, 42);
- REQUIRE(o3 == 42);
-
- tl::optional<std::tuple<int, int>> o4(tl::in_place, 0, 1);
- REQUIRE(o4);
- REQUIRE(std::get<0>(*o4) == 0);
- REQUIRE(std::get<1>(*o4) == 1);
-
- tl::optional<std::vector<int>> o5(tl::in_place, {0, 1});
- REQUIRE(o5);
- REQUIRE((*o5)[0] == 0);
- REQUIRE((*o5)[1] == 1);
-
- tl::optional<takes_init_and_variadic> o6(tl::in_place, {0, 1}, 2, 3);
- REQUIRE(o6->v[0] == 0);
- REQUIRE(o6->v[1] == 1);
- REQUIRE(std::get<0>(o6->t) == 2);
- REQUIRE(std::get<1>(o6->t) == 3);
-}
diff --git a/third_party/optional/tests/issues.cpp b/third_party/optional/tests/issues.cpp
deleted file mode 100644
index 387b083..0000000
--- a/third_party/optional/tests/issues.cpp
+++ /dev/null
@@ -1,34 +0,0 @@
-#include "catch.hpp"
-#include "optional.hpp"
-#include <type_traits>
-
-struct foo{
- int& v() { return i; }
- int i = 0;
-};
-
-int& x(int& i) { i = 42; return i;}
-
-TEST_CASE("issue 14") {
- tl::optional<foo> f = foo{};
- auto v = f.map(&foo::v).map(x);
- static_assert(std::is_same<decltype(v), tl::optional<int&>>::value, "Must return a reference");
- REQUIRE(f->i == 42);
- REQUIRE(*v == 42);
- REQUIRE((&f->i) == (&*v));
-}
-
-struct fail_on_copy_self {
- int value;
- fail_on_copy_self(int v) : value(v) {}
- fail_on_copy_self(const fail_on_copy_self& other) : value(other.value) {
- REQUIRE(&other != this);
- }
-};
-
-TEST_CASE("issue 15") {
- tl::optional<fail_on_copy_self> o = fail_on_copy_self(42);
-
- o = o;
- REQUIRE(o->value == 42);
-}
\ No newline at end of file
diff --git a/third_party/optional/tests/main.cpp b/third_party/optional/tests/main.cpp
deleted file mode 100644
index 0c7c351..0000000
--- a/third_party/optional/tests/main.cpp
+++ /dev/null
@@ -1,2 +0,0 @@
-#define CATCH_CONFIG_MAIN
-#include "catch.hpp"
diff --git a/third_party/optional/tests/make_optional.cpp b/third_party/optional/tests/make_optional.cpp
deleted file mode 100644
index ba44fd9..0000000
--- a/third_party/optional/tests/make_optional.cpp
+++ /dev/null
@@ -1,46 +0,0 @@
-#include "catch.hpp"
-#include "optional.hpp"
-
-#include <tuple>
-#include <vector>
-
-struct takes_init_and_variadic {
- std::vector<int> v;
- std::tuple<int, int> t;
- template <class... Args>
- takes_init_and_variadic(std::initializer_list<int> l, Args &&... args)
- : v(l), t(std::forward<Args>(args)...) {}
-};
-
-TEST_CASE("Make optional", "[make_optional]") {
- auto o1 = tl::make_optional(42);
- auto o2 = tl::optional<int>(42);
-
- constexpr bool is_same = std::is_same<decltype(o1), tl::optional<int>>::value;
- REQUIRE(is_same);
- REQUIRE(o1 == o2);
-
- auto o3 = tl::make_optional<std::tuple<int, int, int, int>>(0, 1, 2, 3);
- REQUIRE(std::get<0>(*o3) == 0);
- REQUIRE(std::get<1>(*o3) == 1);
- REQUIRE(std::get<2>(*o3) == 2);
- REQUIRE(std::get<3>(*o3) == 3);
-
- auto o4 = tl::make_optional<std::vector<int>>({0, 1, 2, 3});
- REQUIRE(o4.value()[0] == 0);
- REQUIRE(o4.value()[1] == 1);
- REQUIRE(o4.value()[2] == 2);
- REQUIRE(o4.value()[3] == 3);
-
- auto o5 = tl::make_optional<takes_init_and_variadic>({0, 1}, 2, 3);
- REQUIRE(o5->v[0] == 0);
- REQUIRE(o5->v[1] == 1);
- REQUIRE(std::get<0>(o5->t) == 2);
- REQUIRE(std::get<1>(o5->t) == 3);
-
- auto i = 42;
- auto o6 = tl::make_optional<int&>(i);
- REQUIRE((std::is_same<decltype(o6), tl::optional<int&>>::value));
- REQUIRE(o6);
- REQUIRE(*o6 == 42);
-}
diff --git a/third_party/optional/tests/noexcept.cpp b/third_party/optional/tests/noexcept.cpp
deleted file mode 100644
index edfa88f..0000000
--- a/third_party/optional/tests/noexcept.cpp
+++ /dev/null
@@ -1,100 +0,0 @@
-#include "catch.hpp"
-#include "optional.hpp"
-
-TEST_CASE("Noexcept", "[noexcept]") {
- tl::optional<int> o1{4};
- tl::optional<int> o2{42};
-
- SECTION("comparison with nullopt") {
- REQUIRE(noexcept(o1 == tl::nullopt));
- REQUIRE(noexcept(tl::nullopt == o1));
- REQUIRE(noexcept(o1 != tl::nullopt));
- REQUIRE(noexcept(tl::nullopt != o1));
- REQUIRE(noexcept(o1 < tl::nullopt));
- REQUIRE(noexcept(tl::nullopt < o1));
- REQUIRE(noexcept(o1 <= tl::nullopt));
- REQUIRE(noexcept(tl::nullopt <= o1));
- REQUIRE(noexcept(o1 > tl::nullopt));
- REQUIRE(noexcept(tl::nullopt > o1));
- REQUIRE(noexcept(o1 >= tl::nullopt));
- REQUIRE(noexcept(tl::nullopt >= o1));
- }
-
- SECTION("swap") {
- //TODO see why this fails
-#if !defined(_MSC_VER) || _MSC_VER > 1900
- REQUIRE(noexcept(swap(o1, o2)) == noexcept(o1.swap(o2)));
-
- struct nothrow_swappable {
- nothrow_swappable &swap(const nothrow_swappable &) noexcept {
- return *this;
- }
- };
-
- struct throw_swappable {
- throw_swappable() = default;
- throw_swappable(const throw_swappable &) {}
- throw_swappable(throw_swappable &&) {}
- throw_swappable &swap(const throw_swappable &) { return *this; }
- };
-
- tl::optional<nothrow_swappable> ont;
- tl::optional<throw_swappable> ot;
-
- REQUIRE(noexcept(ont.swap(ont)));
- REQUIRE(!noexcept(ot.swap(ot)));
- #endif
- }
-
- SECTION("constructors") {
- //TODO see why this fails
-#if !defined(_MSC_VER) || _MSC_VER > 1900
- REQUIRE(noexcept(tl::optional<int>{}));
- REQUIRE(noexcept(tl::optional<int>{tl::nullopt}));
-
- struct nothrow_move {
- nothrow_move(nothrow_move &&) noexcept = default;
- };
-
- struct throw_move {
- throw_move(throw_move &&){};
- };
-
- using nothrow_opt = tl::optional<nothrow_move>;
- using throw_opt = tl::optional<throw_move>;
-
- REQUIRE(std::is_nothrow_move_constructible<nothrow_opt>::value);
- REQUIRE(!std::is_nothrow_move_constructible<throw_opt>::value);
-#endif
- }
-
- SECTION("assignment") {
- REQUIRE(noexcept(o1 = tl::nullopt));
-
- struct nothrow_move_assign {
- nothrow_move_assign() = default;
- nothrow_move_assign(nothrow_move_assign &&) noexcept = default;
- nothrow_move_assign &operator=(const nothrow_move_assign &) = default;
- };
-
- struct throw_move_assign {
- throw_move_assign() = default;
- throw_move_assign(throw_move_assign &&){};
- throw_move_assign &operator=(const throw_move_assign &) { return *this; }
- };
-
- using nothrow_opt = tl::optional<nothrow_move_assign>;
- using throw_opt = tl::optional<throw_move_assign>;
-
- REQUIRE(
- noexcept(std::declval<nothrow_opt>() = std::declval<nothrow_opt>()));
- REQUIRE(!noexcept(std::declval<throw_opt>() = std::declval<throw_opt>()));
- }
-
- SECTION("observers") {
- REQUIRE(noexcept(static_cast<bool>(o1)));
- REQUIRE(noexcept(o1.has_value()));
- }
-
- SECTION("modifiers") { REQUIRE(noexcept(o1.reset())); }
-}
diff --git a/third_party/optional/tests/nullopt.cpp b/third_party/optional/tests/nullopt.cpp
deleted file mode 100644
index 6340724..0000000
--- a/third_party/optional/tests/nullopt.cpp
+++ /dev/null
@@ -1,16 +0,0 @@
-#include "catch.hpp"
-#include "optional.hpp"
-
-TEST_CASE("Nullopt", "[nullopt]") {
- tl::optional<int> o1 = tl::nullopt;
- tl::optional<int> o2{tl::nullopt};
- tl::optional<int> o3(tl::nullopt);
- tl::optional<int> o4 = {tl::nullopt};
-
- REQUIRE(!o1);
- REQUIRE(!o2);
- REQUIRE(!o3);
- REQUIRE(!o4);
-
- REQUIRE(!std::is_default_constructible<tl::nullopt_t>::value);
-}
diff --git a/third_party/optional/tests/observers.cpp b/third_party/optional/tests/observers.cpp
deleted file mode 100644
index 642b9f6..0000000
--- a/third_party/optional/tests/observers.cpp
+++ /dev/null
@@ -1,35 +0,0 @@
-#include "catch.hpp"
-#include "optional.hpp"
-
-struct move_detector {
- move_detector() = default;
- move_detector(move_detector &&rhs) { rhs.been_moved = true; }
- bool been_moved = false;
-};
-
-TEST_CASE("Observers", "[observers]") {
- tl::optional<int> o1 = 42;
- tl::optional<int> o2;
- const tl::optional<int> o3 = 42;
-
- REQUIRE(*o1 == 42);
- REQUIRE(*o1 == o1.value());
- REQUIRE(o2.value_or(42) == 42);
- REQUIRE(o3.value() == 42);
- auto success = std::is_same<decltype(o1.value()), int &>::value;
- REQUIRE(success);
- success = std::is_same<decltype(o3.value()), const int &>::value;
- REQUIRE(success);
- success = std::is_same<decltype(std::move(o1).value()), int &&>::value;
- REQUIRE(success);
-
- #ifndef TL_OPTIONAL_NO_CONSTRR
- success = std::is_same<decltype(std::move(o3).value()), const int &&>::value;
- REQUIRE(success);
- #endif
-
- tl::optional<move_detector> o4{tl::in_place};
- move_detector o5 = std::move(o4).value();
- REQUIRE(o4->been_moved);
- REQUIRE(!o5.been_moved);
-}
diff --git a/third_party/optional/tests/relops.cpp b/third_party/optional/tests/relops.cpp
deleted file mode 100644
index 2f388e7..0000000
--- a/third_party/optional/tests/relops.cpp
+++ /dev/null
@@ -1,153 +0,0 @@
-#include "catch.hpp"
-#include "optional.hpp"
-
-TEST_CASE("Relational ops", "[relops]") {
- tl::optional<int> o1{4};
- tl::optional<int> o2{42};
- tl::optional<int> o3{};
-
- SECTION("self simple") {
- REQUIRE(!(o1 == o2));
- REQUIRE(o1 == o1);
- REQUIRE(o1 != o2);
- REQUIRE(!(o1 != o1));
- REQUIRE(o1 < o2);
- REQUIRE(!(o1 < o1));
- REQUIRE(!(o1 > o2));
- REQUIRE(!(o1 > o1));
- REQUIRE(o1 <= o2);
- REQUIRE(o1 <= o1);
- REQUIRE(!(o1 >= o2));
- REQUIRE(o1 >= o1);
- }
-
- SECTION("nullopt simple") {
- REQUIRE(!(o1 == tl::nullopt));
- REQUIRE(!(tl::nullopt == o1));
- REQUIRE(o1 != tl::nullopt);
- REQUIRE(tl::nullopt != o1);
- REQUIRE(!(o1 < tl::nullopt));
- REQUIRE(tl::nullopt < o1);
- REQUIRE(o1 > tl::nullopt);
- REQUIRE(!(tl::nullopt > o1));
- REQUIRE(!(o1 <= tl::nullopt));
- REQUIRE(tl::nullopt <= o1);
- REQUIRE(o1 >= tl::nullopt);
- REQUIRE(!(tl::nullopt >= o1));
-
- REQUIRE(o3 == tl::nullopt);
- REQUIRE(tl::nullopt == o3);
- REQUIRE(!(o3 != tl::nullopt));
- REQUIRE(!(tl::nullopt != o3));
- REQUIRE(!(o3 < tl::nullopt));
- REQUIRE(!(tl::nullopt < o3));
- REQUIRE(!(o3 > tl::nullopt));
- REQUIRE(!(tl::nullopt > o3));
- REQUIRE(o3 <= tl::nullopt);
- REQUIRE(tl::nullopt <= o3);
- REQUIRE(o3 >= tl::nullopt);
- REQUIRE(tl::nullopt >= o3);
- }
-
- SECTION("with T simple") {
- REQUIRE(!(o1 == 1));
- REQUIRE(!(1 == o1));
- REQUIRE(o1 != 1);
- REQUIRE(1 != o1);
- REQUIRE(!(o1 < 1));
- REQUIRE(1 < o1);
- REQUIRE(o1 > 1);
- REQUIRE(!(1 > o1));
- REQUIRE(!(o1 <= 1));
- REQUIRE(1 <= o1);
- REQUIRE(o1 >= 1);
- REQUIRE(!(1 >= o1));
-
- REQUIRE(o1 == 4);
- REQUIRE(4 == o1);
- REQUIRE(!(o1 != 4));
- REQUIRE(!(4 != o1));
- REQUIRE(!(o1 < 4));
- REQUIRE(!(4 < o1));
- REQUIRE(!(o1 > 4));
- REQUIRE(!(4 > o1));
- REQUIRE(o1 <= 4);
- REQUIRE(4 <= o1);
- REQUIRE(o1 >= 4);
- REQUIRE(4 >= o1);
- }
-
- tl::optional<std::string> o4{"hello"};
- tl::optional<std::string> o5{"xyz"};
-
- SECTION("self complex") {
- REQUIRE(!(o4 == o5));
- REQUIRE(o4 == o4);
- REQUIRE(o4 != o5);
- REQUIRE(!(o4 != o4));
- REQUIRE(o4 < o5);
- REQUIRE(!(o4 < o4));
- REQUIRE(!(o4 > o5));
- REQUIRE(!(o4 > o4));
- REQUIRE(o4 <= o5);
- REQUIRE(o4 <= o4);
- REQUIRE(!(o4 >= o5));
- REQUIRE(o4 >= o4);
- }
-
- SECTION("nullopt complex") {
- REQUIRE(!(o4 == tl::nullopt));
- REQUIRE(!(tl::nullopt == o4));
- REQUIRE(o4 != tl::nullopt);
- REQUIRE(tl::nullopt != o4);
- REQUIRE(!(o4 < tl::nullopt));
- REQUIRE(tl::nullopt < o4);
- REQUIRE(o4 > tl::nullopt);
- REQUIRE(!(tl::nullopt > o4));
- REQUIRE(!(o4 <= tl::nullopt));
- REQUIRE(tl::nullopt <= o4);
- REQUIRE(o4 >= tl::nullopt);
- REQUIRE(!(tl::nullopt >= o4));
-
- REQUIRE(o3 == tl::nullopt);
- REQUIRE(tl::nullopt == o3);
- REQUIRE(!(o3 != tl::nullopt));
- REQUIRE(!(tl::nullopt != o3));
- REQUIRE(!(o3 < tl::nullopt));
- REQUIRE(!(tl::nullopt < o3));
- REQUIRE(!(o3 > tl::nullopt));
- REQUIRE(!(tl::nullopt > o3));
- REQUIRE(o3 <= tl::nullopt);
- REQUIRE(tl::nullopt <= o3);
- REQUIRE(o3 >= tl::nullopt);
- REQUIRE(tl::nullopt >= o3);
- }
-
- SECTION("with T complex") {
- REQUIRE(!(o4 == "a"));
- REQUIRE(!("a" == o4));
- REQUIRE(o4 != "a");
- REQUIRE("a" != o4);
- REQUIRE(!(o4 < "a"));
- REQUIRE("a" < o4);
- REQUIRE(o4 > "a");
- REQUIRE(!("a" > o4));
- REQUIRE(!(o4 <= "a"));
- REQUIRE("a" <= o4);
- REQUIRE(o4 >= "a");
- REQUIRE(!("a" >= o4));
-
- REQUIRE(o4 == "hello");
- REQUIRE("hello" == o4);
- REQUIRE(!(o4 != "hello"));
- REQUIRE(!("hello" != o4));
- REQUIRE(!(o4 < "hello"));
- REQUIRE(!("hello" < o4));
- REQUIRE(!(o4 > "hello"));
- REQUIRE(!("hello" > o4));
- REQUIRE(o4 <= "hello");
- REQUIRE("hello" <= o4);
- REQUIRE(o4 >= "hello");
- REQUIRE("hello" >= o4);
- }
-}
diff --git a/third_party/optional/tl/optional.hpp b/third_party/optional/tl/optional.hpp
deleted file mode 100644
index 27ac1c0..0000000
--- a/third_party/optional/tl/optional.hpp
+++ /dev/null
@@ -1,2353 +0,0 @@
-
-///
-// optional - An implementation of std::optional with extensions
-// Written in 2017 by Simon Brand (@TartanLlama)
-//
-// To the extent possible under law, the author(s) have dedicated all
-// copyright and related and neighboring rights to this software to the
-// public domain worldwide. This software is distributed without any warranty.
-//
-// You should have received a copy of the CC0 Public Domain Dedication
-// along with this software. If not, see
-// <http://creativecommons.org/publicdomain/zero/1.0/>.
-///
-
-#ifndef TL_OPTIONAL_HPP
-#define TL_OPTIONAL_HPP
-
-#define TL_OPTIONAL_VERSION_MAJOR 0
-#define TL_OPTIONAL_VERSION_MINOR 5
-
-#include <exception>
-#include <functional>
-#include <new>
-#include <type_traits>
-#include <utility>
-
-#if (defined(_MSC_VER) && _MSC_VER == 1900)
-#define TL_OPTIONAL_MSVC2015
-#endif
-
-// TODO(Brian): We use libstdc++ with clang too. Sort this out nicely.
-#if (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ <= 9 && \
- !(defined(__clang__) && defined(_LIBCPP_VERSION)))
-#define TL_OPTIONAL_GCC49
-#endif
-
-#if (defined(__GNUC__) && __GNUC__ == 5 && __GNUC_MINOR__ <= 4 && \
- !defined(__clang__))
-#define TL_OPTIONAL_GCC54
-#endif
-
-#if (defined(__GNUC__) && __GNUC__ == 5 && __GNUC_MINOR__ <= 5 && \
- !defined(__clang__))
-#define TL_OPTIONAL_GCC55
-#endif
-
-#ifdef TL_OPTIONAL_GCC49
-// GCC < 5 doesn't support overloading on const&& for member functions
-#define TL_OPTIONAL_NO_CONSTRR
-
-// GCC < 5 doesn't support some standard C++11 type traits
-#define TL_OPTIONAL_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(T) \
- std::has_trivial_copy_constructor<T>::value
-#define TL_OPTIONAL_IS_TRIVIALLY_COPY_ASSIGNABLE(T) std::has_trivial_copy_assign<T>::value
-
-// This one will be different for GCC 5.7 if it's ever supported
-#define TL_OPTIONAL_IS_TRIVIALLY_DESTRUCTIBLE(T) std::is_trivially_destructible<T>::value
-
-// GCC 5 < v < 8 has a bug in is_trivially_copy_constructible which breaks std::vector
-// for non-copyable types
-#elif (defined(__GNUC__) && __GNUC__ < 8 && \
- !defined(__clang__))
-#ifndef TL_GCC_LESS_8_TRIVIALLY_COPY_CONSTRUCTIBLE_MUTEX
-#define TL_GCC_LESS_8_TRIVIALLY_COPY_CONSTRUCTIBLE_MUTEX
-namespace tl {
- namespace detail {
- template<class T>
- struct is_trivially_copy_constructible : std::is_trivially_copy_constructible<T>{};
-#ifdef _GLIBCXX_VECTOR
- template<class T, class A>
- struct is_trivially_copy_constructible<std::vector<T,A>>
- : std::is_trivially_copy_constructible<T>{};
-#endif
- }
-}
-#endif
-
-#define TL_OPTIONAL_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(T) \
- tl::detail::is_trivially_copy_constructible<T>::value
-#define TL_OPTIONAL_IS_TRIVIALLY_COPY_ASSIGNABLE(T) \
- std::is_trivially_copy_assignable<T>::value
-#define TL_OPTIONAL_IS_TRIVIALLY_DESTRUCTIBLE(T) std::is_trivially_destructible<T>::value
-#else
-#define TL_OPTIONAL_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(T) \
- std::is_trivially_copy_constructible<T>::value
-#define TL_OPTIONAL_IS_TRIVIALLY_COPY_ASSIGNABLE(T) \
- std::is_trivially_copy_assignable<T>::value
-#define TL_OPTIONAL_IS_TRIVIALLY_DESTRUCTIBLE(T) std::is_trivially_destructible<T>::value
-#endif
-
-#if __cplusplus > 201103L
-// TODO(Brian): Re-enable this once we have full C++14 support.
-//#define TL_OPTIONAL_CXX14
-#endif
-
-// constexpr implies const in C++11, not C++14
-#if (__cplusplus == 201103L || defined(TL_OPTIONAL_MSVC2015) || \
- defined(TL_OPTIONAL_GCC49))
-/// \exclude
-#define TL_OPTIONAL_11_CONSTEXPR
-#else
-/// \exclude
-#define TL_OPTIONAL_11_CONSTEXPR constexpr
-#endif
-
-namespace tl {
-#ifndef TL_MONOSTATE_INPLACE_MUTEX
-#define TL_MONOSTATE_INPLACE_MUTEX
-/// \brief Used to represent an optional with no data; essentially a bool
-class monostate {};
-
-/// \brief A tag type to tell optional to construct its value in-place
-struct in_place_t {
- explicit in_place_t() = default;
-};
-/// \brief A tag to tell optional to construct its value in-place
-static constexpr in_place_t in_place{};
-#endif
-
-template <class T> class optional;
-
-/// \exclude
-namespace detail {
-#ifndef TL_TRAITS_MUTEX
-#define TL_TRAITS_MUTEX
-// C++14-style aliases for brevity
-template <class T> using remove_const_t = typename std::remove_const<T>::type;
-template <class T>
-using remove_reference_t = typename std::remove_reference<T>::type;
-template <class T> using decay_t = typename std::decay<T>::type;
-template <bool E, class T = void>
-using enable_if_t = typename std::enable_if<E, T>::type;
-template <bool B, class T, class F>
-using conditional_t = typename std::conditional<B, T, F>::type;
-
-// std::conjunction from C++17
-template <class...> struct conjunction : std::true_type {};
-template <class B> struct conjunction<B> : B {};
-template <class B, class... Bs>
-struct conjunction<B, Bs...>
- : std::conditional<bool(B::value), conjunction<Bs...>, B>::type {};
-
-#if defined(_LIBCPP_VERSION) && __cplusplus == 201103L
-#define TL_OPTIONAL_LIBCXX_MEM_FN_WORKAROUND
-#endif
-
-// In C++11 mode, there's an issue in libc++'s std::mem_fn
-// which results in a hard-error when using it in a noexcept expression
-// in some cases. This is a check to workaround the common failing case.
-#ifdef TL_OPTIONAL_LIBCXX_MEM_FN_WORKAROUND
-template <class T> struct is_pointer_to_non_const_member_func : std::false_type{};
-template <class T, class Ret, class... Args>
-struct is_pointer_to_non_const_member_func<Ret (T::*) (Args...)> : std::true_type{};
-template <class T, class Ret, class... Args>
-struct is_pointer_to_non_const_member_func<Ret (T::*) (Args...)&> : std::true_type{};
-template <class T, class Ret, class... Args>
-struct is_pointer_to_non_const_member_func<Ret (T::*) (Args...)&&> : std::true_type{};
-template <class T, class Ret, class... Args>
-struct is_pointer_to_non_const_member_func<Ret (T::*) (Args...) volatile> : std::true_type{};
-template <class T, class Ret, class... Args>
-struct is_pointer_to_non_const_member_func<Ret (T::*) (Args...) volatile&> : std::true_type{};
-template <class T, class Ret, class... Args>
-struct is_pointer_to_non_const_member_func<Ret (T::*) (Args...) volatile&&> : std::true_type{};
-
-template <class T> struct is_const_or_const_ref : std::false_type{};
-template <class T> struct is_const_or_const_ref<T const&> : std::true_type{};
-template <class T> struct is_const_or_const_ref<T const> : std::true_type{};
-#endif
-
-// std::invoke from C++17
-// https://stackoverflow.com/questions/38288042/c11-14-invoke-workaround
-template <typename Fn, typename... Args,
-#ifdef TL_OPTIONAL_LIBCXX_MEM_FN_WORKAROUND
- typename = enable_if_t<!(is_pointer_to_non_const_member_func<Fn>::value
- && is_const_or_const_ref<Args...>::value)>,
-#endif
- typename = enable_if_t<std::is_member_pointer<decay_t<Fn>>::value>,
- int = 0>
-constexpr auto invoke(Fn &&f, Args &&... args) noexcept(
- noexcept(std::mem_fn(f)(std::forward<Args>(args)...)))
- -> decltype(std::mem_fn(f)(std::forward<Args>(args)...)) {
- return std::mem_fn(f)(std::forward<Args>(args)...);
-}
-
-template <typename Fn, typename... Args,
- typename = enable_if_t<!std::is_member_pointer<decay_t<Fn>>::value>>
-constexpr auto invoke(Fn &&f, Args &&... args) noexcept(
- noexcept(std::forward<Fn>(f)(std::forward<Args>(args)...)))
- -> decltype(std::forward<Fn>(f)(std::forward<Args>(args)...)) {
- return std::forward<Fn>(f)(std::forward<Args>(args)...);
-}
-
-// std::invoke_result from C++17
-template <class F, class, class... Us> struct invoke_result_impl;
-
-template <class F, class... Us>
-struct invoke_result_impl<
- F, decltype(detail::invoke(std::declval<F>(), std::declval<Us>()...), void()),
- Us...> {
- using type = decltype(detail::invoke(std::declval<F>(), std::declval<Us>()...));
-};
-
-template <class F, class... Us>
-using invoke_result = invoke_result_impl<F, void, Us...>;
-
-template <class F, class... Us>
-using invoke_result_t = typename invoke_result<F, Us...>::type;
-#endif
-
-// std::void_t from C++17
-template <class...> struct voider { using type = void; };
-template <class... Ts> using void_t = typename voider<Ts...>::type;
-
-// Trait for checking if a type is a tl::optional
-template <class T> struct is_optional_impl : std::false_type {};
-template <class T> struct is_optional_impl<optional<T>> : std::true_type {};
-template <class T> using is_optional = is_optional_impl<decay_t<T>>;
-
-// Change void to tl::monostate
-template <class U>
-using fixup_void = conditional_t<std::is_void<U>::value, monostate, U>;
-
-template <class F, class U, class = invoke_result_t<F, U>>
-using get_map_return = optional<fixup_void<invoke_result_t<F, U>>>;
-
-// Check if invoking F for some Us returns void
-template <class F, class = void, class... U> struct returns_void_impl;
-template <class F, class... U>
-struct returns_void_impl<F, void_t<invoke_result_t<F, U...>>, U...>
- : std::is_void<invoke_result_t<F, U...>> {};
-template <class F, class... U>
-using returns_void = returns_void_impl<F, void, U...>;
-
-template <class T, class... U>
-using enable_if_ret_void = enable_if_t<returns_void<T &&, U...>::value>;
-
-template <class T, class... U>
-using disable_if_ret_void = enable_if_t<!returns_void<T &&, U...>::value>;
-
-template <class T, class U>
-using enable_forward_value =
- detail::enable_if_t<std::is_constructible<T, U &&>::value &&
- !std::is_same<detail::decay_t<U>, in_place_t>::value &&
- !std::is_same<optional<T>, detail::decay_t<U>>::value>;
-
-template <class T, class U, class Other>
-using enable_from_other = detail::enable_if_t<
- std::is_constructible<T, Other>::value &&
- !std::is_constructible<T, optional<U> &>::value &&
- !std::is_constructible<T, optional<U> &&>::value &&
- !std::is_constructible<T, const optional<U> &>::value &&
- !std::is_constructible<T, const optional<U> &&>::value &&
- !std::is_convertible<optional<U> &, T>::value &&
- !std::is_convertible<optional<U> &&, T>::value &&
- !std::is_convertible<const optional<U> &, T>::value &&
- !std::is_convertible<const optional<U> &&, T>::value>;
-
-template <class T, class U>
-using enable_assign_forward = detail::enable_if_t<
- !std::is_same<optional<T>, detail::decay_t<U>>::value &&
- !detail::conjunction<std::is_scalar<T>,
- std::is_same<T, detail::decay_t<U>>>::value &&
- std::is_constructible<T, U>::value && std::is_assignable<T &, U>::value>;
-
-template <class T, class U, class Other>
-using enable_assign_from_other = detail::enable_if_t<
- std::is_constructible<T, Other>::value &&
- std::is_assignable<T &, Other>::value &&
- !std::is_constructible<T, optional<U> &>::value &&
- !std::is_constructible<T, optional<U> &&>::value &&
- !std::is_constructible<T, const optional<U> &>::value &&
- !std::is_constructible<T, const optional<U> &&>::value &&
- !std::is_convertible<optional<U> &, T>::value &&
- !std::is_convertible<optional<U> &&, T>::value &&
- !std::is_convertible<const optional<U> &, T>::value &&
- !std::is_convertible<const optional<U> &&, T>::value &&
- !std::is_assignable<T &, optional<U> &>::value &&
- !std::is_assignable<T &, optional<U> &&>::value &&
- !std::is_assignable<T &, const optional<U> &>::value &&
- !std::is_assignable<T &, const optional<U> &&>::value>;
-
-#ifdef _MSC_VER
-// TODO make a version which works with MSVC
-template <class T, class U = T> struct is_swappable : std::true_type {};
-
-template <class T, class U = T> struct is_nothrow_swappable : std::true_type {};
-#else
-// https://stackoverflow.com/questions/26744589/what-is-a-proper-way-to-implement-is-swappable-to-test-for-the-swappable-concept
-namespace swap_adl_tests {
-// if swap ADL finds this then it would call std::swap otherwise (same
-// signature)
-struct tag {};
-
-template <class T> tag swap(T &, T &);
-template <class T, std::size_t N> tag swap(T (&a)[N], T (&b)[N]);
-
-// helper functions to test if an unqualified swap is possible, and if it
-// becomes std::swap
-template <class, class> std::false_type can_swap(...) noexcept(false);
-template <class T, class U,
- class = decltype(swap(std::declval<T &>(), std::declval<U &>()))>
-std::true_type can_swap(int) noexcept(noexcept(swap(std::declval<T &>(),
- std::declval<U &>())));
-
-template <class, class> std::false_type uses_std(...);
-template <class T, class U>
-std::is_same<decltype(swap(std::declval<T &>(), std::declval<U &>())), tag>
-uses_std(int);
-
-template <class T>
-struct is_std_swap_noexcept
- : std::integral_constant<bool,
- std::is_nothrow_move_constructible<T>::value &&
- std::is_nothrow_move_assignable<T>::value> {};
-
-template <class T, std::size_t N>
-struct is_std_swap_noexcept<T[N]> : is_std_swap_noexcept<T> {};
-
-template <class T, class U>
-struct is_adl_swap_noexcept
- : std::integral_constant<bool, noexcept(can_swap<T, U>(0))> {};
-} // namespace swap_adl_tests
-
-template <class T, class U = T>
-struct is_swappable
- : std::integral_constant<
- bool,
- decltype(detail::swap_adl_tests::can_swap<T, U>(0))::value &&
- (!decltype(detail::swap_adl_tests::uses_std<T, U>(0))::value ||
- (std::is_move_assignable<T>::value &&
- std::is_move_constructible<T>::value))> {};
-
-template <class T, std::size_t N>
-struct is_swappable<T[N], T[N]>
- : std::integral_constant<
- bool,
- decltype(detail::swap_adl_tests::can_swap<T[N], T[N]>(0))::value &&
- (!decltype(
- detail::swap_adl_tests::uses_std<T[N], T[N]>(0))::value ||
- is_swappable<T, T>::value)> {};
-
-template <class T, class U = T>
-struct is_nothrow_swappable
- : std::integral_constant<
- bool,
- is_swappable<T, U>::value &&
- ((decltype(detail::swap_adl_tests::uses_std<T, U>(0))::value
- &&detail::swap_adl_tests::is_std_swap_noexcept<T>::value) ||
- (!decltype(detail::swap_adl_tests::uses_std<T, U>(0))::value &&
- detail::swap_adl_tests::is_adl_swap_noexcept<T,
- U>::value))> {
-};
-#endif
-
-// The storage base manages the actual storage, and correctly propagates
-// trivial destruction from T. This case is for when T is not trivially
-// destructible.
-template <class T, bool = ::std::is_trivially_destructible<T>::value>
-struct optional_storage_base {
- TL_OPTIONAL_11_CONSTEXPR optional_storage_base() noexcept
- : m_dummy(), m_has_value(false) {}
-
- template <class... U>
- TL_OPTIONAL_11_CONSTEXPR optional_storage_base(in_place_t, U &&... u)
- : m_value(std::forward<U>(u)...), m_has_value(true) {}
-
- ~optional_storage_base() {
- if (m_has_value) {
- m_value.~T();
- m_has_value = false;
- }
- }
-
- struct dummy {};
- union {
- dummy m_dummy;
- T m_value;
- };
-
- bool m_has_value;
-};
-
-// This case is for when T is trivially destructible.
-template <class T> struct optional_storage_base<T, true> {
- TL_OPTIONAL_11_CONSTEXPR optional_storage_base() noexcept
- : m_dummy(), m_has_value(false) {}
-
- template <class... U>
- TL_OPTIONAL_11_CONSTEXPR optional_storage_base(in_place_t, U &&... u)
- : m_value(std::forward<U>(u)...), m_has_value(true) {}
-
- // No destructor, so this class is trivially destructible
-
- struct dummy {};
- union {
- dummy m_dummy;
- T m_value;
- };
-
- bool m_has_value = false;
-};
-
-// This base class provides some handy member functions which can be used in
-// further derived classes
-template <class T> struct optional_operations_base : optional_storage_base<T> {
- using optional_storage_base<T>::optional_storage_base;
-
- void hard_reset() noexcept {
- get().~T();
- this->m_has_value = false;
- }
-
- template <class... Args> void construct(Args &&... args) noexcept {
- new (std::addressof(this->m_value)) T(std::forward<Args>(args)...);
- this->m_has_value = true;
- }
-
- template <class Opt> void assign(Opt &&rhs) {
- if (this->has_value()) {
- if (rhs.has_value()) {
- this->m_value = std::forward<Opt>(rhs).get();
- } else {
- this->m_value.~T();
- this->m_has_value = false;
- }
- }
-
- else if (rhs.has_value()) {
- construct(std::forward<Opt>(rhs).get());
- }
- }
-
- bool has_value() const { return this->m_has_value; }
-
- TL_OPTIONAL_11_CONSTEXPR T &get() & { return this->m_value; }
- TL_OPTIONAL_11_CONSTEXPR const T &get() const & { return this->m_value; }
- TL_OPTIONAL_11_CONSTEXPR T &&get() && { return std::move(this->m_value); }
-#ifndef TL_OPTIONAL_NO_CONSTRR
- constexpr const T &&get() const && { return std::move(this->m_value); }
-#endif
-};
-
-// This class manages conditionally having a trivial copy constructor
-// This specialization is for when T is trivially copy constructible
-template <class T, bool = TL_OPTIONAL_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(T)>
-struct optional_copy_base : optional_operations_base<T> {
- using optional_operations_base<T>::optional_operations_base;
-};
-
-// This specialization is for when T is not trivially copy constructible
-template <class T>
-struct optional_copy_base<T, false> : optional_operations_base<T> {
- using optional_operations_base<T>::optional_operations_base;
-
- optional_copy_base() = default;
- optional_copy_base(const optional_copy_base &rhs) {
- if (rhs.has_value()) {
- this->construct(rhs.get());
- } else {
- this->m_has_value = false;
- }
- }
-
- optional_copy_base(optional_copy_base &&rhs) = default;
- optional_copy_base &operator=(const optional_copy_base &rhs) = default;
- optional_copy_base &operator=(optional_copy_base &&rhs) = default;
-};
-
-// This class manages conditionally having a trivial move constructor
-// Unfortunately there's no way to achieve this in GCC < 5 AFAIK, since it
-// doesn't implement an analogue to std::is_trivially_move_constructible. We
-// have to make do with a non-trivial move constructor even if T is trivially
-// move constructible
-#ifndef TL_OPTIONAL_GCC49
-template <class T, bool = std::is_trivially_move_constructible<T>::value>
-struct optional_move_base : optional_copy_base<T> {
- using optional_copy_base<T>::optional_copy_base;
-};
-#else
-template <class T, bool = false> struct optional_move_base;
-#endif
-template <class T> struct optional_move_base<T, false> : optional_copy_base<T> {
- using optional_copy_base<T>::optional_copy_base;
-
- optional_move_base() = default;
- optional_move_base(const optional_move_base &rhs) = default;
-
- optional_move_base(optional_move_base &&rhs) noexcept(
- std::is_nothrow_move_constructible<T>::value) {
- if (rhs.has_value()) {
- this->construct(std::move(rhs.get()));
- } else {
- this->m_has_value = false;
- }
- }
- optional_move_base &operator=(const optional_move_base &rhs) = default;
- optional_move_base &operator=(optional_move_base &&rhs) = default;
-};
-
-// This class manages conditionally having a trivial copy assignment operator
-template <class T, bool = TL_OPTIONAL_IS_TRIVIALLY_COPY_ASSIGNABLE(T) &&
- TL_OPTIONAL_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(T) &&
- TL_OPTIONAL_IS_TRIVIALLY_DESTRUCTIBLE(T)>
-struct optional_copy_assign_base : optional_move_base<T> {
- using optional_move_base<T>::optional_move_base;
-};
-
-template <class T>
-struct optional_copy_assign_base<T, false> : optional_move_base<T> {
- using optional_move_base<T>::optional_move_base;
-
- optional_copy_assign_base() = default;
- optional_copy_assign_base(const optional_copy_assign_base &rhs) = default;
-
- optional_copy_assign_base(optional_copy_assign_base &&rhs) = default;
- optional_copy_assign_base &operator=(const optional_copy_assign_base &rhs) {
- this->assign(rhs);
- return *this;
- }
- optional_copy_assign_base &
- operator=(optional_copy_assign_base &&rhs) = default;
-};
-
-// This class manages conditionally having a trivial move assignment operator
-// Unfortunately there's no way to achieve this in GCC < 5 AFAIK, since it
-// doesn't implement an analogue to std::is_trivially_move_assignable. We have
-// to make do with a non-trivial move assignment operator even if T is trivially
-// move assignable
-#ifndef TL_OPTIONAL_GCC49
-template <class T, bool = std::is_trivially_destructible<T>::value
- &&std::is_trivially_move_constructible<T>::value
- &&std::is_trivially_move_assignable<T>::value>
-struct optional_move_assign_base : optional_copy_assign_base<T> {
- using optional_copy_assign_base<T>::optional_copy_assign_base;
-};
-#else
-template <class T, bool = false> struct optional_move_assign_base;
-#endif
-
-template <class T>
-struct optional_move_assign_base<T, false> : optional_copy_assign_base<T> {
- using optional_copy_assign_base<T>::optional_copy_assign_base;
-
- optional_move_assign_base() = default;
- optional_move_assign_base(const optional_move_assign_base &rhs) = default;
-
- optional_move_assign_base(optional_move_assign_base &&rhs) = default;
-
- optional_move_assign_base &
- operator=(const optional_move_assign_base &rhs) = default;
-
- optional_move_assign_base &
- operator=(optional_move_assign_base &&rhs) noexcept(
- std::is_nothrow_move_constructible<T>::value
- &&std::is_nothrow_move_assignable<T>::value) {
- this->assign(std::move(rhs));
- return *this;
- }
-};
-
-// optional_delete_ctor_base will conditionally delete copy and move
-// constructors depending on whether T is copy/move constructible
-template <class T, bool EnableCopy = std::is_copy_constructible<T>::value,
- bool EnableMove = std::is_move_constructible<T>::value>
-struct optional_delete_ctor_base {
- optional_delete_ctor_base() = default;
- optional_delete_ctor_base(const optional_delete_ctor_base &) = default;
- optional_delete_ctor_base(optional_delete_ctor_base &&) noexcept = default;
- optional_delete_ctor_base &
- operator=(const optional_delete_ctor_base &) = default;
- optional_delete_ctor_base &
- operator=(optional_delete_ctor_base &&) noexcept = default;
-};
-
-template <class T> struct optional_delete_ctor_base<T, true, false> {
- optional_delete_ctor_base() = default;
- optional_delete_ctor_base(const optional_delete_ctor_base &) = default;
- optional_delete_ctor_base(optional_delete_ctor_base &&) noexcept = delete;
- optional_delete_ctor_base &
- operator=(const optional_delete_ctor_base &) = default;
- optional_delete_ctor_base &
- operator=(optional_delete_ctor_base &&) noexcept = default;
-};
-
-template <class T> struct optional_delete_ctor_base<T, false, true> {
- optional_delete_ctor_base() = default;
- optional_delete_ctor_base(const optional_delete_ctor_base &) = delete;
- optional_delete_ctor_base(optional_delete_ctor_base &&) noexcept = default;
- optional_delete_ctor_base &
- operator=(const optional_delete_ctor_base &) = default;
- optional_delete_ctor_base &
- operator=(optional_delete_ctor_base &&) noexcept = default;
-};
-
-template <class T> struct optional_delete_ctor_base<T, false, false> {
- optional_delete_ctor_base() = default;
- optional_delete_ctor_base(const optional_delete_ctor_base &) = delete;
- optional_delete_ctor_base(optional_delete_ctor_base &&) noexcept = delete;
- optional_delete_ctor_base &
- operator=(const optional_delete_ctor_base &) = default;
- optional_delete_ctor_base &
- operator=(optional_delete_ctor_base &&) noexcept = default;
-};
-
-// optional_delete_assign_base will conditionally delete copy and move
-// constructors depending on whether T is copy/move constructible + assignable
-template <class T,
- bool EnableCopy = (std::is_copy_constructible<T>::value &&
- std::is_copy_assignable<T>::value),
- bool EnableMove = (std::is_move_constructible<T>::value &&
- std::is_move_assignable<T>::value)>
-struct optional_delete_assign_base {
- optional_delete_assign_base() = default;
- optional_delete_assign_base(const optional_delete_assign_base &) = default;
- optional_delete_assign_base(optional_delete_assign_base &&) noexcept =
- default;
- optional_delete_assign_base &
- operator=(const optional_delete_assign_base &) = default;
- optional_delete_assign_base &
- operator=(optional_delete_assign_base &&) noexcept = default;
-};
-
-template <class T> struct optional_delete_assign_base<T, true, false> {
- optional_delete_assign_base() = default;
- optional_delete_assign_base(const optional_delete_assign_base &) = default;
- optional_delete_assign_base(optional_delete_assign_base &&) noexcept =
- default;
- optional_delete_assign_base &
- operator=(const optional_delete_assign_base &) = default;
- optional_delete_assign_base &
- operator=(optional_delete_assign_base &&) noexcept = delete;
-};
-
-template <class T> struct optional_delete_assign_base<T, false, true> {
- optional_delete_assign_base() = default;
- optional_delete_assign_base(const optional_delete_assign_base &) = default;
- optional_delete_assign_base(optional_delete_assign_base &&) noexcept =
- default;
- optional_delete_assign_base &
- operator=(const optional_delete_assign_base &) = delete;
- optional_delete_assign_base &
- operator=(optional_delete_assign_base &&) noexcept = default;
-};
-
-template <class T> struct optional_delete_assign_base<T, false, false> {
- optional_delete_assign_base() = default;
- optional_delete_assign_base(const optional_delete_assign_base &) = default;
- optional_delete_assign_base(optional_delete_assign_base &&) noexcept =
- default;
- optional_delete_assign_base &
- operator=(const optional_delete_assign_base &) = delete;
- optional_delete_assign_base &
- operator=(optional_delete_assign_base &&) noexcept = delete;
-};
-
-} // namespace detail
-
-/// \brief A tag type to represent an empty optional
-struct nullopt_t {
- struct do_not_use {};
- constexpr explicit nullopt_t(do_not_use, do_not_use) noexcept {}
-};
-/// \brief Represents an empty optional
-/// \synopsis static constexpr nullopt_t nullopt;
-///
-/// *Examples*:
-/// ```
-/// tl::optional<int> a = tl::nullopt;
-/// void foo (tl::optional<int>);
-/// foo(tl::nullopt); //pass an empty optional
-/// ```
-static constexpr nullopt_t nullopt{nullopt_t::do_not_use{},
- nullopt_t::do_not_use{}};
-
-class bad_optional_access : public std::exception {
-public:
- bad_optional_access() = default;
- const char *what() const noexcept { return "Optional has no value"; }
-};
-
-/// An optional object is an object that contains the storage for another
-/// object and manages the lifetime of this contained object, if any. The
-/// contained object may be initialized after the optional object has been
-/// initialized, and may be destroyed before the optional object has been
-/// destroyed. The initialization state of the contained object is tracked by
-/// the optional object.
-template <class T>
-class optional : private detail::optional_move_assign_base<T>,
- private detail::optional_delete_ctor_base<T>,
- private detail::optional_delete_assign_base<T> {
- using base = detail::optional_move_assign_base<T>;
-
- static_assert(!std::is_same<T, in_place_t>::value,
- "instantiation of optional with in_place_t is ill-formed");
- static_assert(!std::is_same<detail::decay_t<T>, nullopt_t>::value,
- "instantiation of optional with nullopt_t is ill-formed");
-
-public:
-// The different versions for C++14 and 11 are needed because deduced return
-// types are not SFINAE-safe. This provides better support for things like
-// generic lambdas. C.f.
-// http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2017/p0826r0.html
-#if defined(TL_OPTIONAL_CXX14) && !defined(TL_OPTIONAL_GCC49) && \
- !defined(TL_OPTIONAL_GCC54) && !defined(TL_OPTIONAL_GCC55)
- /// \group and_then
- /// Carries out some operation which returns an optional on the stored
- /// object if there is one. \requires `std::invoke(std::forward<F>(f),
- /// value())` returns a `std::optional<U>` for some `U`. \returns Let `U` be
- /// the result of `std::invoke(std::forward<F>(f), value())`. Returns a
- /// `std::optional<U>`. The return value is empty if `*this` is empty,
- /// otherwise the return value of `std::invoke(std::forward<F>(f), value())`
- /// is returned.
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) &;
- template <class F> TL_OPTIONAL_11_CONSTEXPR auto and_then(F &&f) & {
- using result = detail::invoke_result_t<F, T &>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : result(nullopt);
- }
-
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) &&;
- template <class F> TL_OPTIONAL_11_CONSTEXPR auto and_then(F &&f) && {
- using result = detail::invoke_result_t<F, T &&>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), std::move(**this))
- : result(nullopt);
- }
-
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) const &;
- template <class F> constexpr auto and_then(F &&f) const & {
- using result = detail::invoke_result_t<F, const T &>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : result(nullopt);
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) const &&;
- template <class F> constexpr auto and_then(F &&f) const && {
- using result = detail::invoke_result_t<F, const T &&>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), std::move(**this))
- : result(nullopt);
- }
-#endif
-#else
- /// \group and_then
- /// Carries out some operation which returns an optional on the stored
- /// object if there is one. \requires `std::invoke(std::forward<F>(f),
- /// value())` returns a `std::optional<U>` for some `U`.
- /// \returns Let `U` be the result of `std::invoke(std::forward<F>(f),
- /// value())`. Returns a `std::optional<U>`. The return value is empty if
- /// `*this` is empty, otherwise the return value of
- /// `std::invoke(std::forward<F>(f), value())` is returned.
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) &;
- template <class F>
- TL_OPTIONAL_11_CONSTEXPR detail::invoke_result_t<F, T &> and_then(F &&f) & {
- using result = detail::invoke_result_t<F, T &>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : result(nullopt);
- }
-
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) &&;
- template <class F>
- TL_OPTIONAL_11_CONSTEXPR detail::invoke_result_t<F, T &&> and_then(F &&f) && {
- using result = detail::invoke_result_t<F, T &&>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), std::move(**this))
- : result(nullopt);
- }
-
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) const &;
- template <class F>
- constexpr detail::invoke_result_t<F, const T &> and_then(F &&f) const & {
- using result = detail::invoke_result_t<F, const T &>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : result(nullopt);
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) const &&;
- template <class F>
- constexpr detail::invoke_result_t<F, const T &&> and_then(F &&f) const && {
- using result = detail::invoke_result_t<F, const T &&>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), std::move(**this))
- : result(nullopt);
- }
-#endif
-#endif
-
-#if defined(TL_OPTIONAL_CXX14) && !defined(TL_OPTIONAL_GCC49) && \
- !defined(TL_OPTIONAL_GCC54) && !defined(TL_OPTIONAL_GCC55)
- /// \brief Carries out some operation on the stored object if there is one.
- /// \returns Let `U` be the result of `std::invoke(std::forward<F>(f),
- /// value())`. Returns a `std::optional<U>`. The return value is empty if
- /// `*this` is empty, otherwise an `optional<U>` is constructed from the
- /// return value of `std::invoke(std::forward<F>(f), value())` and is
- /// returned.
- ///
- /// \group map
- /// \synopsis template <class F> constexpr auto map(F &&f) &;
- template <class F> TL_OPTIONAL_11_CONSTEXPR auto map(F &&f) & {
- return optional_map_impl(*this, std::forward<F>(f));
- }
-
- /// \group map
- /// \synopsis template <class F> constexpr auto map(F &&f) &&;
- template <class F> TL_OPTIONAL_11_CONSTEXPR auto map(F &&f) && {
- return optional_map_impl(std::move(*this), std::forward<F>(f));
- }
-
- /// \group map
- /// \synopsis template <class F> constexpr auto map(F &&f) const&;
- template <class F> constexpr auto map(F &&f) const & {
- return optional_map_impl(*this, std::forward<F>(f));
- }
-
- /// \group map
- /// \synopsis template <class F> constexpr auto map(F &&f) const&&;
- template <class F> constexpr auto map(F &&f) const && {
- return optional_map_impl(std::move(*this), std::forward<F>(f));
- }
-#else
- /// \brief Carries out some operation on the stored object if there is one.
- /// \returns Let `U` be the result of `std::invoke(std::forward<F>(f),
- /// value())`. Returns a `std::optional<U>`. The return value is empty if
- /// `*this` is empty, otherwise an `optional<U>` is constructed from the
- /// return value of `std::invoke(std::forward<F>(f), value())` and is
- /// returned.
- ///
- /// \group map
- /// \synopsis template <class F> auto map(F &&f) &;
- template <class F>
- TL_OPTIONAL_11_CONSTEXPR decltype(optional_map_impl(std::declval<optional &>(),
- std::declval<F &&>()))
- map(F &&f) & {
- return optional_map_impl(*this, std::forward<F>(f));
- }
-
- /// \group map
- /// \synopsis template <class F> auto map(F &&f) &&;
- template <class F>
- TL_OPTIONAL_11_CONSTEXPR decltype(optional_map_impl(std::declval<optional &&>(),
- std::declval<F &&>()))
- map(F &&f) && {
- return optional_map_impl(std::move(*this), std::forward<F>(f));
- }
-
- /// \group map
- /// \synopsis template <class F> auto map(F &&f) const&;
- template <class F>
- constexpr decltype(optional_map_impl(std::declval<const optional &>(),
- std::declval<F &&>()))
- map(F &&f) const & {
- return optional_map_impl(*this, std::forward<F>(f));
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group map
- /// \synopsis template <class F> auto map(F &&f) const&&;
- template <class F>
- constexpr decltype(optional_map_impl(std::declval<const optional &&>(),
- std::declval<F &&>()))
- map(F &&f) const && {
- return optional_map_impl(std::move(*this), std::forward<F>(f));
- }
-#endif
-#endif
-
- /// \brief Calls `f` if the optional is empty
- /// \requires `std::invoke_result_t<F>` must be void or convertible to
- /// `optional<T>`.
- /// \effects If `*this` has a value, returns `*this`.
- /// Otherwise, if `f` returns `void`, calls `std::forward<F>(f)` and returns
- /// `std::nullopt`. Otherwise, returns `std::forward<F>(f)()`.
- ///
- /// \group or_else
- /// \synopsis template <class F> optional<T> or_else (F &&f) &;
- template <class F, detail::enable_if_ret_void<F> * = nullptr>
- optional<T> TL_OPTIONAL_11_CONSTEXPR or_else(F &&f) & {
- if (has_value())
- return *this;
-
- std::forward<F>(f)();
- return nullopt;
- }
-
- /// \exclude
- template <class F, detail::disable_if_ret_void<F> * = nullptr>
- optional<T> TL_OPTIONAL_11_CONSTEXPR or_else(F &&f) & {
- return has_value() ? *this : std::forward<F>(f)();
- }
-
- /// \group or_else
- /// \synopsis template <class F> optional<T> or_else (F &&f) &&;
- template <class F, detail::enable_if_ret_void<F> * = nullptr>
- optional<T> or_else(F &&f) && {
- if (has_value())
- return std::move(*this);
-
- std::forward<F>(f)();
- return nullopt;
- }
-
- /// \exclude
- template <class F, detail::disable_if_ret_void<F> * = nullptr>
- optional<T> TL_OPTIONAL_11_CONSTEXPR or_else(F &&f) && {
- return has_value() ? std::move(*this) : std::forward<F>(f)();
- }
-
- /// \group or_else
- /// \synopsis template <class F> optional<T> or_else (F &&f) const &;
- template <class F, detail::enable_if_ret_void<F> * = nullptr>
- optional<T> or_else(F &&f) const & {
- if (has_value())
- return *this;
-
- std::forward<F>(f)();
- return nullopt;
- }
-
- /// \exclude
- template <class F, detail::disable_if_ret_void<F> * = nullptr>
- optional<T> TL_OPTIONAL_11_CONSTEXPR or_else(F &&f) const & {
- return has_value() ? *this : std::forward<F>(f)();
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \exclude
- template <class F, detail::enable_if_ret_void<F> * = nullptr>
- optional<T> or_else(F &&f) const && {
- if (has_value())
- return std::move(*this);
-
- std::forward<F>(f)();
- return nullopt;
- }
-
- /// \exclude
- template <class F, detail::disable_if_ret_void<F> * = nullptr>
- optional<T> or_else(F &&f) const && {
- return has_value() ? std::move(*this) : std::forward<F>(f)();
- }
-#endif
-
- /// \brief Maps the stored value with `f` if there is one, otherwise returns
- /// `u`.
- ///
- /// \details If there is a value stored, then `f` is called with `**this`
- /// and the value is returned. Otherwise `u` is returned.
- ///
- /// \group map_or
- template <class F, class U> U map_or(F &&f, U &&u) & {
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : std::forward<U>(u);
- }
-
- /// \group map_or
- template <class F, class U> U map_or(F &&f, U &&u) && {
- return has_value() ? detail::invoke(std::forward<F>(f), std::move(**this))
- : std::forward<U>(u);
- }
-
- /// \group map_or
- template <class F, class U> U map_or(F &&f, U &&u) const & {
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : std::forward<U>(u);
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group map_or
- template <class F, class U> U map_or(F &&f, U &&u) const && {
- return has_value() ? detail::invoke(std::forward<F>(f), std::move(**this))
- : std::forward<U>(u);
- }
-#endif
-
- /// \brief Maps the stored value with `f` if there is one, otherwise calls
- /// `u` and returns the result.
- ///
- /// \details If there is a value stored, then `f` is
- /// called with `**this` and the value is returned. Otherwise
- /// `std::forward<U>(u)()` is returned.
- ///
- /// \group map_or_else
- /// \synopsis template <class F, class U>\nauto map_or_else(F &&f, U &&u) &;
- template <class F, class U>
- detail::invoke_result_t<U> map_or_else(F &&f, U &&u) & {
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : std::forward<U>(u)();
- }
-
- /// \group map_or_else
- /// \synopsis template <class F, class U>\nauto map_or_else(F &&f, U &&u)
- /// &&;
- template <class F, class U>
- detail::invoke_result_t<U> map_or_else(F &&f, U &&u) && {
- return has_value() ? detail::invoke(std::forward<F>(f), std::move(**this))
- : std::forward<U>(u)();
- }
-
- /// \group map_or_else
- /// \synopsis template <class F, class U>\nauto map_or_else(F &&f, U &&u)
- /// const &;
- template <class F, class U>
- detail::invoke_result_t<U> map_or_else(F &&f, U &&u) const & {
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : std::forward<U>(u)();
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group map_or_else
- /// \synopsis template <class F, class U>\nauto map_or_else(F &&f, U &&u)
- /// const &&;
- template <class F, class U>
- detail::invoke_result_t<U> map_or_else(F &&f, U &&u) const && {
- return has_value() ? detail::invoke(std::forward<F>(f), std::move(**this))
- : std::forward<U>(u)();
- }
-#endif
-
- /// \returns `u` if `*this` has a value, otherwise an empty optional.
- template <class U>
- constexpr optional<typename std::decay<U>::type> conjunction(U &&u) const {
- using result = optional<detail::decay_t<U>>;
- return has_value() ? result{u} : result{nullopt};
- }
-
- /// \returns `rhs` if `*this` is empty, otherwise the current value.
- /// \group disjunction
- TL_OPTIONAL_11_CONSTEXPR optional disjunction(const optional &rhs) & {
- return has_value() ? *this : rhs;
- }
-
- /// \group disjunction
- constexpr optional disjunction(const optional &rhs) const & {
- return has_value() ? *this : rhs;
- }
-
- /// \group disjunction
- TL_OPTIONAL_11_CONSTEXPR optional disjunction(const optional &rhs) && {
- return has_value() ? std::move(*this) : rhs;
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group disjunction
- constexpr optional disjunction(const optional &rhs) const && {
- return has_value() ? std::move(*this) : rhs;
- }
-#endif
-
- /// \group disjunction
- TL_OPTIONAL_11_CONSTEXPR optional disjunction(optional &&rhs) & {
- return has_value() ? *this : std::move(rhs);
- }
-
- /// \group disjunction
- constexpr optional disjunction(optional &&rhs) const & {
- return has_value() ? *this : std::move(rhs);
- }
-
- /// \group disjunction
- TL_OPTIONAL_11_CONSTEXPR optional disjunction(optional &&rhs) && {
- return has_value() ? std::move(*this) : std::move(rhs);
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group disjunction
- constexpr optional disjunction(optional &&rhs) const && {
- return has_value() ? std::move(*this) : std::move(rhs);
- }
-#endif
-
- /// Takes the value out of the optional, leaving it empty
- /// \group take
- optional take() & {
- optional ret = *this;
- reset();
- return ret;
- }
-
- /// \group take
- optional take() const & {
- optional ret = *this;
- reset();
- return ret;
- }
-
- /// \group take
- optional take() && {
- optional ret = std::move(*this);
- reset();
- return ret;
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group take
- optional take() const && {
- optional ret = std::move(*this);
- reset();
- return ret;
- }
-#endif
-
- using value_type = T;
-
- /// Constructs an optional that does not contain a value.
- /// \group ctor_empty
- constexpr optional() noexcept = default;
-
- /// \group ctor_empty
- constexpr optional(nullopt_t) noexcept {}
-
- /// Copy constructor
- ///
- /// If `rhs` contains a value, the stored value is direct-initialized with
- /// it. Otherwise, the constructed optional is empty.
- TL_OPTIONAL_11_CONSTEXPR optional(const optional &rhs) = default;
-
- /// Move constructor
- ///
- /// If `rhs` contains a value, the stored value is direct-initialized with
- /// it. Otherwise, the constructed optional is empty.
- TL_OPTIONAL_11_CONSTEXPR optional(optional &&rhs) = default;
-
- /// Constructs the stored value in-place using the given arguments.
- /// \group in_place
- /// \synopsis template <class... Args> constexpr explicit optional(in_place_t, Args&&... args);
- template <class... Args>
- constexpr explicit optional(
- detail::enable_if_t<std::is_constructible<T, Args...>::value, in_place_t>,
- Args &&... args)
- : base(in_place, std::forward<Args>(args)...) {}
-
- /// \group in_place
- /// \synopsis template <class U, class... Args>\nconstexpr explicit optional(in_place_t, std::initializer_list<U>&, Args&&... args);
- template <class U, class... Args>
- TL_OPTIONAL_11_CONSTEXPR explicit optional(
- detail::enable_if_t<std::is_constructible<T, std::initializer_list<U> &,
- Args &&...>::value,
- in_place_t>,
- std::initializer_list<U> il, Args &&... args) {
- this->construct(il, std::forward<Args>(args)...);
- }
-
- /// Constructs the stored value with `u`.
- /// \synopsis template <class U=T> constexpr optional(U &&u);
- template <
- class U = T,
- detail::enable_if_t<std::is_convertible<U &&, T>::value> * = nullptr,
- detail::enable_forward_value<T, U> * = nullptr>
- constexpr optional(U &&u) : base(in_place, std::forward<U>(u)) {}
-
- /// \exclude
- template <
- class U = T,
- detail::enable_if_t<!std::is_convertible<U &&, T>::value> * = nullptr,
- detail::enable_forward_value<T, U> * = nullptr>
- constexpr explicit optional(U &&u) : base(in_place, std::forward<U>(u)) {}
-
- /// Converting copy constructor.
- /// \synopsis template <class U> optional(const optional<U> &rhs);
- template <
- class U, detail::enable_from_other<T, U, const U &> * = nullptr,
- detail::enable_if_t<std::is_convertible<const U &, T>::value> * = nullptr>
- optional(const optional<U> &rhs) {
- this->construct(*rhs);
- }
-
- /// \exclude
- template <class U, detail::enable_from_other<T, U, const U &> * = nullptr,
- detail::enable_if_t<!std::is_convertible<const U &, T>::value> * =
- nullptr>
- explicit optional(const optional<U> &rhs) {
- this->construct(*rhs);
- }
-
- /// Converting move constructor.
- /// \synopsis template <class U> optional(optional<U> &&rhs);
- template <
- class U, detail::enable_from_other<T, U, U &&> * = nullptr,
- detail::enable_if_t<std::is_convertible<U &&, T>::value> * = nullptr>
- optional(optional<U> &&rhs) {
- this->construct(std::move(*rhs));
- }
-
- /// \exclude
- template <
- class U, detail::enable_from_other<T, U, U &&> * = nullptr,
- detail::enable_if_t<!std::is_convertible<U &&, T>::value> * = nullptr>
- explicit optional(optional<U> &&rhs) {
- this->construct(std::move(*rhs));
- }
-
- /// Destroys the stored value if there is one.
- ~optional() = default;
-
- /// Assignment to empty.
- ///
- /// Destroys the current value if there is one.
- optional &operator=(nullopt_t) noexcept {
- if (has_value()) {
- this->m_value.~T();
- this->m_has_value = false;
- }
-
- return *this;
- }
-
- /// Copy assignment.
- ///
- /// Copies the value from `rhs` if there is one. Otherwise resets the stored
- /// value in `*this`.
- optional &operator=(const optional &rhs) = default;
-
- /// Move assignment.
- ///
- /// Moves the value from `rhs` if there is one. Otherwise resets the stored
- /// value in `*this`.
- optional &operator=(optional &&rhs) = default;
-
- /// Assigns the stored value from `u`, destroying the old value if there was
- /// one.
- /// \synopsis optional &operator=(U &&u);
- template <class U = T, detail::enable_assign_forward<T, U> * = nullptr>
- optional &operator=(U &&u) {
- if (has_value()) {
- this->m_value = std::forward<U>(u);
- } else {
- this->construct(std::forward<U>(u));
- }
-
- return *this;
- }
-
- /// Converting copy assignment operator.
- ///
- /// Copies the value from `rhs` if there is one. Otherwise resets the stored
- /// value in `*this`.
- /// \synopsis optional &operator=(const optional<U> & rhs);
- template <class U,
- detail::enable_assign_from_other<T, U, const U &> * = nullptr>
- optional &operator=(const optional<U> &rhs) {
- if (has_value()) {
- if (rhs.has_value()) {
- this->m_value = *rhs;
- } else {
- this->hard_reset();
- }
- }
-
- if (rhs.has_value()) {
- this->construct(*rhs);
- }
-
- return *this;
- }
-
- // TODO check exception guarantee
- /// Converting move assignment operator.
- ///
- /// Moves the value from `rhs` if there is one. Otherwise resets the stored
- /// value in `*this`.
- /// \synopsis optional &operator=(optional<U> && rhs);
- template <class U, detail::enable_assign_from_other<T, U, U> * = nullptr>
- optional &operator=(optional<U> &&rhs) {
- if (has_value()) {
- if (rhs.has_value()) {
- this->m_value = std::move(*rhs);
- } else {
- this->hard_reset();
- }
- }
-
- if (rhs.has_value()) {
- this->construct(std::move(*rhs));
- }
-
- return *this;
- }
-
- /// Constructs the value in-place, destroying the current one if there is
- /// one.
- /// \group emplace
- template <class... Args> T &emplace(Args &&... args) {
- static_assert(std::is_constructible<T, Args &&...>::value,
- "T must be constructible with Args");
-
- *this = nullopt;
- this->construct(std::forward<Args>(args)...);
- return value();
- }
-
- /// \group emplace
- /// \synopsis template <class U, class... Args>\nT& emplace(std::initializer_list<U> il, Args &&... args);
- template <class U, class... Args>
- detail::enable_if_t<
- std::is_constructible<T, std::initializer_list<U> &, Args &&...>::value,
- T &>
- emplace(std::initializer_list<U> il, Args &&... args) {
- *this = nullopt;
- this->construct(il, std::forward<Args>(args)...);
- return value();
- }
-
- /// Swaps this optional with the other.
- ///
- /// If neither optionals have a value, nothing happens.
- /// If both have a value, the values are swapped.
- /// If one has a value, it is moved to the other and the movee is left
- /// valueless.
- void
- swap(optional &rhs) noexcept(std::is_nothrow_move_constructible<T>::value
- &&detail::is_nothrow_swappable<T>::value) {
- if (has_value()) {
- if (rhs.has_value()) {
- using std::swap;
- swap(**this, *rhs);
- } else {
- new (std::addressof(rhs.m_value)) T(std::move(this->m_value));
- this->m_value.T::~T();
- }
- } else if (rhs.has_value()) {
- new (std::addressof(this->m_value)) T(std::move(rhs.m_value));
- rhs.m_value.T::~T();
- }
- }
-
- /// \returns a pointer to the stored value
- /// \requires a value is stored
- /// \group pointer
- /// \synopsis constexpr const T *operator->() const;
- constexpr const T *operator->() const {
- return std::addressof(this->m_value);
- }
-
- /// \group pointer
- /// \synopsis constexpr T *operator->();
- TL_OPTIONAL_11_CONSTEXPR T *operator->() {
- return std::addressof(this->m_value);
- }
-
- /// \returns the stored value
- /// \requires a value is stored
- /// \group deref
- /// \synopsis constexpr T &operator*();
- TL_OPTIONAL_11_CONSTEXPR T &operator*() & { return this->m_value; }
-
- /// \group deref
- /// \synopsis constexpr const T &operator*() const;
- constexpr const T &operator*() const & { return this->m_value; }
-
- /// \exclude
- TL_OPTIONAL_11_CONSTEXPR T &&operator*() && {
- return std::move(this->m_value);
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \exclude
- constexpr const T &&operator*() const && { return std::move(this->m_value); }
-#endif
-
- /// \returns whether or not the optional has a value
- /// \group has_value
- constexpr bool has_value() const noexcept { return this->m_has_value; }
-
- /// \group has_value
- constexpr explicit operator bool() const noexcept {
- return this->m_has_value;
- }
-
- /// \returns the contained value if there is one, otherwise throws
- /// [bad_optional_access]
- /// \group value
- /// \synopsis constexpr T &value();
- TL_OPTIONAL_11_CONSTEXPR T &value() & {
- if (has_value())
- return this->m_value;
- throw bad_optional_access();
- }
- /// \group value
- /// \synopsis constexpr const T &value() const;
- TL_OPTIONAL_11_CONSTEXPR const T &value() const & {
- if (has_value())
- return this->m_value;
- throw bad_optional_access();
- }
- /// \exclude
- TL_OPTIONAL_11_CONSTEXPR T &&value() && {
- if (has_value())
- return std::move(this->m_value);
- throw bad_optional_access();
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \exclude
- TL_OPTIONAL_11_CONSTEXPR const T &&value() const && {
- if (has_value())
- return std::move(this->m_value);
- throw bad_optional_access();
- }
-#endif
-
- /// \returns the stored value if there is one, otherwise returns `u`
- /// \group value_or
- template <class U> constexpr T value_or(U &&u) const & {
- static_assert(std::is_copy_constructible<T>::value &&
- std::is_convertible<U &&, T>::value,
- "T must be copy constructible and convertible from U");
- return has_value() ? **this : static_cast<T>(std::forward<U>(u));
- }
-
- /// \group value_or
- template <class U> TL_OPTIONAL_11_CONSTEXPR T value_or(U &&u) && {
- static_assert(std::is_move_constructible<T>::value &&
- std::is_convertible<U &&, T>::value,
- "T must be move constructible and convertible from U");
- return has_value() ? **this : static_cast<T>(std::forward<U>(u));
- }
-
- /// Destroys the stored value if one exists, making the optional empty
- void reset() noexcept {
- if (has_value()) {
- this->m_value.~T();
- this->m_has_value = false;
- }
- }
-}; // namespace tl
-
-/// \group relop
-/// \brief Compares two optional objects
-/// \details If both optionals contain a value, they are compared with `T`s
-/// relational operators. Otherwise `lhs` and `rhs` are equal only if they are
-/// both empty, and `lhs` is less than `rhs` only if `rhs` is empty and `lhs`
-/// is not.
-template <class T, class U>
-inline constexpr bool operator==(const optional<T> &lhs,
- const optional<U> &rhs) {
- return lhs.has_value() == rhs.has_value() &&
- (!lhs.has_value() || *lhs == *rhs);
-}
-/// \group relop
-template <class T, class U>
-inline constexpr bool operator!=(const optional<T> &lhs,
- const optional<U> &rhs) {
- return lhs.has_value() != rhs.has_value() ||
- (lhs.has_value() && *lhs != *rhs);
-}
-/// \group relop
-template <class T, class U>
-inline constexpr bool operator<(const optional<T> &lhs,
- const optional<U> &rhs) {
- return rhs.has_value() && (!lhs.has_value() || *lhs < *rhs);
-}
-/// \group relop
-template <class T, class U>
-inline constexpr bool operator>(const optional<T> &lhs,
- const optional<U> &rhs) {
- return lhs.has_value() && (!rhs.has_value() || *lhs > *rhs);
-}
-/// \group relop
-template <class T, class U>
-inline constexpr bool operator<=(const optional<T> &lhs,
- const optional<U> &rhs) {
- return !lhs.has_value() || (rhs.has_value() && *lhs <= *rhs);
-}
-/// \group relop
-template <class T, class U>
-inline constexpr bool operator>=(const optional<T> &lhs,
- const optional<U> &rhs) {
- return !rhs.has_value() || (lhs.has_value() && *lhs >= *rhs);
-}
-
-/// \group relop_nullopt
-/// \brief Compares an optional to a `nullopt`
-/// \details Equivalent to comparing the optional to an empty optional
-template <class T>
-inline constexpr bool operator==(const optional<T> &lhs, nullopt_t) noexcept {
- return !lhs.has_value();
-}
-/// \group relop_nullopt
-template <class T>
-inline constexpr bool operator==(nullopt_t, const optional<T> &rhs) noexcept {
- return !rhs.has_value();
-}
-/// \group relop_nullopt
-template <class T>
-inline constexpr bool operator!=(const optional<T> &lhs, nullopt_t) noexcept {
- return lhs.has_value();
-}
-/// \group relop_nullopt
-template <class T>
-inline constexpr bool operator!=(nullopt_t, const optional<T> &rhs) noexcept {
- return rhs.has_value();
-}
-/// \group relop_nullopt
-template <class T>
-inline constexpr bool operator<(const optional<T> &, nullopt_t) noexcept {
- return false;
-}
-/// \group relop_nullopt
-template <class T>
-inline constexpr bool operator<(nullopt_t, const optional<T> &rhs) noexcept {
- return rhs.has_value();
-}
-/// \group relop_nullopt
-template <class T>
-inline constexpr bool operator<=(const optional<T> &lhs, nullopt_t) noexcept {
- return !lhs.has_value();
-}
-/// \group relop_nullopt
-template <class T>
-inline constexpr bool operator<=(nullopt_t, const optional<T> &) noexcept {
- return true;
-}
-/// \group relop_nullopt
-template <class T>
-inline constexpr bool operator>(const optional<T> &lhs, nullopt_t) noexcept {
- return lhs.has_value();
-}
-/// \group relop_nullopt
-template <class T>
-inline constexpr bool operator>(nullopt_t, const optional<T> &) noexcept {
- return false;
-}
-/// \group relop_nullopt
-template <class T>
-inline constexpr bool operator>=(const optional<T> &, nullopt_t) noexcept {
- return true;
-}
-/// \group relop_nullopt
-template <class T>
-inline constexpr bool operator>=(nullopt_t, const optional<T> &rhs) noexcept {
- return !rhs.has_value();
-}
-
-/// \group relop_t
-/// \brief Compares the optional with a value.
-/// \details If the optional has a value, it is compared with the other value
-/// using `T`s relational operators. Otherwise, the optional is considered
-/// less than the value.
-template <class T, class U>
-inline constexpr bool operator==(const optional<T> &lhs, const U &rhs) {
- return lhs.has_value() ? *lhs == rhs : false;
-}
-/// \group relop_t
-template <class T, class U>
-inline constexpr bool operator==(const U &lhs, const optional<T> &rhs) {
- return rhs.has_value() ? lhs == *rhs : false;
-}
-/// \group relop_t
-template <class T, class U>
-inline constexpr bool operator!=(const optional<T> &lhs, const U &rhs) {
- return lhs.has_value() ? *lhs != rhs : true;
-}
-/// \group relop_t
-template <class T, class U>
-inline constexpr bool operator!=(const U &lhs, const optional<T> &rhs) {
- return rhs.has_value() ? lhs != *rhs : true;
-}
-/// \group relop_t
-template <class T, class U>
-inline constexpr bool operator<(const optional<T> &lhs, const U &rhs) {
- return lhs.has_value() ? *lhs < rhs : true;
-}
-/// \group relop_t
-template <class T, class U>
-inline constexpr bool operator<(const U &lhs, const optional<T> &rhs) {
- return rhs.has_value() ? lhs < *rhs : false;
-}
-/// \group relop_t
-template <class T, class U>
-inline constexpr bool operator<=(const optional<T> &lhs, const U &rhs) {
- return lhs.has_value() ? *lhs <= rhs : true;
-}
-/// \group relop_t
-template <class T, class U>
-inline constexpr bool operator<=(const U &lhs, const optional<T> &rhs) {
- return rhs.has_value() ? lhs <= *rhs : false;
-}
-/// \group relop_t
-template <class T, class U>
-inline constexpr bool operator>(const optional<T> &lhs, const U &rhs) {
- return lhs.has_value() ? *lhs > rhs : false;
-}
-/// \group relop_t
-template <class T, class U>
-inline constexpr bool operator>(const U &lhs, const optional<T> &rhs) {
- return rhs.has_value() ? lhs > *rhs : true;
-}
-/// \group relop_t
-template <class T, class U>
-inline constexpr bool operator>=(const optional<T> &lhs, const U &rhs) {
- return lhs.has_value() ? *lhs >= rhs : false;
-}
-/// \group relop_t
-template <class T, class U>
-inline constexpr bool operator>=(const U &lhs, const optional<T> &rhs) {
- return rhs.has_value() ? lhs >= *rhs : true;
-}
-
-/// \synopsis template <class T>\nvoid swap(optional<T> &lhs, optional<T> &rhs);
-template <class T,
- detail::enable_if_t<std::is_move_constructible<T>::value> * = nullptr,
- detail::enable_if_t<detail::is_swappable<T>::value> * = nullptr>
-void swap(optional<T> &lhs,
- optional<T> &rhs) noexcept(noexcept(lhs.swap(rhs))) {
- return lhs.swap(rhs);
-}
-
-namespace detail {
-struct i_am_secret {};
-} // namespace detail
-
-template <class T = detail::i_am_secret, class U,
- class Ret =
- detail::conditional_t<std::is_same<T, detail::i_am_secret>::value,
- detail::decay_t<U>, T>>
-inline constexpr optional<Ret> make_optional(U &&v) {
- return optional<Ret>(std::forward<U>(v));
-}
-
-template <class T, class... Args>
-inline constexpr optional<T> make_optional(Args &&... args) {
- return optional<T>(in_place, std::forward<Args>(args)...);
-}
-template <class T, class U, class... Args>
-inline constexpr optional<T> make_optional(std::initializer_list<U> il,
- Args &&... args) {
- return optional<T>(in_place, il, std::forward<Args>(args)...);
-}
-
-#if __cplusplus >= 201703L
-template <class T> optional(T)->optional<T>;
-#endif
-
-/// \exclude
-namespace detail {
-#ifdef TL_OPTIONAL_CXX14
-template <class Opt, class F,
- class Ret = decltype(detail::invoke(std::declval<F>(),
- *std::declval<Opt>())),
- detail::enable_if_t<!std::is_void<Ret>::value> * = nullptr>
-constexpr auto optional_map_impl(Opt &&opt, F &&f) {
- return opt.has_value()
- ? detail::invoke(std::forward<F>(f), *std::forward<Opt>(opt))
- : optional<Ret>(nullopt);
-}
-
-template <class Opt, class F,
- class Ret = decltype(detail::invoke(std::declval<F>(),
- *std::declval<Opt>())),
- detail::enable_if_t<std::is_void<Ret>::value> * = nullptr>
-auto optional_map_impl(Opt &&opt, F &&f) {
- if (opt.has_value()) {
- detail::invoke(std::forward<F>(f), *std::forward<Opt>(opt));
- return make_optional(monostate{});
- }
-
- return optional<monostate>(nullopt);
-}
-#else
-template <class Opt, class F,
- class Ret = decltype(detail::invoke(std::declval<F>(),
- *std::declval<Opt>())),
- detail::enable_if_t<!std::is_void<Ret>::value> * = nullptr>
-
-constexpr auto optional_map_impl(Opt &&opt, F &&f) -> optional<Ret> {
- return opt.has_value()
- ? detail::invoke(std::forward<F>(f), *std::forward<Opt>(opt))
- : optional<Ret>(nullopt);
-}
-
-template <class Opt, class F,
- class Ret = decltype(detail::invoke(std::declval<F>(),
- *std::declval<Opt>())),
- detail::enable_if_t<std::is_void<Ret>::value> * = nullptr>
-
-auto optional_map_impl(Opt &&opt, F &&f) -> optional<monostate> {
- if (opt.has_value()) {
- detail::invoke(std::forward<F>(f), *std::forward<Opt>(opt));
- return monostate{};
- }
-
- return nullopt;
-}
-#endif
-} // namespace detail
-
-/// Specialization for when `T` is a reference. `optional<T&>` acts similarly
-/// to a `T*`, but provides more operations and shows intent more clearly.
-///
-/// *Examples*:
-///
-/// ```
-/// int i = 42;
-/// tl::optional<int&> o = i;
-/// *o == 42; //true
-/// i = 12;
-/// *o = 12; //true
-/// &*o == &i; //true
-/// ```
-///
-/// Assignment has rebind semantics rather than assign-through semantics:
-///
-/// ```
-/// int j = 8;
-/// o = j;
-///
-/// &*o == &j; //true
-/// ```
-template <class T> class optional<T &> {
-public:
-// The different versions for C++14 and 11 are needed because deduced return
-// types are not SFINAE-safe. This provides better support for things like
-// generic lambdas. C.f.
-// http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2017/p0826r0.html
-#if defined(TL_OPTIONAL_CXX14) && !defined(TL_OPTIONAL_GCC49) && \
- !defined(TL_OPTIONAL_GCC54) && !defined(TL_OPTIONAL_GCC55)
- /// \group and_then
- /// Carries out some operation which returns an optional on the stored
- /// object if there is one. \requires `std::invoke(std::forward<F>(f),
- /// value())` returns a `std::optional<U>` for some `U`. \returns Let `U` be
- /// the result of `std::invoke(std::forward<F>(f), value())`. Returns a
- /// `std::optional<U>`. The return value is empty if `*this` is empty,
- /// otherwise the return value of `std::invoke(std::forward<F>(f), value())`
- /// is returned.
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) &;
- template <class F> TL_OPTIONAL_11_CONSTEXPR auto and_then(F &&f) & {
- using result = detail::invoke_result_t<F, T &>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : result(nullopt);
- }
-
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) &&;
- template <class F> TL_OPTIONAL_11_CONSTEXPR auto and_then(F &&f) && {
- using result = detail::invoke_result_t<F, T &>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : result(nullopt);
- }
-
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) const &;
- template <class F> constexpr auto and_then(F &&f) const & {
- using result = detail::invoke_result_t<F, const T &>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : result(nullopt);
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) const &&;
- template <class F> constexpr auto and_then(F &&f) const && {
- using result = detail::invoke_result_t<F, const T &>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : result(nullopt);
- }
-#endif
-#else
- /// \group and_then
- /// Carries out some operation which returns an optional on the stored
- /// object if there is one. \requires `std::invoke(std::forward<F>(f),
- /// value())` returns a `std::optional<U>` for some `U`. \returns Let `U` be
- /// the result of `std::invoke(std::forward<F>(f), value())`. Returns a
- /// `std::optional<U>`. The return value is empty if `*this` is empty,
- /// otherwise the return value of `std::invoke(std::forward<F>(f), value())`
- /// is returned.
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) &;
- template <class F>
- TL_OPTIONAL_11_CONSTEXPR detail::invoke_result_t<F, T &> and_then(F &&f) & {
- using result = detail::invoke_result_t<F, T &>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : result(nullopt);
- }
-
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) &&;
- template <class F>
- TL_OPTIONAL_11_CONSTEXPR detail::invoke_result_t<F, T &> and_then(F &&f) && {
- using result = detail::invoke_result_t<F, T &>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : result(nullopt);
- }
-
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) const &;
- template <class F>
- constexpr detail::invoke_result_t<F, const T &> and_then(F &&f) const & {
- using result = detail::invoke_result_t<F, const T &>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : result(nullopt);
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group and_then
- /// \synopsis template <class F>\nconstexpr auto and_then(F &&f) const &&;
- template <class F>
- constexpr detail::invoke_result_t<F, const T &> and_then(F &&f) const && {
- using result = detail::invoke_result_t<F, const T &>;
- static_assert(detail::is_optional<result>::value,
- "F must return an optional");
-
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : result(nullopt);
- }
-#endif
-#endif
-
-#if defined(TL_OPTIONAL_CXX14) && !defined(TL_OPTIONAL_GCC49) && \
- !defined(TL_OPTIONAL_GCC54) && !defined(TL_OPTIONAL_GCC55)
- /// \brief Carries out some operation on the stored object if there is one.
- /// \returns Let `U` be the result of `std::invoke(std::forward<F>(f),
- /// value())`. Returns a `std::optional<U>`. The return value is empty if
- /// `*this` is empty, otherwise an `optional<U>` is constructed from the
- /// return value of `std::invoke(std::forward<F>(f), value())` and is
- /// returned.
- ///
- /// \group map
- /// \synopsis template <class F> constexpr auto map(F &&f) &;
- template <class F> TL_OPTIONAL_11_CONSTEXPR auto map(F &&f) & {
- return detail::optional_map_impl(*this, std::forward<F>(f));
- }
-
- /// \group map
- /// \synopsis template <class F> constexpr auto map(F &&f) &&;
- template <class F> TL_OPTIONAL_11_CONSTEXPR auto map(F &&f) && {
- return detail::optional_map_impl(std::move(*this), std::forward<F>(f));
- }
-
- /// \group map
- /// \synopsis template <class F> constexpr auto map(F &&f) const&;
- template <class F> constexpr auto map(F &&f) const & {
- return detail::optional_map_impl(*this, std::forward<F>(f));
- }
-
- /// \group map
- /// \synopsis template <class F> constexpr auto map(F &&f) const&&;
- template <class F> constexpr auto map(F &&f) const && {
- return detail::optional_map_impl(std::move(*this), std::forward<F>(f));
- }
-#else
- /// \brief Carries out some operation on the stored object if there is one.
- /// \returns Let `U` be the result of `std::invoke(std::forward<F>(f),
- /// value())`. Returns a `std::optional<U>`. The return value is empty if
- /// `*this` is empty, otherwise an `optional<U>` is constructed from the
- /// return value of `std::invoke(std::forward<F>(f), value())` and is
- /// returned.
- ///
- /// \group map
- /// \synopsis template <class F> auto map(F &&f) &;
- template <class F>
- TL_OPTIONAL_11_CONSTEXPR decltype(detail::optional_map_impl(std::declval<optional &>(),
- std::declval<F &&>()))
- map(F &&f) & {
- return detail::optional_map_impl(*this, std::forward<F>(f));
- }
-
- /// \group map
- /// \synopsis template <class F> auto map(F &&f) &&;
- template <class F>
- TL_OPTIONAL_11_CONSTEXPR decltype(detail::optional_map_impl(std::declval<optional &&>(),
- std::declval<F &&>()))
- map(F &&f) && {
- return detail::optional_map_impl(std::move(*this), std::forward<F>(f));
- }
-
- /// \group map
- /// \synopsis template <class F> auto map(F &&f) const&;
- template <class F>
- constexpr decltype(detail::optional_map_impl(std::declval<const optional &>(),
- std::declval<F &&>()))
- map(F &&f) const & {
- return detail::optional_map_impl(*this, std::forward<F>(f));
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group map
- /// \synopsis template <class F> auto map(F &&f) const&&;
- template <class F>
- constexpr decltype(detail::optional_map_impl(std::declval<const optional &&>(),
- std::declval<F &&>()))
- map(F &&f) const && {
- return detail::optional_map_impl(std::move(*this), std::forward<F>(f));
- }
-#endif
-#endif
-
- /// \brief Calls `f` if the optional is empty
- /// \requires `std::invoke_result_t<F>` must be void or convertible to
- /// `optional<T>`. \effects If `*this` has a value, returns `*this`.
- /// Otherwise, if `f` returns `void`, calls `std::forward<F>(f)` and returns
- /// `std::nullopt`. Otherwise, returns `std::forward<F>(f)()`.
- ///
- /// \group or_else
- /// \synopsis template <class F> optional<T> or_else (F &&f) &;
- template <class F, detail::enable_if_ret_void<F> * = nullptr>
- optional<T> TL_OPTIONAL_11_CONSTEXPR or_else(F &&f) & {
- if (has_value())
- return *this;
-
- std::forward<F>(f)();
- return nullopt;
- }
-
- /// \exclude
- template <class F, detail::disable_if_ret_void<F> * = nullptr>
- optional<T> TL_OPTIONAL_11_CONSTEXPR or_else(F &&f) & {
- return has_value() ? *this : std::forward<F>(f)();
- }
-
- /// \group or_else
- /// \synopsis template <class F> optional<T> or_else (F &&f) &&;
- template <class F, detail::enable_if_ret_void<F> * = nullptr>
- optional<T> or_else(F &&f) && {
- if (has_value())
- return std::move(*this);
-
- std::forward<F>(f)();
- return nullopt;
- }
-
- /// \exclude
- template <class F, detail::disable_if_ret_void<F> * = nullptr>
- optional<T> TL_OPTIONAL_11_CONSTEXPR or_else(F &&f) && {
- return has_value() ? std::move(*this) : std::forward<F>(f)();
- }
-
- /// \group or_else
- /// \synopsis template <class F> optional<T> or_else (F &&f) const &;
- template <class F, detail::enable_if_ret_void<F> * = nullptr>
- optional<T> or_else(F &&f) const & {
- if (has_value())
- return *this;
-
- std::forward<F>(f)();
- return nullopt;
- }
-
- /// \exclude
- template <class F, detail::disable_if_ret_void<F> * = nullptr>
- optional<T> TL_OPTIONAL_11_CONSTEXPR or_else(F &&f) const & {
- return has_value() ? *this : std::forward<F>(f)();
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \exclude
- template <class F, detail::enable_if_ret_void<F> * = nullptr>
- optional<T> or_else(F &&f) const && {
- if (has_value())
- return std::move(*this);
-
- std::forward<F>(f)();
- return nullopt;
- }
-
- /// \exclude
- template <class F, detail::disable_if_ret_void<F> * = nullptr>
- optional<T> or_else(F &&f) const && {
- return has_value() ? std::move(*this) : std::forward<F>(f)();
- }
-#endif
-
- /// \brief Maps the stored value with `f` if there is one, otherwise returns
- /// `u`.
- ///
- /// \details If there is a value stored, then `f` is called with `**this`
- /// and the value is returned. Otherwise `u` is returned.
- ///
- /// \group map_or
- template <class F, class U> U map_or(F &&f, U &&u) & {
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : std::forward<U>(u);
- }
-
- /// \group map_or
- template <class F, class U> U map_or(F &&f, U &&u) && {
- return has_value() ? detail::invoke(std::forward<F>(f), std::move(**this))
- : std::forward<U>(u);
- }
-
- /// \group map_or
- template <class F, class U> U map_or(F &&f, U &&u) const & {
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : std::forward<U>(u);
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group map_or
- template <class F, class U> U map_or(F &&f, U &&u) const && {
- return has_value() ? detail::invoke(std::forward<F>(f), std::move(**this))
- : std::forward<U>(u);
- }
-#endif
-
- /// \brief Maps the stored value with `f` if there is one, otherwise calls
- /// `u` and returns the result.
- ///
- /// \details If there is a value stored, then `f` is
- /// called with `**this` and the value is returned. Otherwise
- /// `std::forward<U>(u)()` is returned.
- ///
- /// \group map_or_else
- /// \synopsis template <class F, class U>\nauto map_or_else(F &&f, U &&u) &;
- template <class F, class U>
- detail::invoke_result_t<U> map_or_else(F &&f, U &&u) & {
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : std::forward<U>(u)();
- }
-
- /// \group map_or_else
- /// \synopsis template <class F, class U>\nauto map_or_else(F &&f, U &&u)
- /// &&;
- template <class F, class U>
- detail::invoke_result_t<U> map_or_else(F &&f, U &&u) && {
- return has_value() ? detail::invoke(std::forward<F>(f), std::move(**this))
- : std::forward<U>(u)();
- }
-
- /// \group map_or_else
- /// \synopsis template <class F, class U>\nauto map_or_else(F &&f, U &&u)
- /// const &;
- template <class F, class U>
- detail::invoke_result_t<U> map_or_else(F &&f, U &&u) const & {
- return has_value() ? detail::invoke(std::forward<F>(f), **this)
- : std::forward<U>(u)();
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group map_or_else
- /// \synopsis template <class F, class U>\nauto map_or_else(F &&f, U &&u)
- /// const &&;
- template <class F, class U>
- detail::invoke_result_t<U> map_or_else(F &&f, U &&u) const && {
- return has_value() ? detail::invoke(std::forward<F>(f), std::move(**this))
- : std::forward<U>(u)();
- }
-#endif
-
- /// \returns `u` if `*this` has a value, otherwise an empty optional.
- template <class U>
- constexpr optional<typename std::decay<U>::type> conjunction(U &&u) const {
- using result = optional<detail::decay_t<U>>;
- return has_value() ? result{u} : result{nullopt};
- }
-
- /// \returns `rhs` if `*this` is empty, otherwise the current value.
- /// \group disjunction
- TL_OPTIONAL_11_CONSTEXPR optional disjunction(const optional &rhs) & {
- return has_value() ? *this : rhs;
- }
-
- /// \group disjunction
- constexpr optional disjunction(const optional &rhs) const & {
- return has_value() ? *this : rhs;
- }
-
- /// \group disjunction
- TL_OPTIONAL_11_CONSTEXPR optional disjunction(const optional &rhs) && {
- return has_value() ? std::move(*this) : rhs;
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group disjunction
- constexpr optional disjunction(const optional &rhs) const && {
- return has_value() ? std::move(*this) : rhs;
- }
-#endif
-
- /// \group disjunction
- TL_OPTIONAL_11_CONSTEXPR optional disjunction(optional &&rhs) & {
- return has_value() ? *this : std::move(rhs);
- }
-
- /// \group disjunction
- constexpr optional disjunction(optional &&rhs) const & {
- return has_value() ? *this : std::move(rhs);
- }
-
- /// \group disjunction
- TL_OPTIONAL_11_CONSTEXPR optional disjunction(optional &&rhs) && {
- return has_value() ? std::move(*this) : std::move(rhs);
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group disjunction
- constexpr optional disjunction(optional &&rhs) const && {
- return has_value() ? std::move(*this) : std::move(rhs);
- }
-#endif
-
- /// Takes the value out of the optional, leaving it empty
- /// \group take
- optional take() & {
- optional ret = *this;
- reset();
- return ret;
- }
-
- /// \group take
- optional take() const & {
- optional ret = *this;
- reset();
- return ret;
- }
-
- /// \group take
- optional take() && {
- optional ret = std::move(*this);
- reset();
- return ret;
- }
-
-#ifndef TL_OPTIONAL_NO_CONSTRR
- /// \group take
- optional take() const && {
- optional ret = std::move(*this);
- reset();
- return ret;
- }
-#endif
-
- using value_type = T &;
-
- /// Constructs an optional that does not contain a value.
- /// \group ctor_empty
- constexpr optional() noexcept : m_value(nullptr) {}
-
- /// \group ctor_empty
- constexpr optional(nullopt_t) noexcept : m_value(nullptr) {}
-
- /// Copy constructor
- ///
- /// If `rhs` contains a value, the stored value is direct-initialized with
- /// it. Otherwise, the constructed optional is empty.
- TL_OPTIONAL_11_CONSTEXPR optional(const optional &rhs) noexcept = default;
-
- /// Move constructor
- ///
- /// If `rhs` contains a value, the stored value is direct-initialized with
- /// it. Otherwise, the constructed optional is empty.
- TL_OPTIONAL_11_CONSTEXPR optional(optional &&rhs) = default;
-
- /// Constructs the stored value with `u`.
- /// \synopsis template <class U=T> constexpr optional(U &&u);
- template <class U = T,
- detail::enable_if_t<!detail::is_optional<detail::decay_t<U>>::value>
- * = nullptr>
- constexpr optional(U &&u) : m_value(std::addressof(u)) {
- static_assert(std::is_lvalue_reference<U>::value, "U must be an lvalue");
- }
-
- /// \exclude
- template <class U>
- constexpr explicit optional(const optional<U> &rhs) : optional(*rhs) {}
-
- /// No-op
- ~optional() = default;
-
- /// Assignment to empty.
- ///
- /// Destroys the current value if there is one.
- optional &operator=(nullopt_t) noexcept {
- m_value = nullptr;
- return *this;
- }
-
- /// Copy assignment.
- ///
- /// Rebinds this optional to the referee of `rhs` if there is one. Otherwise
- /// resets the stored value in `*this`.
- optional &operator=(const optional &rhs) = default;
-
- /// Rebinds this optional to `u`.
- ///
- /// \requires `U` must be an lvalue reference.
- /// \synopsis optional &operator=(U &&u);
- template <class U = T,
- detail::enable_if_t<!detail::is_optional<detail::decay_t<U>>::value>
- * = nullptr>
- optional &operator=(U &&u) {
- static_assert(std::is_lvalue_reference<U>::value, "U must be an lvalue");
- m_value = std::addressof(u);
- return *this;
- }
-
- /// Converting copy assignment operator.
- ///
- /// Rebinds this optional to the referee of `rhs` if there is one. Otherwise
- /// resets the stored value in `*this`.
- template <class U> optional &operator=(const optional<U> &rhs) {
- m_value = std::addressof(rhs.value());
- return *this;
- }
-
- /// Constructs the value in-place, destroying the current one if there is
- /// one.
- ///
- /// \group emplace
- template <class... Args> T &emplace(Args &&... args) noexcept {
- static_assert(std::is_constructible<T, Args &&...>::value,
- "T must be constructible with Args");
-
- *this = nullopt;
- this->construct(std::forward<Args>(args)...);
- return value();
- }
-
- /// Swaps this optional with the other.
- ///
- /// If neither optionals have a value, nothing happens.
- /// If both have a value, the values are swapped.
- /// If one has a value, it is moved to the other and the movee is left
- /// valueless.
- void swap(optional &rhs) noexcept { std::swap(m_value, rhs.m_value); }
-
- /// \returns a pointer to the stored value
- /// \requires a value is stored
- /// \group pointer
- /// \synopsis constexpr const T *operator->() const;
- constexpr const T *operator->() const { return m_value; }
-
- /// \group pointer
- /// \synopsis constexpr T *operator->();
- TL_OPTIONAL_11_CONSTEXPR T *operator->() { return m_value; }
-
- /// \returns the stored value
- /// \requires a value is stored
- /// \group deref
- /// \synopsis constexpr T &operator*();
- TL_OPTIONAL_11_CONSTEXPR T &operator*() { return *m_value; }
-
- /// \group deref
- /// \synopsis constexpr const T &operator*() const;
- constexpr const T &operator*() const { return *m_value; }
-
- /// \returns whether or not the optional has a value
- /// \group has_value
- constexpr bool has_value() const noexcept { return m_value != nullptr; }
-
- /// \group has_value
- constexpr explicit operator bool() const noexcept {
- return m_value != nullptr;
- }
-
- /// \returns the contained value if there is one, otherwise throws
- /// [bad_optional_access]
- /// \group value
- /// synopsis constexpr T &value();
- TL_OPTIONAL_11_CONSTEXPR T &value() {
- if (has_value())
- return *m_value;
- throw bad_optional_access();
- }
- /// \group value
- /// \synopsis constexpr const T &value() const;
- TL_OPTIONAL_11_CONSTEXPR const T &value() const {
- if (has_value())
- return *m_value;
- throw bad_optional_access();
- }
-
- /// \returns the stored value if there is one, otherwise returns `u`
- /// \group value_or
- template <class U> constexpr T value_or(U &&u) const & {
- static_assert(std::is_copy_constructible<T>::value &&
- std::is_convertible<U &&, T>::value,
- "T must be copy constructible and convertible from U");
- return has_value() ? **this : static_cast<T>(std::forward<U>(u));
- }
-
- /// \group value_or
- template <class U> TL_OPTIONAL_11_CONSTEXPR T value_or(U &&u) && {
- static_assert(std::is_move_constructible<T>::value &&
- std::is_convertible<U &&, T>::value,
- "T must be move constructible and convertible from U");
- return has_value() ? **this : static_cast<T>(std::forward<U>(u));
- }
-
- /// Destroys the stored value if one exists, making the optional empty
- void reset() noexcept { m_value = nullptr; }
-
-private:
- T *m_value;
-}; // namespace tl
-
-
-
-} // namespace tl
-
-namespace std {
-// TODO SFINAE
-template <class T> struct hash<tl::optional<T>> {
- ::std::size_t operator()(const tl::optional<T> &o) const {
- if (!o.has_value())
- return 0;
-
- return std::hash<tl::detail::remove_const_t<T>>()(*o);
- }
-};
-} // namespace std
-
-#endif
diff --git a/third_party/protobuf/src/google/protobuf/extension_set.cc b/third_party/protobuf/src/google/protobuf/extension_set.cc
index cb205c4..2b8da34 100644
--- a/third_party/protobuf/src/google/protobuf/extension_set.cc
+++ b/third_party/protobuf/src/google/protobuf/extension_set.cc
@@ -138,7 +138,7 @@
// http://www.open-std.org/jtc1/sc22/wg21/docs/cwg_defects.html#195
// Also note: Some compilers do not allow function pointers to be "const".
// Which makes sense, I suppose, because it's meaningless.
- return ((EnumValidityFunc*)arg)(number);
+ return ((EnumValidityFunc*)const_cast<void *>(arg))(number);
}
void ExtensionSet::RegisterEnumExtension(const MessageLite* containing_type,
diff --git a/tools/cpp/BUILD b/tools/cpp/BUILD
index c2c285d..c0d0b38 100644
--- a/tools/cpp/BUILD
+++ b/tools/cpp/BUILD
@@ -54,56 +54,56 @@
)
filegroup(
- name = "clang_3p6_all_files",
+ name = "clang_6p0_all_files",
srcs = [
":flags_compiler_inputs",
- "//tools/cpp/clang_3p6:as",
- "//tools/cpp/clang_3p6:tool-wrappers",
- "@clang_3p6_repo//:compiler_pieces",
+ "//tools/cpp/clang_6p0:as",
+ "//tools/cpp/clang_6p0:tool-wrappers",
+ "@clang_6p0_repo//:compiler_pieces",
],
)
filegroup(
- name = "clang_3p6_linker_files",
+ name = "clang_6p0_linker_files",
srcs = [
- "//tools/cpp/clang_3p6:ar",
- "//tools/cpp/clang_3p6:clang",
- "//tools/cpp/clang_3p6:clang-symlinks",
- "//tools/cpp/clang_3p6:ld",
- "@clang_3p6_repo//:compiler_pieces",
+ "//tools/cpp/clang_6p0:ar",
+ "//tools/cpp/clang_6p0:clang",
+ "//tools/cpp/clang_6p0:clang-symlinks",
+ "//tools/cpp/clang_6p0:ld",
+ "@clang_6p0_repo//:compiler_pieces",
],
)
filegroup(
- name = "clang_3p6_strip_files",
+ name = "clang_6p0_strip_files",
srcs = [
- "//tools/cpp/clang_3p6:strip",
- "@clang_3p6_repo//:compiler_pieces",
+ "//tools/cpp/clang_6p0:strip",
+ "@clang_6p0_repo//:compiler_pieces",
],
)
filegroup(
- name = "clang_3p6_compiler_files",
+ name = "clang_6p0_compiler_files",
srcs = [
"flags_compiler_inputs",
- "//tools/cpp/clang_3p6:clang",
- "//tools/cpp/clang_3p6:ld",
- "@clang_3p6_repo//:compiler_components",
- "@clang_3p6_repo//:compiler_pieces",
+ "//tools/cpp/clang_6p0:clang",
+ "//tools/cpp/clang_6p0:ld",
+ "@clang_6p0_repo//:compiler_components",
+ "@clang_6p0_repo//:compiler_pieces",
],
)
cc_toolchain(
name = "cc-compiler-k8",
- all_files = ":clang_3p6_all_files",
- compiler_files = ":clang_3p6_compiler_files",
+ all_files = ":clang_6p0_all_files",
+ compiler_files = ":clang_6p0_compiler_files",
cpu = "k8",
dwp_files = ":empty",
dynamic_runtime_libs = [":empty"],
- linker_files = ":clang_3p6_linker_files",
- objcopy_files = "//tools/cpp/clang_3p6:objcopy",
+ linker_files = ":clang_6p0_linker_files",
+ objcopy_files = "//tools/cpp/clang_6p0:objcopy",
static_runtime_libs = [":empty"],
- strip_files = ":clang_3p6_strip_files",
+ strip_files = ":clang_6p0_strip_files",
supports_param_files = 1,
toolchain_identifier = "k8_linux",
)
@@ -165,36 +165,36 @@
filegroup(
name = "linaro-gcc-files",
srcs = [
- ":clang_3p6_all_files",
+ ":clang_6p0_all_files",
"//tools/cpp/linaro_linux_gcc:clang-symlinks",
"//tools/cpp/linaro_linux_gcc:tool-wrappers",
- "@linaro_linux_gcc_4_9_repo//:compiler_pieces",
+ "@linaro_linux_gcc_repo//:compiler_pieces",
],
)
filegroup(
name = "linaro_linux_linker_files",
srcs = [
- ":clang_3p6_linker_files",
+ ":clang_6p0_linker_files",
"//tools/cpp/linaro_linux_gcc:ar",
"//tools/cpp/linaro_linux_gcc:clang",
"//tools/cpp/linaro_linux_gcc:clang-ld",
"//tools/cpp/linaro_linux_gcc:clang-symlinks",
"//tools/cpp/linaro_linux_gcc:gcc",
"//tools/cpp/linaro_linux_gcc:ld",
- "@linaro_linux_gcc_4_9_repo//:compiler_pieces",
+ "@linaro_linux_gcc_repo//:compiler_pieces",
],
)
filegroup(
name = "linaro_linux_compiler_files",
srcs = [
- ":clang_3p6_compiler_files",
+ ":clang_6p0_compiler_files",
"//tools/cpp/linaro_linux_gcc:as",
"//tools/cpp/linaro_linux_gcc:clang",
"//tools/cpp/linaro_linux_gcc:gcc",
"//tools/cpp/linaro_linux_gcc:ld",
- "@linaro_linux_gcc_4_9_repo//:compiler_pieces",
+ "@linaro_linux_gcc_repo//:compiler_pieces",
],
)
@@ -202,7 +202,7 @@
name = "linaro_linux_strip_files",
srcs = [
"//tools/cpp/linaro_linux_gcc:strip",
- "@linaro_linux_gcc_4_9_repo//:compiler_pieces",
+ "@linaro_linux_gcc_repo//:compiler_pieces",
],
)
diff --git a/tools/cpp/CROSSTOOL b/tools/cpp/CROSSTOOL
index 128954a..21b3349 100644
--- a/tools/cpp/CROSSTOOL
+++ b/tools/cpp/CROSSTOOL
@@ -105,59 +105,65 @@
abi_libc_version: "local"
tool_path {
name: "ar"
- path: "clang_3p6/x86_64-linux-gnu-ar"
+ path: "clang_6p0/x86_64-linux-gnu-ar"
}
tool_path {
name: "compat-ld"
- path: "clang_3p6/x86_64-linux-gnu-ld"
+ path: "clang_6p0/x86_64-linux-gnu-ld"
}
tool_path {
name: "cpp"
- path: "clang_3p6/x86_64-linux-gnu-cpp"
+ path: "clang_6p0/x86_64-linux-gnu-cpp"
}
tool_path {
name: "dwp"
- path: "clang_3p6/x86_64-linux-gnu-dwp"
+ path: "clang_6p0/x86_64-linux-gnu-dwp"
}
tool_path {
name: "gcc"
- path: "clang_3p6/x86_64-linux-gnu-clang-3.6"
+ path: "clang_6p0/x86_64-linux-gnu-clang-6.0"
}
tool_path {
name: "gcov"
- path: "clang_3p6/x86_64-linux-gnu-gcov"
+ path: "clang_6p0/x86_64-linux-gnu-gcov"
}
tool_path {
name: "ld"
- path: "clang_3p6/x86_64-linux-gnu-ld"
+ path: "clang_6p0/x86_64-linux-gnu-ld"
}
tool_path {
name: "nm"
- path: "clang_3p6/x86_64-linux-gnu-nm"
+ path: "clang_6p0/x86_64-linux-gnu-nm"
}
tool_path {
name: "objcopy"
- path: "clang_3p6/x86_64-linux-gnu-objcopy"
+ path: "clang_6p0/x86_64-linux-gnu-objcopy"
}
tool_path {
name: "objdump"
- path: "clang_3p6/x86_64-linux-gnu-objdump"
+ path: "clang_6p0/x86_64-linux-gnu-objdump"
}
tool_path {
name: "strip"
- path: "clang_3p6/x86_64-linux-gnu-strip"
+ path: "clang_6p0/x86_64-linux-gnu-strip"
}
supports_gold_linker: false
supports_thin_archives: false
needsPic: true
- compiler_flag: "--sysroot=external/clang_3p6_repo/"
+ compiler_flag: "--sysroot=external/clang_6p0_repo/"
compiler_flag: "-nostdinc"
compiler_flag: "-isystem"
- compiler_flag: "external/clang_3p6_repo/usr/include"
+ compiler_flag: "external/clang_6p0_repo/usr/include/x86_64-linux-gnu"
compiler_flag: "-isystem"
- compiler_flag: "external/clang_3p6_repo/usr/include/x86_64-linux-gnu"
+ compiler_flag: "external/clang_6p0_repo/usr/lib/llvm-6.0/lib/clang/6.0.0/include"
compiler_flag: "-isystem"
- compiler_flag: "external/clang_3p6_repo/usr/lib/llvm-3.6/lib/clang/3.6.2/include"
+ compiler_flag: "external/clang_6p0_repo/usr/include/c++/7.4.0"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/clang_6p0_repo/usr/include/x86_64-linux-gnu/c++/7.4.0"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/clang_6p0_repo/usr/include/c++/7.4.0/backward"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/clang_6p0_repo/usr/include"
compiler_flag: "-D__STDC_FORMAT_MACROS"
compiler_flag: "-D__STDC_CONSTANT_MACROS"
compiler_flag: "-D__STDC_LIMIT_MACROS"
@@ -185,22 +191,18 @@
compiler_flag: "-pipe"
compiler_flag: "-ggdb3"
cxx_flag: "-isystem"
- cxx_flag: "external/clang_3p6_repo/usr/include/c++/4.9"
- cxx_flag: "-isystem"
- cxx_flag: "external/clang_3p6_repo/usr/include/x86_64-linux-gnu/c++/4.9"
- cxx_flag: "-isystem"
- cxx_flag: "external/clang_3p6_repo/usr/include/c++/4.9/backward"
+ cxx_flag: "external/clang_6p0_repo/usr/include"
linker_flag: "-nodefaultlibs"
- linker_flag: "--sysroot=external/clang_3p6_repo/"
+ linker_flag: "--sysroot=external/clang_6p0_repo/"
linker_flag: "-lstdc++"
linker_flag: "-lc"
linker_flag: "-lgcc"
linker_flag: "-lgcc_s"
- linker_flag: "-Bexternal/clang_3p6_repo/usr/bin/"
- linker_flag: "-Ltools/cpp/clang_3p6/clang_more_libs"
- linker_flag: "-Lexternal/clang_3p6/lib/x86_64-linux-gnu"
- linker_flag: "-Lexternal/clang_3p6/usr/lib/x86_64-linux-gnu"
- linker_flag: "-Lexternal/clang_3p6/usr/lib/gcc/x86_64-linux-gnu"
+ linker_flag: "-Bexternal/clang_6p0_repo/usr/bin/"
+ linker_flag: "-Ltools/cpp/clang_6p0/clang_more_libs"
+ linker_flag: "-Lexternal/clang_6p0_repo/lib/x86_64-linux-gnu"
+ linker_flag: "-Lexternal/clang_6p0_repo/usr/lib/x86_64-linux-gnu"
+ linker_flag: "-Lexternal/clang_6p0_repo/usr/lib/gcc/x86_64-linux-gnu"
linker_flag: "-no-canonical-prefixes"
linker_flag: "-fuse-ld=gold"
linker_flag: "-Wl,-z,relro,-z,now"
@@ -222,20 +224,21 @@
linking_mode_flags {
mode: DYNAMIC
}
- cxx_builtin_include_directory: "%package(@clang_3p6_repo//usr)%/include/c++/4.9"
- cxx_builtin_include_directory: "%package(@clang_3p6_repo//usr)%/include/x86_64-linux-gnu/c++/4.9"
- cxx_builtin_include_directory: "%package(@clang_3p6_repo//usr)%/include/c++/4.9/backward"
- cxx_builtin_include_directory: "%package(@clang_3p6_repo//usr)%/local/include"
- cxx_builtin_include_directory: "%package(@clang_3p6_repo//usr)%/lib/llvm-3.6/lib/clang/3.6.2/include"
- cxx_builtin_include_directory: "%package(@clang_3p6_repo//usr)%/include/x86_64-linux-gnu"
- cxx_builtin_include_directory: "%package(@clang_3p6_repo//usr)%/include"
- cxx_builtin_include_directory: "%package(@clang_3p6_repo//usr)%/lib/clang/3.6.2/include"
+ cxx_builtin_include_directory: "%package(@clang_6p0_repo//usr)%/include/c++/7.4.0"
+ cxx_builtin_include_directory: "%package(@clang_6p0_repo//usr)%/include/x86_64-linux-gnu/c++/7.4.0"
+ cxx_builtin_include_directory: "%package(@clang_6p0_repo//usr)%/include/c++/7.4.0/backward"
+ cxx_builtin_include_directory: "%package(@clang_6p0_repo//usr)%/local/include"
+ cxx_builtin_include_directory: "%package(@clang_6p0_repo//usr)%/lib/llvm-6.0/lib/clang/6.0.0/include"
+ cxx_builtin_include_directory: "%package(@clang_6p0_repo//usr)%/include/x86_64-linux-gnu"
builtin_sysroot: ""
unfiltered_cxx_flag: "-no-canonical-prefixes"
unfiltered_cxx_flag: "-Wno-builtin-macro-redefined"
unfiltered_cxx_flag: "-D__DATE__=\"redacted\""
unfiltered_cxx_flag: "-D__TIMESTAMP__=\"redacted\""
unfiltered_cxx_flag: "-D__TIME__=\"redacted\""
+ unfiltered_cxx_flag: "-Wno-varargs"
+ unfiltered_cxx_flag: "-Wno-null-pointer-arithmetic"
+ unfiltered_cxx_flag: "-Wno-mismatched-new-delete"
supports_normalizing_ar: false
supports_start_end_lib: false
supports_interface_shared_objects: false
@@ -305,7 +308,7 @@
action: "c++-header-preprocessing"
action: "c++-module-compile"
flag_group {
- flag: "-std=gnu++1y"
+ flag: "-std=gnu++1z"
}
}
flag_set {
@@ -553,10 +556,10 @@
linking_mode_flags {
mode: DYNAMIC
}
- cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2019-linux-gnueabi/usr/lib/gcc/arm-frc2019-linux-gnueabi/6.3.0/include)%"
- cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2019-linux-gnueabi/usr/lib/gcc/arm-frc2019-linux-gnueabi/6.3.0/include-fixed)%"
- cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2019-linux-gnueabi/usr/include/c++/6.3.0/arm-frc2019-linux-gnueabi)%"
- cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2019-linux-gnueabi/usr/include/c++/6.3.0/backward)%"
+ cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2020-linux-gnueabi/usr/lib/gcc/arm-frc2020-linux-gnueabi/7.3.0/include)%"
+ cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2020-linux-gnueabi/usr/lib/gcc/arm-frc2020-linux-gnueabi/7.3.0/include-fixed)%"
+ cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0/arm-frc2020-linux-gnueabi)%"
+ cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0/backward)%"
builtin_sysroot: ""
unfiltered_cxx_flag: "-no-canonical-prefixes"
unfiltered_cxx_flag: "-Wno-builtin-macro-redefined"
@@ -581,12 +584,12 @@
action: "lto-backend"
action: "clif-match"
flag_group {
- flag: "--sysroot=external/arm_frc_linux_gnueabi_repo/arm-frc2019-linux-gnueabi"
+ flag: "--sysroot=external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi"
flag: "-nostdinc"
flag: "-isystem"
- flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2019-linux-gnueabi/usr/lib/gcc/arm-frc2019-linux-gnueabi/6.3.0/include"
+ flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/lib/gcc/arm-frc2020-linux-gnueabi/7.3.0/include"
flag: "-isystem"
- flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2019-linux-gnueabi/usr/lib/gcc/arm-frc2019-linux-gnueabi/6.3.0/include-fixed"
+ flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/lib/gcc/arm-frc2020-linux-gnueabi/7.3.0/include-fixed"
}
}
flag_set {
@@ -606,11 +609,11 @@
action: "c++-module-codegen"
flag_group {
flag: "-isystem"
- flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2019-linux-gnueabi/usr/include/c++/6.3.0"
+ flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0"
flag: "-isystem"
- flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2019-linux-gnueabi/usr/include/c++/6.3.0/arm-frc2019-linux-gnueabi"
+ flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0/arm-frc2020-linux-gnueabi"
flag: "-isystem"
- flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2019-linux-gnueabi/usr/include/c++/6.3.0/backward"
+ flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0/backward"
}
}
flag_set {
@@ -625,7 +628,7 @@
action: "clif-match"
flag_group {
flag: "-isystem"
- flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2019-linux-gnueabi/usr/include"
+ flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/include"
flag: "-mfpu=neon"
flag: "-D__STDC_FORMAT_MACROS"
flag: "-D__STDC_CONSTANT_MACROS"
@@ -837,7 +840,7 @@
action: "c++-header-preprocessing"
action: "c++-module-compile"
flag_group {
- flag: "-std=gnu++1y"
+ flag: "-std=gnu++1z"
flag: "-fno-sized-deallocation"
}
}
@@ -874,7 +877,7 @@
target_cpu: "armhf-debian"
target_libc: "glibc_2.19"
compiler: "clang"
- abi_version: "clang_3.6"
+ abi_version: "clang_6.0"
abi_libc_version: "glibc_2.19"
tool_path {
name: "ar"
@@ -925,18 +928,26 @@
needsPic: true
compiler_flag: "-target"
compiler_flag: "armv7a-arm-linux-gnueabif"
- compiler_flag: "--sysroot=external/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/libc"
+ compiler_flag: "--sysroot=external/linaro_linux_gcc_repo/arm-linux-gnueabihf/libc"
compiler_flag: "-mfloat-abi=hard"
compiler_flag: "-mfpu=vfpv3-d16"
compiler_flag: "-nostdinc"
compiler_flag: "-isystem"
- compiler_flag: "/usr/lib/clang/3.6/include"
+ compiler_flag: "/usr/lib/clang/6.0/include"
compiler_flag: "-isystem"
- compiler_flag: "external/linaro_linux_gcc_4_9_repo/lib/gcc/arm-linux-gnueabihf/4.9.3/include"
+ compiler_flag: "external/linaro_linux_gcc_repo/lib/gcc/arm-linux-gnueabihf/7.4.1/include"
compiler_flag: "-isystem"
- compiler_flag: "external/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/libc/usr/include"
+ compiler_flag: "external/linaro_linux_gcc_repo/lib/gcc/arm-linux-gnueabihf/7.4.1/include-fixed"
compiler_flag: "-isystem"
- compiler_flag: "external/linaro_linux_gcc_4_9_repo/lib/gcc/arm-linux-gnueabihf/4.9.3/include-fixed"
+ compiler_flag: "external/linaro_linux_gcc_repo/arm-linux-gnueabihf/include/c++/7.4.1/arm-linux-gnueabihf"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/linaro_linux_gcc_repo/arm-linux-gnueabihf/include/c++/7.4.1"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/linaro_linux_gcc_repo/include/c++/7.4.1/arm-linux-gnueabihf"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/linaro_linux_gcc_repo/include/c++/7.4.1"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/linaro_linux_gcc_repo/arm-linux-gnueabihf/libc/usr/include"
compiler_flag: "-D__STDC_FORMAT_MACROS"
compiler_flag: "-D__STDC_CONSTANT_MACROS"
compiler_flag: "-D__STDC_LIMIT_MACROS"
@@ -961,23 +972,17 @@
compiler_flag: "-fno-omit-frame-pointer"
compiler_flag: "-pipe"
compiler_flag: "-ggdb3"
- cxx_flag: "-isystem"
- cxx_flag: "external/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/include/c++/4.9.3/arm-linux-gnueabihf"
- cxx_flag: "-isystem"
- cxx_flag: "external/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/include/c++/4.9.3"
- cxx_flag: "-isystem"
- cxx_flag: "external/linaro_linux_gcc_4_9_repo/include/c++/4.9.3/arm-linux-gnueabihf"
- cxx_flag: "-isystem"
- cxx_flag: "external/linaro_linux_gcc_4_9_repo/include/c++/4.9.3"
linker_flag: "-target"
linker_flag: "armv7a-arm-linux-gnueabif"
- linker_flag: "--sysroot=external/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/libc"
+ linker_flag: "--sysroot=external/linaro_linux_gcc_repo/arm-linux-gnueabihf/libc"
linker_flag: "-lstdc++"
linker_flag: "-Ltools/cpp/linaro_linux_gcc/clang_more_libs"
- linker_flag: "-Lexternal/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/lib"
- linker_flag: "-Lexternal/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/libc/lib"
- linker_flag: "-Lexternal/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/libc/usr/lib"
- linker_flag: "-Bexternal/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/bin"
+ linker_flag: "-Lexternal/linaro_linux_gcc_repo/arm-linux-gnueabihf/lib"
+ linker_flag: "-Lexternal/linaro_linux_gcc_repo/arm-linux-gnueabihf/libc/lib"
+ linker_flag: "-Lexternal/linaro_linux_gcc_repo/arm-linux-gnueabihf/libc/usr/lib"
+ linker_flag: "-Lexternal/linaro_linux_gcc_repo/lib/gcc/arm-linux-gnueabihf/7.4.1"
+ linker_flag: "-Bexternal/linaro_linux_gcc_repo/lib/gcc/arm-linux-gnueabihf/7.4.1"
+ linker_flag: "-Bexternal/linaro_linux_gcc_repo/arm-linux-gnueabihf/bin"
linker_flag: "-Wl,--dynamic-linker=/lib/ld-linux-armhf.so.3"
linker_flag: "-no-canonical-prefixes"
linker_flag: "-Wl,-z,relro,-z,now"
@@ -998,20 +1003,23 @@
linking_mode_flags {
mode: DYNAMIC
}
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//include)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//arm-linux-gnueabihf/libc/usr/include)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//arm-linux-gnueabihf/libc/usr/lib/include)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//arm-linux-gnueabihf/libc/lib/gcc/arm-linux-gnueabihf/4.9.3/include-fixed)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//include)%/c++/4.9.3"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//arm-linux-gnueabihf/libc/lib/gcc/arm-linux-gnueabihf/4.9.3/include)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//arm-linux-gnueabihf/libc/lib/gcc/arm-linux-gnueabihf/4.9.3/include-fixed)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//lib/gcc/arm-linux-gnueabihf/4.9.3/include)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//lib/gcc/arm-linux-gnueabihf/4.9.3/include-fixed)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//arm-linux-gnueabihf/include)%/c++/4.9.3"
- cxx_builtin_include_directory: "/usr/lib/clang/3.6/include"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//include)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//arm-linux-gnueabihf/libc/usr/include)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//arm-linux-gnueabihf/libc/usr/lib/include)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//arm-linux-gnueabihf/libc/lib/gcc/arm-linux-gnueabihf/7.4.1/include-fixed)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//include)%/c++/7.4.1"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//arm-linux-gnueabihf/libc/lib/gcc/arm-linux-gnueabihf/7.4.1/include)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//arm-linux-gnueabihf/libc/lib/gcc/arm-linux-gnueabihf/7.4.1/include-fixed)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//lib/gcc/arm-linux-gnueabihf/7.4.1/include)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//lib/gcc/arm-linux-gnueabihf/7.4.1/include-fixed)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//arm-linux-gnueabihf/include)%/c++/7.4.1"
+ cxx_builtin_include_directory: "/usr/lib/clang/6.0/include"
builtin_sysroot: ""
unfiltered_cxx_flag: "-no-canonical-prefixes"
unfiltered_cxx_flag: "-Wno-builtin-macro-redefined"
+ unfiltered_cxx_flag: "-Wno-mismatched-new-delete"
+ unfiltered_cxx_flag: "-Wno-null-pointer-arithmetic"
+ unfiltered_cxx_flag: "-Wno-varargs"
unfiltered_cxx_flag: "-D__DATE__=\"redacted\""
unfiltered_cxx_flag: "-D__TIMESTAMP__=\"redacted\""
unfiltered_cxx_flag: "-D__TIME__=\"redacted\""
@@ -1084,7 +1092,7 @@
action: "c++-header-preprocessing"
action: "c++-module-compile"
flag_group {
- flag: "-std=gnu++1y"
+ flag: "-std=gnu++1z"
}
}
flag_set {
@@ -1283,7 +1291,7 @@
action: "c++-header-preprocessing"
action: "c++-module-compile"
flag_group {
- flag: "--std=gnu++1y"
+ flag: "--std=gnu++1z"
flag: "-fno-exceptions"
flag: "-fno-rtti"
}
@@ -1486,7 +1494,7 @@
action: "c++-header-preprocessing"
action: "c++-module-compile"
flag_group {
- flag: "--std=gnu++1y"
+ flag: "--std=gnu++1z"
flag: "-fno-exceptions"
flag: "-fno-rtti"
}
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ar b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ar
index 09e37a4..21341e9 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ar
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ar
@@ -4,6 +4,6 @@
LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
export LD_LIBRARY_PATH
-exec -a arm-frc2019-linux-gnueabi-ar \
- "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2019-linux-gnueabi-ar" \
+exec -a arm-frc2020-linux-gnueabi-ar \
+ "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-ar" \
"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-as b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-as
index df82796..9235820 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-as
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-as
@@ -4,6 +4,6 @@
LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
export LD_LIBRARY_PATH
-exec -a arm-frc2019-linux-gnueabi-as \
- "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2019-linux-gnueabi-as" \
+exec -a arm-frc2020-linux-gnueabi-as \
+ "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-as" \
"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-cpp b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-cpp
index 00e88d6..09926da 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-cpp
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-cpp
@@ -4,6 +4,6 @@
LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
export LD_LIBRARY_PATH
-exec -a arm-frc2019-linux-gnueabi-cpp \
- "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2019-linux-gnueabi-cpp" \
+exec -a arm-frc2020-linux-gnueabi-cpp \
+ "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-cpp" \
"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-dwp b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-dwp
index 9201bbe..23579ba 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-dwp
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-dwp
@@ -4,6 +4,6 @@
LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
export LD_LIBRARY_PATH
-exec -a arm-frc2019-linux-gnueabi-dwp \
- "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2019-linux-gnueabi-dwp" \
+exec -a arm-frc2020-linux-gnueabi-dwp \
+ "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-dwp" \
"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcc b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcc
index 33bf997..3669d2e 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcc
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcc
@@ -4,5 +4,5 @@
LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
export LD_LIBRARY_PATH
-exec "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2019-linux-gnueabi-gcc" \
+exec "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-gcc" \
"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcov b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcov
index 2f0a64e..291cf01 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcov
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-gcov
@@ -4,6 +4,6 @@
LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
export LD_LIBRARY_PATH
-exec -a arm-frc2019-linux-gnueabi-gcov \
- "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2019-linux-gnueabi-gcov" \
+exec -a arm-frc2020-linux-gnueabi-gcov \
+ "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-gcov" \
"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ld b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ld
index 862fb3c..79ee223 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ld
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-ld
@@ -4,6 +4,6 @@
LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
export LD_LIBRARY_PATH
-exec -a arm-frc2019-linux-gnueabi-ld \
- "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2019-linux-gnueabi-ld" \
+exec -a arm-frc2020-linux-gnueabi-ld \
+ "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-ld" \
"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-nm b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-nm
index 1436464..b6295b7 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-nm
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-nm
@@ -4,6 +4,6 @@
LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
export LD_LIBRARY_PATH
-exec -a arm-frc2019-linux-gnueabi-nm \
- "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2019-linux-gnueabi-nm" \
+exec -a arm-frc2020-linux-gnueabi-nm \
+ "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-nm" \
"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objcopy b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objcopy
index fec13a6..f53cfc3 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objcopy
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objcopy
@@ -4,6 +4,6 @@
LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
export LD_LIBRARY_PATH
-exec -a arm-frc2019-linux-gnueabi-objcopy \
- "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2019-linux-gnueabi-objcopy" \
+exec -a arm-frc2020-linux-gnueabi-objcopy \
+ "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-objcopy" \
"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objdump b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objdump
index d305185..2543956 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objdump
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-objdump
@@ -4,6 +4,6 @@
LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
export LD_LIBRARY_PATH
-exec -a arm-frc2019-linux-gnueabi-objdump \
- "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2019-linux-gnueabi-objdump" \
+exec -a arm-frc2020-linux-gnueabi-objdump \
+ "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-objdump" \
"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-strip b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-strip
index 3de77a6..cc1e77a 100755
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-strip
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi-strip
@@ -4,6 +4,6 @@
LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/arm_frc_gnueabi_deps/lib/x86_64-linux-gnu"
export LD_LIBRARY_PATH
-exec -a arm-frc2019-linux-gnueabi-strip \
- "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2019-linux-gnueabi-strip" \
+exec -a arm-frc2020-linux-gnueabi-strip \
+ "${BAZEL_OUTPUT_ROOT}external/arm_frc_linux_gnueabi_repo/bin/arm-frc2020-linux-gnueabi-strip" \
"$@"
diff --git a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi.BUILD b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi.BUILD
index 51b17a7..c83bdf5 100644
--- a/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi.BUILD
+++ b/tools/cpp/arm-frc-linux-gnueabi/arm-frc-linux-gnueabi.BUILD
@@ -1,6 +1,6 @@
package(default_visibility = ["//visibility:public"])
-prefix = "arm-frc2019-linux-gnueabi"
+prefix = "arm-frc2020-linux-gnueabi"
filegroup(
name = "gcc",
@@ -65,9 +65,9 @@
"usr/lib/**",
"lib/**",
"bin/**",
- "**"
+ "**",
]] + [
- "libexec/gcc/" + prefix + "/6.3.0/**",
+ "libexec/gcc/" + prefix + "/7.3.0/**",
"bin/**",
]),
)
diff --git a/tools/cpp/clang_3p6/x86_64-linux-gnu-ar b/tools/cpp/clang_3p6/x86_64-linux-gnu-ar
deleted file mode 100755
index b8ba259..0000000
--- a/tools/cpp/clang_3p6/x86_64-linux-gnu-ar
+++ /dev/null
@@ -1,9 +0,0 @@
-#!/bin/bash --norc
-
-LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib/x86_64-linux-gnu"
-LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib"
-export LD_LIBRARY_PATH
-
-exec -a ar \
- ${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/bin/ar \
- "$@"
diff --git a/tools/cpp/clang_3p6/x86_64-linux-gnu-as b/tools/cpp/clang_3p6/x86_64-linux-gnu-as
deleted file mode 100755
index 461f584..0000000
--- a/tools/cpp/clang_3p6/x86_64-linux-gnu-as
+++ /dev/null
@@ -1,9 +0,0 @@
-#!/bin/bash --norc
-
-LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib/x86_64-linux-gnu"
-LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib"
-export LD_LIBRARY_PATH
-
-exec -a as \
- ${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/bin/as \
- "$@"
diff --git a/tools/cpp/clang_3p6/x86_64-linux-gnu-clang-3.6 b/tools/cpp/clang_3p6/x86_64-linux-gnu-clang-3.6
deleted file mode 100755
index 369bf41..0000000
--- a/tools/cpp/clang_3p6/x86_64-linux-gnu-clang-3.6
+++ /dev/null
@@ -1,11 +0,0 @@
-#!/bin/bash --norc
-
-LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib/x86_64-linux-gnu"
-# TODO(Brian): Figure out why it segfaults with this enabled, and re-enable it.
-#LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/lib/x86_64-linux-gnu"
-LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib"
-export LD_LIBRARY_PATH
-
-exec \
- ${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/bin/clang-3.6 \
- "$@"
diff --git a/tools/cpp/clang_3p6/x86_64-linux-gnu-cpp b/tools/cpp/clang_3p6/x86_64-linux-gnu-cpp
deleted file mode 100755
index 5bc6499..0000000
--- a/tools/cpp/clang_3p6/x86_64-linux-gnu-cpp
+++ /dev/null
@@ -1,9 +0,0 @@
-#!/bin/bash --norc
-
-LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib/x86_64-linux-gnu"
-LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib"
-export LD_LIBRARY_PATH
-
-exec -a cpp \
- ${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/bin/cpp \
- "$@"
diff --git a/tools/cpp/clang_3p6/x86_64-linux-gnu-gcc b/tools/cpp/clang_3p6/x86_64-linux-gnu-gcc
deleted file mode 100755
index 1d0e502..0000000
--- a/tools/cpp/clang_3p6/x86_64-linux-gnu-gcc
+++ /dev/null
@@ -1,10 +0,0 @@
-#!/bin/bash --norc
-
-LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib/x86_64-linux-gnu"
-LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib"
-export LD_LIBRARY_PATH
-
-PATH="${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib/gcc/x86_64-linux-gnu/4.9:$PATH" \
- exec \
- ${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/bin/gcc \
- "$@"
diff --git a/tools/cpp/clang_3p6/x86_64-linux-gnu-gcov b/tools/cpp/clang_3p6/x86_64-linux-gnu-gcov
deleted file mode 100755
index 58b621c..0000000
--- a/tools/cpp/clang_3p6/x86_64-linux-gnu-gcov
+++ /dev/null
@@ -1,9 +0,0 @@
-#!/bin/bash --norc
-
-LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib/x86_64-linux-gnu"
-LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib"
-export LD_LIBRARY_PATH
-
-exec -a gcov \
- ${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/bin/gcov \
- "$@"
diff --git a/tools/cpp/clang_3p6/x86_64-linux-gnu-ld b/tools/cpp/clang_3p6/x86_64-linux-gnu-ld
deleted file mode 100755
index 9f59f2e..0000000
--- a/tools/cpp/clang_3p6/x86_64-linux-gnu-ld
+++ /dev/null
@@ -1,9 +0,0 @@
-#!/bin/bash --norc
-
-LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib/x86_64-linux-gnu"
-LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib"
-export LD_LIBRARY_PATH
-
-exec -a ld \
- ${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/bin/ld \
- "$@"
diff --git a/tools/cpp/clang_3p6/x86_64-linux-gnu-nm b/tools/cpp/clang_3p6/x86_64-linux-gnu-nm
deleted file mode 100755
index f0b12c8..0000000
--- a/tools/cpp/clang_3p6/x86_64-linux-gnu-nm
+++ /dev/null
@@ -1,9 +0,0 @@
-#!/bin/bash --norc
-
-LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib/x86_64-linux-gnu"
-LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib"
-export LD_LIBRARY_PATH
-
-exec -a nm \
- ${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/bin/nm \
- "$@"
diff --git a/tools/cpp/clang_3p6/x86_64-linux-gnu-objcopy b/tools/cpp/clang_3p6/x86_64-linux-gnu-objcopy
deleted file mode 100755
index 55b6b3d..0000000
--- a/tools/cpp/clang_3p6/x86_64-linux-gnu-objcopy
+++ /dev/null
@@ -1,9 +0,0 @@
-#!/bin/bash --norc
-
-LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib/x86_64-linux-gnu"
-LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib"
-export LD_LIBRARY_PATH
-
-exec -a objcopy \
- ${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/bin/objcopy \
- "$@"
diff --git a/tools/cpp/clang_3p6/x86_64-linux-gnu-objdump b/tools/cpp/clang_3p6/x86_64-linux-gnu-objdump
deleted file mode 100755
index 194ffe9..0000000
--- a/tools/cpp/clang_3p6/x86_64-linux-gnu-objdump
+++ /dev/null
@@ -1,9 +0,0 @@
-#!/bin/bash --norc
-
-LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib/x86_64-linux-gnu"
-LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib"
-export LD_LIBRARY_PATH
-
-exec -a objdump \
- ${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/bin/objdump \
- "$@"
diff --git a/tools/cpp/clang_3p6/x86_64-linux-gnu-strip b/tools/cpp/clang_3p6/x86_64-linux-gnu-strip
deleted file mode 100755
index c53f8dd..0000000
--- a/tools/cpp/clang_3p6/x86_64-linux-gnu-strip
+++ /dev/null
@@ -1,9 +0,0 @@
-#!/bin/bash --norc
-
-LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib/x86_64-linux-gnu"
-LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/lib"
-export LD_LIBRARY_PATH
-
-exec -a strip \
- ${BAZEL_OUTPUT_ROOT}external/clang_3p6_repo/usr/bin/strip \
- "$@"
diff --git a/tools/cpp/clang_3p6/BUILD b/tools/cpp/clang_6p0/BUILD
similarity index 76%
rename from tools/cpp/clang_3p6/BUILD
rename to tools/cpp/clang_6p0/BUILD
index 23504d7..7777859 100644
--- a/tools/cpp/clang_3p6/BUILD
+++ b/tools/cpp/clang_6p0/BUILD
@@ -4,7 +4,7 @@
name = "ar",
srcs = [
"x86_64-linux-gnu-ar",
- "@clang_3p6_repo//:ar",
+ "@clang_6p0_repo//:ar",
],
)
@@ -12,7 +12,7 @@
name = "ld",
srcs = [
"x86_64-linux-gnu-ld",
- "@clang_3p6_repo//:ld",
+ "@clang_6p0_repo//:ld",
],
)
@@ -20,7 +20,7 @@
name = "nm",
srcs = [
"x86_64-linux-gnu-nm",
- "@clang_3p6_repo//:nm",
+ "@clang_6p0_repo//:nm",
],
)
@@ -28,7 +28,7 @@
name = "objcopy",
srcs = [
"x86_64-linux-gnu-objcopy",
- "@clang_3p6_repo//:objcopy",
+ "@clang_6p0_repo//:objcopy",
],
)
@@ -36,7 +36,7 @@
name = "objdump",
srcs = [
"x86_64-linux-gnu-objdump",
- "@clang_3p6_repo//:objdump",
+ "@clang_6p0_repo//:objdump",
],
)
@@ -44,7 +44,7 @@
name = "strip",
srcs = [
"x86_64-linux-gnu-strip",
- "@clang_3p6_repo//:strip",
+ "@clang_6p0_repo//:strip",
],
)
@@ -52,15 +52,15 @@
name = "as",
srcs = [
"x86_64-linux-gnu-as",
- "@clang_3p6_repo//:as",
+ "@clang_6p0_repo//:as",
],
)
filegroup(
name = "clang",
srcs = [
- "x86_64-linux-gnu-clang-3.6",
- "@clang_3p6_repo//:clang",
+ "x86_64-linux-gnu-clang-6.0",
+ "@clang_6p0_repo//:clang",
],
)
diff --git a/tools/cpp/clang_3p6/clang_3p6.BUILD b/tools/cpp/clang_6p0/clang_6p0.BUILD
similarity index 95%
rename from tools/cpp/clang_3p6/clang_3p6.BUILD
rename to tools/cpp/clang_6p0/clang_6p0.BUILD
index 648a511..e70f8a9 100644
--- a/tools/cpp/clang_3p6/clang_3p6.BUILD
+++ b/tools/cpp/clang_6p0/clang_6p0.BUILD
@@ -3,7 +3,7 @@
filegroup(
name = "clang-format",
srcs = [
- "usr/bin/clang-3.6",
+ "usr/bin/clang-6.0",
":compiler_pieces",
],
)
@@ -11,7 +11,7 @@
filegroup(
name = "clang",
srcs = [
- "usr/bin/clang-3.6",
+ "usr/bin/clang-6.0",
],
)
diff --git a/tools/cpp/clang_3p6/clang_more_libs/libc.so b/tools/cpp/clang_6p0/clang_more_libs/libc.so
similarity index 100%
rename from tools/cpp/clang_3p6/clang_more_libs/libc.so
rename to tools/cpp/clang_6p0/clang_more_libs/libc.so
diff --git a/tools/cpp/clang_3p6/clang_more_libs/libpthread.so b/tools/cpp/clang_6p0/clang_more_libs/libpthread.so
similarity index 100%
rename from tools/cpp/clang_3p6/clang_more_libs/libpthread.so
rename to tools/cpp/clang_6p0/clang_more_libs/libpthread.so
diff --git a/tools/cpp/clang_6p0/x86_64-linux-gnu-ar b/tools/cpp/clang_6p0/x86_64-linux-gnu-ar
new file mode 100755
index 0000000..869dd16
--- /dev/null
+++ b/tools/cpp/clang_6p0/x86_64-linux-gnu-ar
@@ -0,0 +1,9 @@
+#!/bin/bash --norc
+
+LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib/x86_64-linux-gnu"
+LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib"
+export LD_LIBRARY_PATH
+
+exec -a ar \
+ ${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/bin/ar \
+ "$@"
diff --git a/tools/cpp/clang_6p0/x86_64-linux-gnu-as b/tools/cpp/clang_6p0/x86_64-linux-gnu-as
new file mode 100755
index 0000000..5f55a68
--- /dev/null
+++ b/tools/cpp/clang_6p0/x86_64-linux-gnu-as
@@ -0,0 +1,9 @@
+#!/bin/bash --norc
+
+LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib/x86_64-linux-gnu"
+LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib"
+export LD_LIBRARY_PATH
+
+exec -a as \
+ ${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/bin/as \
+ "$@"
diff --git a/tools/cpp/clang_6p0/x86_64-linux-gnu-clang-6.0 b/tools/cpp/clang_6p0/x86_64-linux-gnu-clang-6.0
new file mode 100755
index 0000000..a652027
--- /dev/null
+++ b/tools/cpp/clang_6p0/x86_64-linux-gnu-clang-6.0
@@ -0,0 +1,11 @@
+#!/bin/bash --norc
+
+LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib/x86_64-linux-gnu"
+# TODO(Brian): Figure out why it segfaults with this enabled, and re-enable it.
+#LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/lib/x86_64-linux-gnu"
+LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib"
+export LD_LIBRARY_PATH
+
+exec \
+ ${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/bin/clang-6.0 \
+ "$@"
diff --git a/tools/cpp/clang_6p0/x86_64-linux-gnu-cpp b/tools/cpp/clang_6p0/x86_64-linux-gnu-cpp
new file mode 100755
index 0000000..d0e1d86
--- /dev/null
+++ b/tools/cpp/clang_6p0/x86_64-linux-gnu-cpp
@@ -0,0 +1,9 @@
+#!/bin/bash --norc
+
+LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib/x86_64-linux-gnu"
+LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib"
+export LD_LIBRARY_PATH
+
+exec -a cpp \
+ ${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/bin/cpp \
+ "$@"
diff --git a/tools/cpp/clang_6p0/x86_64-linux-gnu-gcc b/tools/cpp/clang_6p0/x86_64-linux-gnu-gcc
new file mode 100755
index 0000000..0f822e4
--- /dev/null
+++ b/tools/cpp/clang_6p0/x86_64-linux-gnu-gcc
@@ -0,0 +1,10 @@
+#!/bin/bash --norc
+
+LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib/x86_64-linux-gnu"
+LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib"
+export LD_LIBRARY_PATH
+
+PATH="${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib/gcc/x86_64-linux-gnu/4.9:$PATH" \
+ exec \
+ ${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/bin/gcc \
+ "$@"
diff --git a/tools/cpp/clang_6p0/x86_64-linux-gnu-gcov b/tools/cpp/clang_6p0/x86_64-linux-gnu-gcov
new file mode 100755
index 0000000..37195e5
--- /dev/null
+++ b/tools/cpp/clang_6p0/x86_64-linux-gnu-gcov
@@ -0,0 +1,9 @@
+#!/bin/bash --norc
+
+LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib/x86_64-linux-gnu"
+LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib"
+export LD_LIBRARY_PATH
+
+exec -a gcov \
+ ${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/bin/gcov \
+ "$@"
diff --git a/tools/cpp/clang_6p0/x86_64-linux-gnu-ld b/tools/cpp/clang_6p0/x86_64-linux-gnu-ld
new file mode 100755
index 0000000..95e302f
--- /dev/null
+++ b/tools/cpp/clang_6p0/x86_64-linux-gnu-ld
@@ -0,0 +1,9 @@
+#!/bin/bash --norc
+
+LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib/x86_64-linux-gnu"
+LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib"
+export LD_LIBRARY_PATH
+
+exec -a ld \
+ ${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/bin/ld \
+ "$@"
diff --git a/tools/cpp/clang_6p0/x86_64-linux-gnu-nm b/tools/cpp/clang_6p0/x86_64-linux-gnu-nm
new file mode 100755
index 0000000..4368330
--- /dev/null
+++ b/tools/cpp/clang_6p0/x86_64-linux-gnu-nm
@@ -0,0 +1,9 @@
+#!/bin/bash --norc
+
+LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib/x86_64-linux-gnu"
+LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib"
+export LD_LIBRARY_PATH
+
+exec -a nm \
+ ${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/bin/nm \
+ "$@"
diff --git a/tools/cpp/clang_6p0/x86_64-linux-gnu-objcopy b/tools/cpp/clang_6p0/x86_64-linux-gnu-objcopy
new file mode 100755
index 0000000..d33835b
--- /dev/null
+++ b/tools/cpp/clang_6p0/x86_64-linux-gnu-objcopy
@@ -0,0 +1,9 @@
+#!/bin/bash --norc
+
+LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib/x86_64-linux-gnu"
+LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib"
+export LD_LIBRARY_PATH
+
+exec -a objcopy \
+ ${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/bin/objcopy \
+ "$@"
diff --git a/tools/cpp/clang_6p0/x86_64-linux-gnu-objdump b/tools/cpp/clang_6p0/x86_64-linux-gnu-objdump
new file mode 100755
index 0000000..29e9e37
--- /dev/null
+++ b/tools/cpp/clang_6p0/x86_64-linux-gnu-objdump
@@ -0,0 +1,9 @@
+#!/bin/bash --norc
+
+LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib/x86_64-linux-gnu"
+LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib"
+export LD_LIBRARY_PATH
+
+exec -a objdump \
+ ${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/bin/objdump \
+ "$@"
diff --git a/tools/cpp/clang_6p0/x86_64-linux-gnu-strip b/tools/cpp/clang_6p0/x86_64-linux-gnu-strip
new file mode 100755
index 0000000..34b412a
--- /dev/null
+++ b/tools/cpp/clang_6p0/x86_64-linux-gnu-strip
@@ -0,0 +1,9 @@
+#!/bin/bash --norc
+
+LD_LIBRARY_PATH="${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib/x86_64-linux-gnu"
+LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/lib"
+export LD_LIBRARY_PATH
+
+exec -a strip \
+ ${BAZEL_OUTPUT_ROOT}external/clang_6p0_repo/usr/bin/strip \
+ "$@"
diff --git a/tools/cpp/cortex_m4f_crosstool.pb b/tools/cpp/cortex_m4f_crosstool.pb
index 867e8b0..68114e6 100644
--- a/tools/cpp/cortex_m4f_crosstool.pb
+++ b/tools/cpp/cortex_m4f_crosstool.pb
@@ -84,7 +84,7 @@
action: "c++-header-preprocessing"
action: "c++-module-compile"
flag_group {
- flag: "--std=gnu++1y"
+ flag: "--std=gnu++1z"
flag: "-fno-exceptions"
flag: "-fno-rtti"
}
diff --git a/tools/cpp/linaro_linux_gcc/BUILD b/tools/cpp/linaro_linux_gcc/BUILD
index 4800436..b5ea5a5 100644
--- a/tools/cpp/linaro_linux_gcc/BUILD
+++ b/tools/cpp/linaro_linux_gcc/BUILD
@@ -12,7 +12,7 @@
name = "gcc",
srcs = [
"arm-linux-gnueabihf-gcc",
- "@linaro_linux_gcc_4_9_repo//:gcc",
+ "@linaro_linux_gcc_repo//:gcc",
],
)
@@ -20,7 +20,7 @@
name = "ar",
srcs = [
"arm-linux-gnueabihf-ar",
- "@linaro_linux_gcc_4_9_repo//:ar",
+ "@linaro_linux_gcc_repo//:ar",
],
)
@@ -28,7 +28,7 @@
name = "ld",
srcs = [
"arm-linux-gnueabihf-ld",
- "@linaro_linux_gcc_4_9_repo//:ld",
+ "@linaro_linux_gcc_repo//:ld",
],
)
@@ -36,7 +36,7 @@
name = "nm",
srcs = [
"arm-linux-gnueabihf-nm",
- "@linaro_linux_gcc_4_9_repo//:nm",
+ "@linaro_linux_gcc_repo//:nm",
],
)
@@ -44,7 +44,7 @@
name = "objcopy",
srcs = [
"arm-linux-gnueabihf-objcopy",
- "@linaro_linux_gcc_4_9_repo//:objcopy",
+ "@linaro_linux_gcc_repo//:objcopy",
],
)
@@ -52,7 +52,7 @@
name = "objdump",
srcs = [
"arm-linux-gnueabihf-objdump",
- "@linaro_linux_gcc_4_9_repo//:objdump",
+ "@linaro_linux_gcc_repo//:objdump",
],
)
@@ -60,7 +60,7 @@
name = "strip",
srcs = [
"arm-linux-gnueabihf-strip",
- "@linaro_linux_gcc_4_9_repo//:strip",
+ "@linaro_linux_gcc_repo//:strip",
],
)
@@ -68,7 +68,7 @@
name = "as",
srcs = [
"arm-linux-gnueabihf-as",
- "@linaro_linux_gcc_4_9_repo//:as",
+ "@linaro_linux_gcc_repo//:as",
],
)
diff --git a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-ar b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-ar
index abdb214..7641296 100755
--- a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-ar
+++ b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-ar
@@ -5,5 +5,5 @@
export LD_LIBRARY_PATH
exec -a arm-linux-gnueabihf-ar \
- ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_4_9_repo/bin/arm-linux-gnueabihf-ar \
+ ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_repo/bin/arm-linux-gnueabihf-ar \
"$@"
diff --git a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-as b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-as
index 6a749b4..91ccdfb 100755
--- a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-as
+++ b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-as
@@ -5,5 +5,5 @@
export LD_LIBRARY_PATH
exec -a arm-linux-gnueabihf-as \
- ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_4_9_repo/bin/arm-linux-gnueabihf-as \
+ ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_repo/bin/arm-linux-gnueabihf-as \
"$@"
diff --git a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-cpp b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-cpp
index 7d97f51..d9a0513 100755
--- a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-cpp
+++ b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-cpp
@@ -5,5 +5,5 @@
export LD_LIBRARY_PATH
exec -a arm-linux-gnueabihf-cpp \
- ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_4_9_repo/bin/arm-linux-gnueabihf-cpp \
+ ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_repo/bin/arm-linux-gnueabihf-cpp \
"$@"
diff --git a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-gcc b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-gcc
index 71dd060..820f94c 100755
--- a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-gcc
+++ b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-gcc
@@ -4,7 +4,7 @@
LD_LIBRARY_PATH+=":${BAZEL_OUTPUT_ROOT}external/linaro_49_deps/lib/x86_64-linux-gnu"
export LD_LIBRARY_PATH
-PATH="${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_4_9_repo/libexec/gcc/arm-linux-gnueabihf/4.9.3:$PATH" \
+PATH="${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_repo/libexec/gcc/arm-linux-gnueabihf/7.4.1:$PATH" \
exec \
- ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_4_9_repo/bin/arm-linux-gnueabihf-gcc \
+ ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_repo/bin/arm-linux-gnueabihf-gcc \
"$@"
diff --git a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-gcov b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-gcov
index 5e179c4..adda433 100755
--- a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-gcov
+++ b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-gcov
@@ -5,5 +5,5 @@
export LD_LIBRARY_PATH
exec -a arm-linux-gnueabihf-gcov \
- ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_4_9_repo/bin/arm-linux-gnueabihf-gcov \
+ ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_repo/bin/arm-linux-gnueabihf-gcov \
"$@"
diff --git a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-ld b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-ld
index b4b9fb2..ef83660 100755
--- a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-ld
+++ b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-ld
@@ -5,5 +5,5 @@
export LD_LIBRARY_PATH
exec -a arm-linux-gnueabihf-ld \
- ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_4_9_repo/bin/arm-linux-gnueabihf-ld \
+ ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_repo/bin/arm-linux-gnueabihf-ld \
"$@"
diff --git a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-nm b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-nm
index 514dc67..9f5eddc 100755
--- a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-nm
+++ b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-nm
@@ -5,5 +5,5 @@
export LD_LIBRARY_PATH
exec -a arm-linux-gnueabihf-nm \
- ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_4_9_repo/bin/arm-linux-gnueabihf-nm \
+ ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_repo/bin/arm-linux-gnueabihf-nm \
"$@"
diff --git a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-objcopy b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-objcopy
index d435e92..1d359a0 100755
--- a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-objcopy
+++ b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-objcopy
@@ -5,5 +5,5 @@
export LD_LIBRARY_PATH
exec -a arm-linux-gnueabihf-objcopy \
- ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_4_9_repo/bin/arm-linux-gnueabihf-objcopy \
+ ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_repo/bin/arm-linux-gnueabihf-objcopy \
"$@"
diff --git a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-objdump b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-objdump
index 260d9c0..14a960b 100755
--- a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-objdump
+++ b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-objdump
@@ -5,5 +5,5 @@
export LD_LIBRARY_PATH
exec -a arm-linux-gnueabihf-objdump \
- ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_4_9_repo/bin/arm-linux-gnueabihf-objdump \
+ ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_repo/bin/arm-linux-gnueabihf-objdump \
"$@"
diff --git a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-strip b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-strip
index 2942227..a7389f3 100755
--- a/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-strip
+++ b/tools/cpp/linaro_linux_gcc/arm-linux-gnueabihf-strip
@@ -5,5 +5,5 @@
export LD_LIBRARY_PATH
exec -a arm-linux-gnueabihf-strip \
- ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_4_9_repo/bin/arm-linux-gnueabihf-strip \
+ ${BAZEL_OUTPUT_ROOT}external/linaro_linux_gcc_repo/bin/arm-linux-gnueabihf-strip \
"$@"
diff --git a/tools/cpp/linaro_linux_gcc/clang_bin/clang b/tools/cpp/linaro_linux_gcc/clang_bin/clang
index 99f6067..dcde513 100755
--- a/tools/cpp/linaro_linux_gcc/clang_bin/clang
+++ b/tools/cpp/linaro_linux_gcc/clang_bin/clang
@@ -1,4 +1,4 @@
#!/bin/bash --norc
exec -a "$0" \
- "tools/cpp/clang_3p6/x86_64-linux-gnu-clang-3.6" "$@"
+ "tools/cpp/clang_6p0/x86_64-linux-gnu-clang-6.0" "$@"
diff --git a/tools/cpp/static_crosstool.pb b/tools/cpp/static_crosstool.pb
index 6914825..3435ece 100644
--- a/tools/cpp/static_crosstool.pb
+++ b/tools/cpp/static_crosstool.pb
@@ -38,6 +38,7 @@
}
toolchain {
+ toolchain_identifier: "stub_armeabi-v7a"
abi_version: "armeabi-v7a"
abi_libc_version: "armeabi-v7a"
builtin_sysroot: ""
@@ -54,7 +55,6 @@
target_libc: "armeabi-v7a"
target_cpu: "armeabi-v7a"
target_system_name: "armeabi-v7a"
- toolchain_identifier: "stub_armeabi-v7a"
tool_path { name: "ar" path: "/bin/false" }
tool_path { name: "compat-ld" path: "/bin/false" }
@@ -90,63 +90,63 @@
toolchain_identifier: "k8_linux"
# These paths are relative to //tools/cpp.
- tool_path { name: "ar" path: "clang_3p6/x86_64-linux-gnu-ar" }
- tool_path { name: "compat-ld" path: "clang_3p6/x86_64-linux-gnu-ld" }
- tool_path { name: "cpp" path: "clang_3p6/x86_64-linux-gnu-cpp" }
- tool_path { name: "dwp" path: "clang_3p6/x86_64-linux-gnu-dwp" }
- tool_path { name: "gcc" path: "clang_3p6/x86_64-linux-gnu-clang-3.6" }
- tool_path { name: "gcov" path: "clang_3p6/x86_64-linux-gnu-gcov" }
+ tool_path { name: "ar" path: "clang_6p0/x86_64-linux-gnu-ar" }
+ tool_path { name: "compat-ld" path: "clang_6p0/x86_64-linux-gnu-ld" }
+ tool_path { name: "cpp" path: "clang_6p0/x86_64-linux-gnu-cpp" }
+ tool_path { name: "dwp" path: "clang_6p0/x86_64-linux-gnu-dwp" }
+ tool_path { name: "gcc" path: "clang_6p0/x86_64-linux-gnu-clang-6.0" }
+ tool_path { name: "gcov" path: "clang_6p0/x86_64-linux-gnu-gcov" }
# C(++) compiles invoke the compiler (as that is the one knowing where
# to find libraries), but we provide LD so other rules can invoke the linker.
- tool_path { name: "ld" path: "clang_3p6/x86_64-linux-gnu-ld" }
- tool_path { name: "nm" path: "clang_3p6/x86_64-linux-gnu-nm" }
- tool_path { name: "objcopy" path: "clang_3p6/x86_64-linux-gnu-objcopy" }
+ tool_path { name: "ld" path: "clang_6p0/x86_64-linux-gnu-ld" }
+ tool_path { name: "nm" path: "clang_6p0/x86_64-linux-gnu-nm" }
+ tool_path { name: "objcopy" path: "clang_6p0/x86_64-linux-gnu-objcopy" }
objcopy_embed_flag: "-I"
objcopy_embed_flag: "binary"
- tool_path { name: "objdump" path: "clang_3p6/x86_64-linux-gnu-objdump" }
- tool_path { name: "strip" path: "clang_3p6/x86_64-linux-gnu-strip" }
+ tool_path { name: "objdump" path: "clang_6p0/x86_64-linux-gnu-objdump" }
+ tool_path { name: "strip" path: "clang_6p0/x86_64-linux-gnu-strip" }
linking_mode_flags { mode: DYNAMIC }
- compiler_flag: "--sysroot=external/clang_3p6_repo/"
+ compiler_flag: "--sysroot=external/clang_6p0_repo/"
compiler_flag: "-nostdinc"
compiler_flag: "-isystem"
- compiler_flag: "external/clang_3p6_repo/usr/include",
+ compiler_flag: "external/clang_6p0_repo/usr/include/x86_64-linux-gnu",
compiler_flag: "-isystem"
- compiler_flag: "external/clang_3p6_repo/usr/include/x86_64-linux-gnu",
- compiler_flag: "-isystem"
- compiler_flag: "external/clang_3p6_repo/usr/lib/llvm-3.6/lib/clang/3.6.2/include",
+ compiler_flag: "external/clang_6p0_repo/usr/lib/llvm-6.0/lib/clang/6.0.0/include",
- cxx_flag: "-isystem"
- cxx_flag: "external/clang_3p6_repo/usr/include/c++/4.9"
- cxx_flag: "-isystem"
- cxx_flag: "external/clang_3p6_repo/usr/include/x86_64-linux-gnu/c++/4.9"
- cxx_flag: "-isystem"
- cxx_flag: "external/clang_3p6_repo/usr/include/c++/4.9/backward"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/clang_6p0_repo/usr/include/c++/7.4.0"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/clang_6p0_repo/usr/include/x86_64-linux-gnu/c++/7.4.0"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/clang_6p0_repo/usr/include/c++/7.4.0/backward"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/clang_6p0_repo/usr/include"
# TODO(bazel-team): In theory, the path here ought to exactly match the path
# used by gcc. That works because bazel currently doesn't track files at
# absolute locations and has no remote execution, yet. However, this will need
# to be fixed, maybe with auto-detection?
- cxx_builtin_include_directory: '%package(@clang_3p6_repo//usr)%/include/c++/4.9'
- cxx_builtin_include_directory: '%package(@clang_3p6_repo//usr)%/include/x86_64-linux-gnu/c++/4.9'
- cxx_builtin_include_directory: '%package(@clang_3p6_repo//usr)%/include/c++/4.9/backward'
- cxx_builtin_include_directory: '%package(@clang_3p6_repo//usr)%/local/include'
- cxx_builtin_include_directory: '%package(@clang_3p6_repo//usr)%/lib/llvm-3.6/lib/clang/3.6.2/include'
- cxx_builtin_include_directory: '%package(@clang_3p6_repo//usr)%/include/x86_64-linux-gnu'
- cxx_builtin_include_directory: '%package(@clang_3p6_repo//usr)%/include'
- cxx_builtin_include_directory: '%package(@clang_3p6_repo//usr)%/lib/clang/3.6.2/include'
+ cxx_builtin_include_directory: "%package(@clang_6p0_repo//usr)%/include/c++/7.4.0"
+ cxx_builtin_include_directory: "%package(@clang_6p0_repo//usr)%/include/x86_64-linux-gnu/c++/7.4.0"
+ cxx_builtin_include_directory: "%package(@clang_6p0_repo//usr)%/include/c++/7.4.0/backward"
+ cxx_builtin_include_directory: "%package(@clang_6p0_repo//usr)%/local/include"
+ cxx_builtin_include_directory: "%package(@clang_6p0_repo//usr)%/lib/llvm-6.0/lib/clang/6.0.0/include"
+ cxx_builtin_include_directory: "%package(@clang_6p0_repo//usr)%/include/x86_64-linux-gnu"
+ cxx_flag: "-isystem"
+ cxx_flag: "external/clang_6p0_repo/usr/include"
linker_flag: "-nodefaultlibs"
- linker_flag: "--sysroot=external/clang_3p6_repo/"
+ linker_flag: "--sysroot=external/clang_6p0_repo/"
linker_flag: "-lstdc++"
linker_flag: "-lc"
linker_flag: "-lgcc"
linker_flag: "-lgcc_s"
- linker_flag: "-Bexternal/clang_3p6_repo/usr/bin/"
- linker_flag: "-Ltools/cpp/clang_3p6/clang_more_libs"
- linker_flag: "-Lexternal/clang_3p6/lib/x86_64-linux-gnu"
- linker_flag: "-Lexternal/clang_3p6/usr/lib/x86_64-linux-gnu"
- linker_flag: "-Lexternal/clang_3p6/usr/lib/gcc/x86_64-linux-gnu"
+ linker_flag: "-Bexternal/clang_6p0_repo/usr/bin/"
+ linker_flag: "-Ltools/cpp/clang_6p0/clang_more_libs"
+ linker_flag: "-Lexternal/clang_6p0_repo/lib/x86_64-linux-gnu"
+ linker_flag: "-Lexternal/clang_6p0_repo/usr/lib/x86_64-linux-gnu"
+ linker_flag: "-Lexternal/clang_6p0_repo/usr/lib/gcc/x86_64-linux-gnu"
feature {
name: "opt"
@@ -215,7 +215,7 @@
action: "c++-header-preprocessing"
action: "c++-module-compile"
flag_group {
- flag: "-std=gnu++1y"
+ flag: "-std=gnu++1z"
}
}
flag_set {
@@ -256,6 +256,17 @@
unfiltered_cxx_flag: "-D__TIMESTAMP__=\"redacted\""
unfiltered_cxx_flag: "-D__TIME__=\"redacted\""
+ # C++17 libraries that tend to cause issues in some libraries that we include.
+ unfiltered_cxx_flag: "-Wno-varargs"
+ unfiltered_cxx_flag: "-Wno-null-pointer-arithmetic"
+ # The mismatched-new-delete seems to be a bit overly strict currently
+ # and errors on:
+ # char *p = new char;
+ # delete p;
+ # p = new char[100];
+ # delete[] p;
+ unfiltered_cxx_flag: "-Wno-mismatched-new-delete"
+
# Security hardening on by default.
# Conservative choice; -D_FORTIFY_SOURCE=2 may be unsafe in some cases.
# We need to undef it before redefining it as some distributions now have
@@ -539,12 +550,12 @@
action: "lto-backend"
action: "clif-match"
flag_group {
- flag: "--sysroot=external/arm_frc_linux_gnueabi_repo/arm-frc2019-linux-gnueabi"
+ flag: "--sysroot=external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi"
flag: "-nostdinc"
flag: "-isystem"
- flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2019-linux-gnueabi/usr/lib/gcc/arm-frc2019-linux-gnueabi/6.3.0/include"
+ flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/lib/gcc/arm-frc2020-linux-gnueabi/7.3.0/include"
flag: "-isystem"
- flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2019-linux-gnueabi/usr/lib/gcc/arm-frc2019-linux-gnueabi/6.3.0/include-fixed"
+ flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/lib/gcc/arm-frc2020-linux-gnueabi/7.3.0/include-fixed"
}
}
@@ -566,11 +577,11 @@
action: "c++-module-codegen"
flag_group {
flag: "-isystem"
- flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2019-linux-gnueabi/usr/include/c++/6.3.0"
+ flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0"
flag: "-isystem"
- flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2019-linux-gnueabi/usr/include/c++/6.3.0/arm-frc2019-linux-gnueabi"
+ flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0/arm-frc2020-linux-gnueabi"
flag: "-isystem"
- flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2019-linux-gnueabi/usr/include/c++/6.3.0/backward"
+ flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0/backward"
}
}
@@ -586,7 +597,7 @@
action: "clif-match"
flag_group {
flag: "-isystem"
- flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2019-linux-gnueabi/usr/include"
+ flag: "external/arm_frc_linux_gnueabi_repo/arm-frc2020-linux-gnueabi/usr/include"
flag: "-mfpu=neon"
@@ -623,6 +634,7 @@
flag: "-Wformat=2"
flag: "-Werror"
flag: "-Wunused-local-typedefs"
+ flag: "-Wno-cast-align"
# Keep stack frames for debugging, even in opt mode.
flag: "-fno-omit-frame-pointer"
@@ -674,10 +686,10 @@
# absolute locations and has no remote execution, yet. However, this will need
# to be fixed, maybe with auto-detection?
- cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2019-linux-gnueabi/usr/lib/gcc/arm-frc2019-linux-gnueabi/6.3.0/include)%"
- cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2019-linux-gnueabi/usr/lib/gcc/arm-frc2019-linux-gnueabi/6.3.0/include-fixed)%"
- cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2019-linux-gnueabi/usr/include/c++/6.3.0/arm-frc2019-linux-gnueabi)%"
- cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2019-linux-gnueabi/usr/include/c++/6.3.0/backward)%"
+ cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2020-linux-gnueabi/usr/lib/gcc/arm-frc2020-linux-gnueabi/7.3.0/include)%"
+ cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2020-linux-gnueabi/usr/lib/gcc/arm-frc2020-linux-gnueabi/7.3.0/include-fixed)%"
+ cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0/arm-frc2020-linux-gnueabi)%"
+ cxx_builtin_include_directory: "%package(@arm_frc_linux_gnueabi_repo//arm-frc2020-linux-gnueabi/usr/include/c++/7.3.0/backward)%"
linker_flag: "-lstdc++"
linker_flag: "-Ltools/cpp/arm-frc-linux-gnueabi/libs"
@@ -845,7 +857,7 @@
action: "c++-header-preprocessing"
action: "c++-module-compile"
flag_group {
- flag: "-std=gnu++1y"
+ flag: "-std=gnu++1z"
flag: "-fno-sized-deallocation"
}
}
@@ -904,7 +916,7 @@
}
toolchain {
- abi_version: "clang_3.6"
+ abi_version: "clang_6.0"
abi_libc_version: "glibc_2.19"
builtin_sysroot: ""
compiler: "clang"
@@ -941,49 +953,51 @@
compiler_flag: "-target"
compiler_flag: "armv7a-arm-linux-gnueabif"
- compiler_flag: "--sysroot=external/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/libc"
+ compiler_flag: "--sysroot=external/linaro_linux_gcc_repo/arm-linux-gnueabihf/libc"
compiler_flag: "-mfloat-abi=hard"
compiler_flag: "-mfpu=vfpv3-d16"
compiler_flag: "-nostdinc"
compiler_flag: "-isystem"
- compiler_flag: "/usr/lib/clang/3.6/include"
+ compiler_flag: "/usr/lib/clang/6.0/include"
compiler_flag: "-isystem"
- compiler_flag: "external/linaro_linux_gcc_4_9_repo/lib/gcc/arm-linux-gnueabihf/4.9.3/include"
+ compiler_flag: "external/linaro_linux_gcc_repo/lib/gcc/arm-linux-gnueabihf/7.4.1/include"
compiler_flag: "-isystem"
- compiler_flag: "external/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/libc/usr/include"
+ compiler_flag: "external/linaro_linux_gcc_repo/lib/gcc/arm-linux-gnueabihf/7.4.1/include-fixed"
compiler_flag: "-isystem"
- compiler_flag: "external/linaro_linux_gcc_4_9_repo/lib/gcc/arm-linux-gnueabihf/4.9.3/include-fixed"
- cxx_flag: "-isystem"
- cxx_flag: "external/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/include/c++/4.9.3/arm-linux-gnueabihf"
- cxx_flag: "-isystem"
- cxx_flag: "external/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/include/c++/4.9.3"
- cxx_flag: "-isystem"
- cxx_flag: "external/linaro_linux_gcc_4_9_repo/include/c++/4.9.3/arm-linux-gnueabihf"
- cxx_flag: "-isystem"
- cxx_flag: "external/linaro_linux_gcc_4_9_repo/include/c++/4.9.3"
+ compiler_flag: "external/linaro_linux_gcc_repo/arm-linux-gnueabihf/include/c++/7.4.1/arm-linux-gnueabihf"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/linaro_linux_gcc_repo/arm-linux-gnueabihf/include/c++/7.4.1"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/linaro_linux_gcc_repo/include/c++/7.4.1/arm-linux-gnueabihf"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/linaro_linux_gcc_repo/include/c++/7.4.1"
+ compiler_flag: "-isystem"
+ compiler_flag: "external/linaro_linux_gcc_repo/arm-linux-gnueabihf/libc/usr/include"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//include)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//arm-linux-gnueabihf/libc/usr/include)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//arm-linux-gnueabihf/libc/usr/lib/include)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//arm-linux-gnueabihf/libc/lib/gcc/arm-linux-gnueabihf/4.9.3/include-fixed)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//include)%/c++/4.9.3"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//arm-linux-gnueabihf/libc/lib/gcc/arm-linux-gnueabihf/4.9.3/include)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//arm-linux-gnueabihf/libc/lib/gcc/arm-linux-gnueabihf/4.9.3/include-fixed)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//lib/gcc/arm-linux-gnueabihf/4.9.3/include)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//lib/gcc/arm-linux-gnueabihf/4.9.3/include-fixed)%"
- cxx_builtin_include_directory: "%package(@linaro_linux_gcc_4_9_repo//arm-linux-gnueabihf/include)%/c++/4.9.3"
- cxx_builtin_include_directory: '/usr/lib/clang/3.6/include'
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//include)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//arm-linux-gnueabihf/libc/usr/include)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//arm-linux-gnueabihf/libc/usr/lib/include)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//arm-linux-gnueabihf/libc/lib/gcc/arm-linux-gnueabihf/7.4.1/include-fixed)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//include)%/c++/7.4.1"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//arm-linux-gnueabihf/libc/lib/gcc/arm-linux-gnueabihf/7.4.1/include)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//arm-linux-gnueabihf/libc/lib/gcc/arm-linux-gnueabihf/7.4.1/include-fixed)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//lib/gcc/arm-linux-gnueabihf/7.4.1/include)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//lib/gcc/arm-linux-gnueabihf/7.4.1/include-fixed)%"
+ cxx_builtin_include_directory: "%package(@linaro_linux_gcc_repo//arm-linux-gnueabihf/include)%/c++/7.4.1"
+ cxx_builtin_include_directory: '/usr/lib/clang/6.0/include'
linker_flag: "-target"
linker_flag: "armv7a-arm-linux-gnueabif"
- linker_flag: "--sysroot=external/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/libc"
+ linker_flag: "--sysroot=external/linaro_linux_gcc_repo/arm-linux-gnueabihf/libc"
linker_flag: "-lstdc++"
linker_flag: "-Ltools/cpp/linaro_linux_gcc/clang_more_libs"
- linker_flag: "-Lexternal/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/lib"
- linker_flag: "-Lexternal/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/libc/lib"
- linker_flag: "-Lexternal/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/libc/usr/lib"
- linker_flag: "-Bexternal/linaro_linux_gcc_4_9_repo/arm-linux-gnueabihf/bin"
+ linker_flag: "-Lexternal/linaro_linux_gcc_repo/arm-linux-gnueabihf/lib"
+ linker_flag: "-Lexternal/linaro_linux_gcc_repo/arm-linux-gnueabihf/libc/lib"
+ linker_flag: "-Lexternal/linaro_linux_gcc_repo/arm-linux-gnueabihf/libc/usr/lib"
+ linker_flag: "-Lexternal/linaro_linux_gcc_repo/lib/gcc/arm-linux-gnueabihf/7.4.1"
+ linker_flag: "-Bexternal/linaro_linux_gcc_repo/lib/gcc/arm-linux-gnueabihf/7.4.1"
+ linker_flag: "-Bexternal/linaro_linux_gcc_repo/arm-linux-gnueabihf/bin"
linker_flag: "-Wl,--dynamic-linker=/lib/ld-linux-armhf.so.3"
feature {
@@ -1053,7 +1067,7 @@
action: "c++-header-preprocessing"
action: "c++-module-compile"
flag_group {
- flag: "-std=gnu++1y"
+ flag: "-std=gnu++1z"
}
}
flag_set {
@@ -1088,6 +1102,9 @@
# Make C++ compilation deterministic. Use linkstamping instead of these
# compiler symbols.
unfiltered_cxx_flag: "-Wno-builtin-macro-redefined"
+ unfiltered_cxx_flag: "-Wno-mismatched-new-delete"
+ unfiltered_cxx_flag: "-Wno-null-pointer-arithmetic"
+ unfiltered_cxx_flag: "-Wno-varargs"
unfiltered_cxx_flag: "-D__DATE__=\"redacted\""
unfiltered_cxx_flag: "-D__TIMESTAMP__=\"redacted\""
unfiltered_cxx_flag: "-D__TIME__=\"redacted\""
diff --git a/y2017/control_loops/superstructure/column/column.cc b/y2017/control_loops/superstructure/column/column.cc
index b2e7c5c..f1aea39 100644
--- a/y2017/control_loops/superstructure/column/column.cc
+++ b/y2017/control_loops/superstructure/column/column.cc
@@ -437,6 +437,7 @@
state_ = State::ZEROING_UNINITIALIZED;
// Fall through so we can start the zeroing process immediately.
+ [[fallthrough]];
case State::ZEROING_UNINITIALIZED:
// Set up the profile to be the zeroing profile.
diff --git a/y2018/control_loops/superstructure/arm/arm.cc b/y2018/control_loops/superstructure/arm/arm.cc
index 1f904e2..1c29157 100644
--- a/y2018/control_loops/superstructure/arm/arm.cc
+++ b/y2018/control_loops/superstructure/arm/arm.cc
@@ -138,6 +138,7 @@
} else {
break;
}
+ [[fallthrough]];
case State::DISABLED: {
follower_.SwitchTrajectory(nullptr);
@@ -167,6 +168,7 @@
break;
}
}
+ [[fallthrough]];
case State::GOTO_PATH:
if (outputs_disabled) {
diff --git a/y2018/vision/image_streamer.cc b/y2018/vision/image_streamer.cc
index 4050260..b0c1f86 100644
--- a/y2018/vision/image_streamer.cc
+++ b/y2018/vision/image_streamer.cc
@@ -310,7 +310,7 @@
::std::unique_ptr<CameraStream> camera1;
::std::unique_ptr<CameraStream> camera0(new CameraStream(
params0, "/dev/video0", &tcp_server_, true,
- [&camera0, &camera1, &status_socket, &vision_status]() {
+ [&camera0, &status_socket, &vision_status]() {
vision_status.set_low_frame_count(vision_status.low_frame_count() + 1);
AOS_LOG(INFO, "Got a frame cam0\n");
if (camera0->active()) {
@@ -322,7 +322,7 @@
// params,
// "/dev/v4l/by-path/platform-tegra-xhci-usb-0:3.1:1.0-video-index0",
params1, "/dev/video1", &tcp_server_, false,
- [&camera0, &camera1, &status_socket, &vision_status]() {
+ [&camera1, &status_socket, &vision_status]() {
vision_status.set_high_frame_count(vision_status.high_frame_count() +
1);
AOS_LOG(INFO, "Got a frame cam1\n");
diff --git a/y2019/jevois/BUILD b/y2019/jevois/BUILD
index 0363ced..dc170be 100644
--- a/y2019/jevois/BUILD
+++ b/y2019/jevois/BUILD
@@ -98,7 +98,6 @@
"//aos/logging",
"//aos/util:bitpacking",
"//third_party/GSL",
- "//third_party/optional",
],
)
@@ -116,7 +115,6 @@
":structures_mcu",
"//aos/util:bitpacking",
"//third_party/GSL",
- "//third_party/optional",
],
)
@@ -137,7 +135,6 @@
"//aos/logging",
"//aos/util:bitpacking",
"//third_party/GSL",
- "//third_party/optional",
],
)
@@ -157,7 +154,6 @@
"//aos/containers:sized_array",
"//aos/util:bitpacking",
"//third_party/GSL",
- "//third_party/optional",
],
)
diff --git a/y2019/jevois/spi.cc b/y2019/jevois/spi.cc
index b6a281e..5c504e2 100644
--- a/y2019/jevois/spi.cc
+++ b/y2019/jevois/spi.cc
@@ -183,7 +183,7 @@
return transfer;
}
-tl::optional<TeensyToRoborio> SpiUnpackToRoborio(
+std::optional<TeensyToRoborio> SpiUnpackToRoborio(
gsl::span<const char, spi_transfer_size()> transfer) {
TeensyToRoborio message;
gsl::span<const char> remaining_input = transfer;
@@ -232,7 +232,7 @@
remaining_input = remaining_input.subspan(sizeof(received_crc));
AOS_CHECK(remaining_input.empty());
if (calculated_crc != received_crc) {
- return tl::nullopt;
+ return std::nullopt;
}
}
return message;
@@ -267,7 +267,7 @@
return transfer;
}
-tl::optional<RoborioToTeensy> SpiUnpackToTeensy(
+std::optional<RoborioToTeensy> SpiUnpackToTeensy(
gsl::span<const char, spi_transfer_size()> transfer) {
RoborioToTeensy message;
gsl::span<const char> remaining_input = transfer;
@@ -298,7 +298,7 @@
memcpy(&received_crc, &remaining_input[0], sizeof(received_crc));
remaining_input = remaining_input.subspan(sizeof(received_crc));
if (calculated_crc != received_crc) {
- return tl::nullopt;
+ return std::nullopt;
}
}
return message;
diff --git a/y2019/jevois/spi.h b/y2019/jevois/spi.h
index 7c14a57..8b16d5c 100644
--- a/y2019/jevois/spi.h
+++ b/y2019/jevois/spi.h
@@ -6,7 +6,7 @@
#include <array>
#include "third_party/GSL/include/gsl/gsl"
-#include "third_party/optional/tl/optional.hpp"
+#include <optional>
#include "y2019/jevois/structures.h"
// This file manages serializing and deserializing the various structures for
@@ -27,10 +27,10 @@
using SpiTransfer = std::array<char, spi_transfer_size()>;
SpiTransfer SpiPackToRoborio(const TeensyToRoborio &message);
-tl::optional<TeensyToRoborio> SpiUnpackToRoborio(
+std::optional<TeensyToRoborio> SpiUnpackToRoborio(
gsl::span<const char, spi_transfer_size()> transfer);
SpiTransfer SpiPackToTeensy(const RoborioToTeensy &message);
-tl::optional<RoborioToTeensy> SpiUnpackToTeensy(
+std::optional<RoborioToTeensy> SpiUnpackToTeensy(
gsl::span<const char, spi_transfer_size()> transfer);
} // namespace jevois
diff --git a/y2019/jevois/teensy.cc b/y2019/jevois/teensy.cc
index 58d1570..4da89a8 100644
--- a/y2019/jevois/teensy.cc
+++ b/y2019/jevois/teensy.cc
@@ -1,6 +1,8 @@
#include <inttypes.h>
#include <stdio.h>
+#include <optional>
+
#include "aos/time/time.h"
#include "motors/core/kinetis.h"
#include "motors/core/time.h"
@@ -115,18 +117,18 @@
SpiQueue(const SpiQueue &) = delete;
SpiQueue &operator=(const SpiQueue &) = delete;
- tl::optional<gsl::span<const char, spi_transfer_size()>> Tick() {
+ std::optional<gsl::span<const char, spi_transfer_size()>> Tick() {
{
DisableInterrupts disable_interrupts;
if (waiting_for_enable_ || waiting_for_disable_) {
- return tl::nullopt;
+ return std::nullopt;
}
}
const auto now = aos::monotonic_clock::now();
if (TransferTimedOut(now)) {
printf("SPI timeout with %d left\n", static_cast<int>(to_receive_.size()));
WaitForNextTransfer();
- return tl::nullopt;
+ return std::nullopt;
}
{
DisableInterrupts disable_interrupts;
@@ -138,7 +140,7 @@
if (DeassertHappened(now)) {
printf("CS deasserted with %d left\n", static_cast<int>(to_receive_.size()));
WaitForNextTransfer();
- return tl::nullopt;
+ return std::nullopt;
}
bool all_done;
{
@@ -160,7 +162,7 @@
WaitForNextTransfer();
return received_transfer_;
}
- return tl::nullopt;
+ return std::nullopt;
}
void HandleInterrupt() {
diff --git a/y2019/jevois/uart.cc b/y2019/jevois/uart.cc
index 6ebfe30..b1fdcfb 100644
--- a/y2019/jevois/uart.cc
+++ b/y2019/jevois/uart.cc
@@ -55,12 +55,13 @@
return result;
}
-tl::optional<CameraFrame> UartUnpackToTeensy(gsl::span<const char> encoded_buffer) {
+std::optional<CameraFrame> UartUnpackToTeensy(
+ gsl::span<const char> encoded_buffer) {
std::array<char, uart_to_teensy_size()> buffer;
if (static_cast<size_t>(
CobsDecode<uart_to_teensy_size()>(encoded_buffer, &buffer).size()) !=
buffer.size()) {
- return tl::nullopt;
+ return std::nullopt;
}
CameraFrame message;
@@ -97,7 +98,7 @@
remaining_input = remaining_input.subspan(sizeof(received_crc));
AOS_CHECK(remaining_input.empty());
if (calculated_crc != received_crc) {
- return tl::nullopt;
+ return std::nullopt;
}
}
return message;
@@ -142,13 +143,13 @@
return result;
}
-tl::optional<CameraCalibration> UartUnpackToCamera(
+std::optional<CameraCalibration> UartUnpackToCamera(
gsl::span<const char> encoded_buffer) {
std::array<char, uart_to_camera_size()> buffer;
if (static_cast<size_t>(
CobsDecode<uart_to_camera_size()>(encoded_buffer, &buffer).size()) !=
buffer.size()) {
- return tl::nullopt;
+ return std::nullopt;
}
CameraCalibration message;
@@ -187,7 +188,7 @@
remaining_input = remaining_input.subspan(sizeof(received_crc));
AOS_CHECK(remaining_input.empty());
if (calculated_crc != received_crc) {
- return tl::nullopt;
+ return std::nullopt;
}
}
return message;
diff --git a/y2019/jevois/uart.h b/y2019/jevois/uart.h
index b9e784b..14a46da 100644
--- a/y2019/jevois/uart.h
+++ b/y2019/jevois/uart.h
@@ -3,7 +3,7 @@
#include "aos/containers/sized_array.h"
#include "third_party/GSL/include/gsl/gsl"
-#include "third_party/optional/tl/optional.hpp"
+#include <optional>
#include "y2019/jevois/cobs.h"
#include "y2019/jevois/structures.h"
@@ -30,10 +30,10 @@
aos::SizedArray<char, CobsMaxEncodedSize(uart_to_camera_size())>;
UartToTeensyBuffer UartPackToTeensy(const CameraFrame &message);
-tl::optional<CameraFrame> UartUnpackToTeensy(gsl::span<const char> buffer);
+std::optional<CameraFrame> UartUnpackToTeensy(gsl::span<const char> buffer);
UartToCameraBuffer UartPackToCamera(const CameraCalibration &message);
-tl::optional<CameraCalibration> UartUnpackToCamera(
+std::optional<CameraCalibration> UartUnpackToCamera(
gsl::span<const char> buffer);
} // namespace jevois
diff --git a/y2019/jevois/uart_test.cc b/y2019/jevois/uart_test.cc
index b8f25c1..4f58e73 100644
--- a/y2019/jevois/uart_test.cc
+++ b/y2019/jevois/uart_test.cc
@@ -93,7 +93,7 @@
}
{
UartToTeensyBuffer buffer = UartPackToTeensy(input_message);
- buffer[0] = 255;
+ buffer[0] = -1;
EXPECT_FALSE(UartUnpackToTeensy(buffer));
}
}
@@ -118,7 +118,7 @@
}
{
UartToCameraBuffer buffer = UartPackToCamera(input_message);
- buffer[0] = 255;
+ buffer[0] = -1;
EXPECT_FALSE(UartUnpackToCamera(buffer));
}
}
diff --git a/y2019/vision/global_calibration.cc b/y2019/vision/global_calibration.cc
index ac559b0..e2c4490 100644
--- a/y2019/vision/global_calibration.cc
+++ b/y2019/vision/global_calibration.cc
@@ -198,7 +198,7 @@
const ::aos::vision::Vector<2> target_point = target_value[j];
// Now build up the residual block.
- auto ftor = [template_point, target_point, i](
+ auto ftor = [template_point, target_point](
const double *const intrinsics, const double *const extrinsics,
double *residual) {
const IntrinsicParams intrinsic_params =