diff --git a/CMakeLists.txt b/CMakeLists.txt index 3fe11fcd5f1aab55cd4e23da15782d75ae90156c..879eb9c9bc6039c2c11858e21290ad80d5cd45b2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -86,7 +86,7 @@ if (WITH_FIXSTARS) endif() endif() -if(${CMAKE_VERSION} VERSION_GREATER "3.12.0") +if(${CMAKE_VERSION} VERSION_GREATER "3.12.0") cmake_policy(SET CMP0074 NEW) endif() @@ -111,13 +111,13 @@ if (REALSENSE_LIBRARY) #set_property(TARGET nanogui PROPERTY INTERFACE_INCLUDE_DIRECTORIES ${NANOGUI_EXTRA_INCS}) set_property(TARGET realsense PROPERTY IMPORTED_LOCATION ${REALSENSE_LIBRARY}) message(STATUS "Found Realsense SDK: ${REALSENSE_LIBRARY}") - + if(WIN32) # Find include find_path(REALSENSE_INCLUDE_DIRS - NAMES librealsense2/rs.hpp - PATHS "C:/Program Files/Intel RealSense SDK 2.0" "C:/Program Files (x86)/Intel RealSense SDK 2.0" ${REALSENSE_DIR} - PATH_SUFFIXES include + NAMES librealsense2/rs.hpp + PATHS "C:/Program Files/Intel RealSense SDK 2.0" "C:/Program Files (x86)/Intel RealSense SDK 2.0" ${REALSENSE_DIR} + PATH_SUFFIXES include ) set_property(TARGET realsense PROPERTY INTERFACE_INCLUDE_DIRECTORIES ${REALSENSE_INCLUDE_DIRS}) endif() @@ -149,13 +149,13 @@ if (NVPIPE_LIBRARY) #set_property(TARGET nanogui PROPERTY INTERFACE_INCLUDE_DIRECTORIES ${NANOGUI_EXTRA_INCS}) set_property(TARGET nvpipe PROPERTY IMPORTED_LOCATION ${NVPIPE_LIBRARY}) message(STATUS "Found NvPipe: ${NVPIPE_LIBRARY}") - + if(WIN32) # Find include find_path(NVPIPE_INCLUDE_DIRS - NAMES NvPipe.h - PATHS "C:/Program Files/NvPipe" "C:/Program Files (x86)/NvPipe" ${NVPIPE_DIR} - PATH_SUFFIXES include + NAMES NvPipe.h + PATHS "C:/Program Files/NvPipe" "C:/Program Files (x86)/NvPipe" ${NVPIPE_DIR} + PATH_SUFFIXES include ) set_property(TARGET nvpipe PROPERTY INTERFACE_INCLUDE_DIRECTORIES ${NVPIPE_INCLUDE_DIRS}) endif() @@ -172,13 +172,13 @@ if (PORTAUDIO_LIBRARY) #set_property(TARGET nanogui PROPERTY INTERFACE_INCLUDE_DIRECTORIES ${NANOGUI_EXTRA_INCS}) set_property(TARGET portaudio PROPERTY IMPORTED_LOCATION ${PORTAUDIO_LIBRARY}) message(STATUS "Found Portaudio: ${PORTAUDIO_LIBRARY}") - + if(WIN32) # Find include find_path(PORTAUDIO_INCLUDE_DIRS - NAMES portaudio.h - PATHS "C:/Program Files/Portaudio" "C:/Program Files (x86)/Portaudio" ${PORTAUDIO_DIR} - PATH_SUFFIXES include + NAMES portaudio.h + PATHS "C:/Program Files/Portaudio" "C:/Program Files (x86)/Portaudio" ${PORTAUDIO_DIR} + PATH_SUFFIXES include ) set_property(TARGET portaudio PROPERTY INTERFACE_INCLUDE_DIRECTORIES ${PORTAUDIO_INCLUDE_DIRS}) endif() @@ -204,8 +204,8 @@ include_directories(${CMAKE_CUDA_TOOLKIT_INCLUDE_DIRECTORIES}) # Some kind of fix for nvcc and -pthread problem on Linux set_property(TARGET Threads::Threads - PROPERTY INTERFACE_COMPILE_OPTIONS $<$<COMPILE_LANGUAGE:CUDA>:-Xcompiler -pthread> - "$<$<NOT:$<COMPILE_LANGUAGE:CUDA>>:-pthread>") + PROPERTY INTERFACE_COMPILE_OPTIONS $<$<COMPILE_LANGUAGE:CUDA>:-Xcompiler -pthread> + "$<$<NOT:$<COMPILE_LANGUAGE:CUDA>>:-pthread>") endif () @@ -219,9 +219,9 @@ else() if(WIN32) # Find include find_path(MSGPACK_INCLUDE_DIRS - NAMES msgpack.hpp - PATHS "C:/Program Files/msgpack" "C:/Program Files (x86)/msgpack" - PATH_SUFFIXES include + NAMES msgpack.hpp + PATHS "C:/Program Files/msgpack" "C:/Program Files (x86)/msgpack" + PATH_SUFFIXES include ) endif() # TODO(nick) Create imported target. @@ -324,7 +324,8 @@ if (BUILD_VISION) endif() if (BUILD_CALIBRATION) - find_package( cvsba REQUIRED ) + find_package(Ceres REQUIRED) + add_subdirectory(applications/calibration-ceres) add_subdirectory(applications/calibration-multi) endif() @@ -339,11 +340,11 @@ endif() ### Generate Build Configuration Files ========================================= configure_file(${CMAKE_SOURCE_DIR}/components/common/cpp/include/ftl/config.h.in - ${CMAKE_SOURCE_DIR}/components/common/cpp/include/ftl/config.h + ${CMAKE_SOURCE_DIR}/components/common/cpp/include/ftl/config.h ) configure_file(${CMAKE_SOURCE_DIR}/components/common/cpp/src/config.cpp.in - ${CMAKE_SOURCE_DIR}/components/common/cpp/src/config.cpp + ${CMAKE_SOURCE_DIR}/components/common/cpp/src/config.cpp ) # For issue #17 diff --git a/applications/calibration-ceres/CMakeLists.txt b/applications/calibration-ceres/CMakeLists.txt new file mode 100644 index 0000000000000000000000000000000000000000..f10bc716360aee2bfede7152c6d763192258ae7f --- /dev/null +++ b/applications/calibration-ceres/CMakeLists.txt @@ -0,0 +1,13 @@ +add_executable (ftl-calibration-ceres + src/main.cpp + src/calibration_data.cpp + src/visibility.cpp + src/calibration.cpp + src/optimization.cpp +) + +target_include_directories(ftl-calibration-ceres PRIVATE src/) +target_include_directories(ftl-calibration-ceres PUBLIC ${OpenCV_INCLUDE_DIRS}) +target_link_libraries(ftl-calibration-ceres pthread ftlcommon Eigen3::Eigen ceres) + +add_subdirectory(test) diff --git a/applications/calibration-ceres/src/calibration.cpp b/applications/calibration-ceres/src/calibration.cpp new file mode 100644 index 0000000000000000000000000000000000000000..2c09538e3672742b9874b287994cb3dde8d92e37 --- /dev/null +++ b/applications/calibration-ceres/src/calibration.cpp @@ -0,0 +1,154 @@ +#include "calibration.hpp" +#include "optimization.hpp" + +#include "loguru.hpp" + +#include <opencv2/core.hpp> +#include <opencv2/calib3d.hpp> + +using std::vector; + +using cv::Mat; +using cv::Size; +using cv::Point2d; +using cv::Point3d; +using cv::Vec3d; + +using cv::norm; + +using ftl::calibration::BundleAdjustment; + +using namespace ftl::calibration; + +double ftl::calibration::reprojectionError(const vector<Point2d>& points_im, + const vector<Point3d>& points, const Mat& K, const Mat& D, const Mat& R, + const Mat& t) { + + Mat rvec; + if (R.size() == Size(3, 3)) { cv::Rodrigues(R, rvec); } + else { rvec = R; } + + vector<Point2d> points_reprojected; + cv::projectPoints(points, rvec, t, K, D, points_reprojected); + + double err = 0.0; + int npoints = points_im.size(); + + for (int i = 0; i < npoints; i++) { + err += norm(points_im[i] - points_reprojected[i]); + } + + return err / ((double) npoints); +} + +int ftl::calibration::recoverPose(const Mat &E, const vector<Point2d> &_points1, + const vector<Point2d> &_points2, const Mat &_cameraMatrix1, + const Mat &_cameraMatrix2, Mat &_R, Mat &_t, double distanceThresh, + Mat &triangulatedPoints) { + + Mat cameraMatrix1; + Mat cameraMatrix2; + Mat cameraMatrix; + + Mat points1(_points1.size(), 2, CV_64FC1); + Mat points2(_points2.size(), 2, CV_64FC1); + + CHECK(points1.size() == points2.size()); + + for (size_t i = 0; i < _points1.size(); i++) { + auto p1 = points1.ptr<double>(i); + p1[0] = _points1[i].x; + p1[1] = _points1[i].y; + + auto p2 = points2.ptr<double>(i); + p2[0] = _points2[i].x; + p2[1] = _points2[i].y; + } + + _cameraMatrix1.convertTo(cameraMatrix1, CV_64F); + _cameraMatrix2.convertTo(cameraMatrix2, CV_64F); + cameraMatrix = Mat::eye(Size(3, 3), CV_64FC1); + + double fx1 = cameraMatrix1.at<double>(0,0); + double fy1 = cameraMatrix1.at<double>(1,1); + double cx1 = cameraMatrix1.at<double>(0,2); + double cy1 = cameraMatrix1.at<double>(1,2); + + double fx2 = cameraMatrix2.at<double>(0,0); + double fy2 = cameraMatrix2.at<double>(1,1); + double cx2 = cameraMatrix2.at<double>(0,2); + double cy2 = cameraMatrix2.at<double>(1,2); + + points1.col(0) = (points1.col(0) - cx1) / fx1; + points1.col(1) = (points1.col(1) - cy1) / fy1; + + points2.col(0) = (points2.col(0) - cx2) / fx2; + points2.col(1) = (points2.col(1) - cy2) / fy2; + + // TODO mask + // cameraMatrix = I (for details, see OpenCV's recoverPose() source code) + // modules/calib3d/src/five-point.cpp (461) + // + // https://github.com/opencv/opencv/blob/371bba8f54560b374fbcd47e7e02f015ac4969ad/modules/calib3d/src/five-point.cpp#L461 + + return cv::recoverPose(E, points1, points2, cameraMatrix, _R, _t, distanceThresh, cv::noArray(), triangulatedPoints); +} + +double ftl::calibration::computeExtrinsicParameters(const Mat &K1, const Mat &D1, + const Mat &K2, const Mat &D2, const vector<Point2d> &points1, + const vector<Point2d> &points2, const vector<Point3d> &object_points, Mat &R, + Mat &t, vector<Point3d> &points_out) { + + Mat F = cv::findFundamentalMat(points1, points2, cv::noArray(), cv::FM_8POINT); + Mat E = K2.t() * F * K1; + + Mat points3dh; + // distanceThresh unit? + recoverPose(E, points1, points2, K1, K2, R, t, 1000.0, points3dh); + + points_out.clear(); + points_out.reserve(points3dh.cols); + + for (int col = 0; col < points3dh.cols; col++) { + CHECK(points3dh.at<double>(3, col) != 0); + Point3d p = Point3d(points3dh.at<double>(0, col), + points3dh.at<double>(1, col), + points3dh.at<double>(2, col)) + / points3dh.at<double>(3, col); + points_out.push_back(p); + } + + double s = ftl::calibration::optimizeScale(object_points, points_out); + t = t * s; + + auto params1 = Camera(K1, D1, Mat::eye(3, 3, CV_64FC1), Mat::zeros(3, 1, CV_64FC1)); + auto params2 = Camera(K2, D2, R, t); + + auto ba = BundleAdjustment(); + ba.addCamera(params1); + ba.addCamera(params2); + + for (size_t i = 0; i < points_out.size(); i++) { + ba.addPoint({points1[i], points2[i]}, points_out[i]); + } + + double error_before = ba.reprojectionError(); + + BundleAdjustment::Options options; + options.optimize_intrinsic = false; + options.fix_camera_extrinsic = {0}; + ba.run(options); + + double error_after = ba.reprojectionError(); + + // bundle adjustment didn't work correctly if these checks fail + if (error_before < error_after) { + LOG(WARNING) << "error before < error_after (" << error_before << " <" << error_after << ")"; + } + CHECK((cv::countNonZero(params1.rvec()) == 0) && (cv::countNonZero(params1.tvec()) == 0)); + + R = params2.rmat(); + t = params2.tvec(); + + return sqrt(error_after); +} diff --git a/applications/calibration-ceres/src/calibration.hpp b/applications/calibration-ceres/src/calibration.hpp new file mode 100644 index 0000000000000000000000000000000000000000..5151d1a96766a7d06d044b7818d4105123815421 --- /dev/null +++ b/applications/calibration-ceres/src/calibration.hpp @@ -0,0 +1,106 @@ +#pragma once +#ifndef _FTL_CALIBRATION_HPP_ +#define _FTL_CALIBRATION_HPP_ + +#include <vector> + +#include <opencv2/core/core.hpp> + +namespace ftl { +namespace calibration { + +namespace transform { + +/** + * @brief Get rotation matrix and translation vector from transformation matrix. + * @param T transformation matrix (4x4) or (3x4) + * @param R (out) rotation matrix (3x3) + * @param t (out) translation vector (3x1) + */ +inline void getRotationAndTranslation(const cv::Mat &T, cv::Mat &R, cv::Mat &t) { + T(cv::Rect(0, 0, 3, 3)).copyTo(R); + T(cv::Rect(3, 0, 1, 3)).copyTo(t); +} + +/** + * @brief Inverse transform inplace + * @param R rotation matrix (3x3) + * @param t translation vector (3x1) + */ +inline void inverse(cv::Mat &R, cv::Mat &t) { + cv::Mat t_(3, 1, CV_64FC1); + + t_.at<double>(0) = -R.col(0).dot(t); + t_.at<double>(1) = -R.col(1).dot(t); + t_.at<double>(2) = -R.col(2).dot(t); + + cv::swap(t_, t); + R = R.t(); +} + +/** + * @brief Inverse transform inplace + * @param T transformation matrix (4x4) + */ +inline void inverse(cv::Mat &T) { + cv::Mat rmat; + cv::Mat tvec; + getRotationAndTranslation(T, rmat, tvec); + T = cv::Mat::eye(4, 4, CV_64FC1); + + T(cv::Rect(3, 0, 1, 1)) = -rmat.col(0).dot(tvec); + T(cv::Rect(3, 1, 1, 1)) = -rmat.col(1).dot(tvec); + T(cv::Rect(3, 2, 1, 1)) = -rmat.col(2).dot(tvec); + T(cv::Rect(0, 0, 3, 3)) = rmat.t(); +} + +inline cv::Point3d apply(const cv::Point3d& point, const cv::InputArray& R, const cv::InputArray& t) { + cv::Mat R_ = R.getMat(); + cv::Mat t_ = t.getMat(); + cv::Mat p_new = R_ * cv::Mat(point) + t_; + return cv::Point3d(p_new.at<double>(0), p_new.at<double>(1), p_new.at<double>(2)); +} + +inline cv::Point3d apply(const cv::Point3d& point, const cv::InputArray& T) { + cv::Mat T_ = T.getMat(); + cv::Mat rmat; + cv::Mat tvec; + getRotationAndTranslation(T_, rmat, tvec); + return apply(point, rmat, tvec); +} + +} // namespace transform + +/** + * @brief Calculate MSE reprojection error + */ +double reprojectionError(const std::vector<cv::Point2d>& points_im, + const std::vector<cv::Point3d>& points, const cv::Mat& K, const cv::Mat& D, + const cv::Mat& R, const cv::Mat& t); + +/** + * Same as OpenCV's recoverPose(), but does not assume same intrinsic paramters + * for both cameras. + * + * @todo Write unit tests to check that intrinsic parameters work as expected. + */ +int recoverPose(const cv::Mat &E, const std::vector<cv::Point2d> &_points1, + const std::vector<cv::Point2d> &_points2, const cv::Mat &_cameraMatrix1, + const cv::Mat &_cameraMatrix2, cv::Mat &_R, cv::Mat &_t, + double distanceThresh, cv::Mat &triangulatedPoints); + +/** + * Find camera rotation and translation from first to second camera. Uses + * OpenCV's recoverPose() (with modifications) to estimate camera pose and + * triangulate point locations. Scale is estimated from object_points. 8 point + * algorithm (OpenCV) is used to estimate fundamental matrix at beginning. + */ +double computeExtrinsicParameters(const cv::Mat &K1, const cv::Mat &D1, + const cv::Mat &K2, const cv::Mat &D2, const std::vector<cv::Point2d> &points1, + const std::vector<cv::Point2d> &points2, const std::vector<cv::Point3d> &object_points, + cv::Mat &R, cv::Mat &t, std::vector<cv::Point3d> &points_out); + +} +} + +#endif diff --git a/applications/calibration-ceres/src/calibration_data.cpp b/applications/calibration-ceres/src/calibration_data.cpp new file mode 100644 index 0000000000000000000000000000000000000000..28b77fa8b6b21a07abb8b7e32f46dab0f4363505 --- /dev/null +++ b/applications/calibration-ceres/src/calibration_data.cpp @@ -0,0 +1,212 @@ +#include "calibration_data.hpp" + +#include <opencv2/calib3d.hpp> + +using std::vector; +using std::reference_wrapper; +using std::pair; +using std::make_pair; + +using cv::Mat; +using cv::Point2d; +using cv::Point3d; +using cv::Vec3d; +using cv::Rect; +using cv::Size; + +using ftl::calibration::CalibrationData; +using ftl::calibration::Camera; + +//////////////////////////////////////////////////////////////////////////////// + +void Camera::setRotation(const Mat& R) { + if (((R.size() != Size(3, 3)) && + (R.size() != Size(3, 1)) && + (R.size() != Size(1, 3))) || + (R.type() != CV_64FC1)) { throw std::exception(); } + + Mat rvec; + if (R.size() == cv::Size(3, 3)) { cv::Rodrigues(R, rvec); } + else { rvec = R; } + + data[Parameter::RX] = rvec.at<double>(0); + data[Parameter::RY] = rvec.at<double>(1); + data[Parameter::RZ] = rvec.at<double>(2); +} + +void Camera::setTranslation(const Mat& t) { + if ((t.type() != CV_64FC1) || + (t.size() != cv::Size(1, 3))) { throw std::exception(); } + + data[Parameter::TX] = t.at<double>(0); + data[Parameter::TY] = t.at<double>(1); + data[Parameter::TZ] = t.at<double>(2); +} + + +void Camera::setIntrinsic(const Mat& K) { + if ((K.type() != CV_64FC1) || (K.size() != cv::Size(3, 3))) { + throw std::exception(); + } + + data[Parameter::F] = K.at<double>(0, 0); + data[Parameter::CX] = K.at<double>(0, 2); + data[Parameter::CY] = K.at<double>(1, 2); +} + +void Camera::setDistortion(const Mat& D) { + if ((D.type() != CV_64FC1)) { throw std::exception(); } + switch(D.total()) { + case 12: + /* + data[Parameter::S1] = D.at<double>(8); + data[Parameter::S2] = D.at<double>(9); + data[Parameter::S3] = D.at<double>(10); + data[Parameter::S4] = D.at<double>(11); + */ + [[fallthrough]]; + + case 8: + /* + data[Parameter::K4] = D.at<double>(5); + data[Parameter::K5] = D.at<double>(6); + data[Parameter::K6] = D.at<double>(7); + */ + [[fallthrough]]; + + case 5: + data[Parameter::K3] = D.at<double>(4); + [[fallthrough]]; + + default: + data[Parameter::K1] = D.at<double>(0); + data[Parameter::K2] = D.at<double>(1); + /* + data[Parameter::P1] = D.at<double>(2); + data[Parameter::P2] = D.at<double>(3); + */ + } +} + +Camera::Camera(const Mat &K, const Mat &D, const Mat &R, const Mat &tvec) { + setIntrinsic(K, D); + if (!R.empty()) { setRotation(R); } + if (!tvec.empty()) { setTranslation(tvec); } +} + +Mat Camera::intrinsicMatrix() const { + Mat K = Mat::eye(3, 3, CV_64FC1); + K.at<double>(0, 0) = data[Parameter::F]; + K.at<double>(1, 1) = data[Parameter::F]; + K.at<double>(0, 2) = data[Parameter::CX]; + K.at<double>(1, 2) = data[Parameter::CY]; + return K; +} + +Mat Camera::distortionCoefficients() const { + Mat D; + // OpenCV distortion parameter sizes: 4, 5, 8, 12, 14 + if (_NDISTORTION_PARAMETERS <= 4) { D = Mat::zeros(4, 1, CV_64FC1); } + else if (_NDISTORTION_PARAMETERS <= 5) { D = Mat::zeros(5, 1, CV_64FC1); } + else if (_NDISTORTION_PARAMETERS <= 8) { D = Mat::zeros(8, 1, CV_64FC1); } + else if (_NDISTORTION_PARAMETERS <= 12) { D = Mat::zeros(12, 1, CV_64FC1); } + else if (_NDISTORTION_PARAMETERS <= 14) { D = Mat::zeros(14, 1, CV_64FC1); } + + for (int i = 0; i < _NDISTORTION_PARAMETERS; i++) { + D.at<double>(i) = data[Parameter::DISTORTION+i]; + } + return D; +} + +Mat Camera::rvec() const { + return Mat(Vec3d(data[Parameter::RX], data[Parameter::RY], data[Parameter::RZ])); +} + +Mat Camera::tvec() const { + return Mat(Vec3d(data[Parameter::TX], data[Parameter::TY], data[Parameter::TZ])); +} + +Mat Camera::rmat() const { + Mat R; + cv::Rodrigues(rvec(), R); + return R; +} + +Mat Camera::extrinsicMatrix() const { + Mat T = Mat::eye(4, 4, CV_64FC1); + rmat().copyTo(T(Rect(0, 0, 3, 3))); + tvec().copyTo(T(Rect(3, 0, 1, 3))); + return T; +} + +Mat Camera::extrinsicMatrixInverse() const { + return extrinsicMatrix().inv(); +} + +//////////////////////////////////////////////////////////////////////////////// + +CalibrationData::CalibrationData(int n_cameras) { init(n_cameras); } + +void CalibrationData::init(int n_cameras) { + n_cameras_ = n_cameras; + cameras_ = vector<Camera>(n_cameras); +} + +int CalibrationData::addObservation(const vector<bool> &visible, const vector<Point2d> &observations) { + if ((int) observations.size() != n_cameras_) { throw std::exception(); } + if ((int) visible.size() != n_cameras_) { throw std::exception(); } + visible_.insert(visible_.end(), visible.begin(), visible.end()); + observations_.insert(observations_.end(), observations.begin(), observations.end()); + points_.push_back(Point3d(0.0, 0.0, 0.0)); + + return npoints() - 1; +} + +int CalibrationData::addObservation(const vector<bool> &visible, const vector<Point2d> &observations, const Point3d &point) { + if ((int) observations.size() != n_cameras_) { throw std::exception(); } + if ((int) visible.size() != n_cameras_) { throw std::exception(); } + visible_.insert(visible_.end(), visible.begin(), visible.end()); + observations_.insert(observations_.end(), observations.begin(), observations.end()); + points_.push_back(point); + + return npoints() - 1; +} + +int CalibrationData::addObservations(const vector<bool>& visible, const vector<vector<Point2d>>& observations, const vector<Point3d>& points) { + int retval = -1; + for (size_t i = 0; i < observations.size(); i++) { + retval = addObservation(visible, observations[i], points[i]); + } + return retval; +} + +pair<vector<vector<Point2d>>, vector<reference_wrapper<Point3d>>> CalibrationData::_getVisible(const vector<int> &cameras) { + + int n_points = npoints(); + vector<vector<Point2d>> observations(cameras.size()); + vector<reference_wrapper<Point3d>> points; + + for (size_t k = 0; k < cameras.size(); k++) { + observations[k].reserve(n_points); + } + points.reserve(n_points); + + for (int i = 0; i < n_points; i++) { + if (!isVisible(cameras, i)) { continue; } + + for (size_t k = 0; k < cameras.size(); k++) { + observations[k].push_back(getObservation(cameras[k], i)); + } + points.push_back(getPoint(i)); + } + + return make_pair(observations, points); +} + +vector<vector<Point2d>> CalibrationData::getObservations(const vector<int> &cameras) { + return _getVisible(cameras).first; +} + +vector<reference_wrapper<Point3d>> CalibrationData::getPoints(const vector<int> &cameras) { + return _getVisible(cameras).second; +} diff --git a/applications/calibration-ceres/src/calibration_data.hpp b/applications/calibration-ceres/src/calibration_data.hpp new file mode 100644 index 0000000000000000000000000000000000000000..e98ed3d3c0f86a97e78961eeeb2e102581da9e14 --- /dev/null +++ b/applications/calibration-ceres/src/calibration_data.hpp @@ -0,0 +1,126 @@ +#pragma once +#ifndef _FTL_CALIBRATION_DATA_HPP_ +#define _FTL_CALIBRATION_DATA_HPP_ + +#include <vector> +#include <opencv2/core/core.hpp> + +#define _NDISTORTION_PARAMETERS 3 +#define _NCAMERA_PARAMETERS (9 + _NDISTORTION_PARAMETERS) + +namespace ftl { +namespace calibration { + +/** + * Camera paramters + */ +struct Camera { + Camera() {} + Camera(const cv::Mat& K, const cv::Mat& D, const cv::Mat& R, const cv::Mat& tvec); + + void setRotation(const cv::Mat& R); + void setTranslation(const cv::Mat& tvec); + void setExtrinsic(const cv::Mat& R, const cv::Mat& t) { + setRotation(R); + setTranslation(t); + } + + void setIntrinsic(const cv::Mat& K); + void setDistortion(const cv::Mat &D); + void setIntrinsic(const cv::Mat& K, const cv::Mat& D) { + setIntrinsic(K); + setDistortion(D); + } + + cv::Mat intrinsicMatrix() const; + cv::Mat distortionCoefficients() const; + + cv::Mat rvec() const; + cv::Mat tvec() const; + cv::Mat rmat() const; + + cv::Mat extrinsicMatrix() const; + cv::Mat extrinsicMatrixInverse() const; + + double data[_NCAMERA_PARAMETERS] = {0.0}; + + enum Parameter { + ROTATION = 0, + RX = 0, + RY = 1, + RZ = 2, + TRANSLATION = 3, + TX = 3, + TY = 4, + TZ = 5, + F = 6, + CX = 7, + CY = 8, + DISTORTION = 9, + K1 = 9, + K2 = 10, + K3 = 11 + }; +}; + +class CalibrationData { +public: + CalibrationData() {}; + explicit CalibrationData(int n_cameras); + + void init(int n_cameras); + + int addObservation(const std::vector<bool>& visible, const std::vector<cv::Point2d>& observations); + int addObservation(const std::vector<bool>& visible, const std::vector<cv::Point2d>& observations, const cv::Point3d& point); + + int addObservations(const std::vector<bool>& visible, const std::vector<std::vector<cv::Point2d>>& observations, const std::vector<cv::Point3d>& point); + + void reserve(int n_points) { + points_.reserve(n_points); + points_camera_.reserve(n_points*n_cameras_); + observations_.reserve(n_points*n_cameras_); + visible_.reserve(n_points*n_cameras_); + } + + // TODO: method for save poinst_camera_, could return (for example) + // vector<pair<Point3d*>, vector<Point3d*>> + + std::vector<std::vector<cv::Point2d>> getObservations(const std::vector<int> &cameras); + /* Get points corresponding to observations returned by getObservations() or getObservationsPtr() */ + std::vector<std::reference_wrapper<cv::Point3d>> getPoints(const std::vector<int> &cameras); + + /* get reference/pointer to data */ + inline Camera& getCamera(int k) { return cameras_[k]; } + inline std::vector<Camera>& getCameras() { return cameras_; } + inline cv::Point3d& getPoint(int i) { return points_[i]; } + inline cv::Point2d& getObservation(int k, int i) { return observations_[n_cameras_*i+k]; } + inline bool isVisible(int k, int i) { return visible_[n_cameras_*i+k]; } + inline bool isVisible(const std::vector<int> &cameras, int i) { + for (const auto &k : cameras) { if (!isVisible(k, i)) { return false; } } + return true; + } + + int npoints() const { return points_.size(); } + int ncameras() const { return n_cameras_; } + +private: + std::pair<std::vector<std::vector<cv::Point2d>>, std::vector<std::reference_wrapper<cv::Point3d>>> _getVisible(const std::vector<int> &cameras); + + int n_cameras_; + + // cameras + std::vector<Camera> cameras_; + // points for each observation + std::vector<cv::Point3d> points_; + // points estimated from cameras' observations + std::vector<cv::Point3d> points_camera_; + // observations + std::vector<cv::Point2d> observations_; + // visibility + std::vector<bool> visible_; +}; + +} +} + +#endif diff --git a/applications/calibration-ceres/src/main.cpp b/applications/calibration-ceres/src/main.cpp new file mode 100644 index 0000000000000000000000000000000000000000..087c3283ba303eceab82ac565c626ec0051e403e --- /dev/null +++ b/applications/calibration-ceres/src/main.cpp @@ -0,0 +1,223 @@ +#include "loguru.hpp" + +#include <tuple> + +#include <opencv2/core.hpp> +#include <opencv2/calib3d.hpp> + +#include <opencv2/opencv.hpp> + +#include <ceres/ceres.h> +#include <ceres/rotation.h> + +#include "optimization.hpp" +#include "visibility.hpp" +#include "calibration.hpp" + +using std::string; +using std::vector; +using std::map; +using std::reference_wrapper; + +using std::tuple; +using std::pair; +using std::make_pair; + +using cv::Mat; +using cv::Size; + +using cv::Point2d; +using cv::Point3d; + +using namespace ftl::calibration; + +void loadData( const string &fname, + Visibility &visibility, + CalibrationData &data) { + + vector<Mat> K; + vector<vector<int>> visible; + vector<vector<Point2d>> points; + + cv::FileStorage fs(fname, cv::FileStorage::READ); + + fs["K"] >> K; + fs["points2d"] >> points; + fs["visible"] >> visible; + fs.release(); + + int ncameras = K.size(); + int npoints = points[0].size(); + + visibility.init(ncameras); + data.init(ncameras); + + for (int i = 0; i < npoints; i+= 1) { + + vector<bool> v(ncameras, 0); + vector<Point2d> p(ncameras); + + for (int k = 0; k < ncameras; k++) { + v[k] = visible[k][i]; + p[k] = points[k][i]; + } + + visibility.update(v); + data.addObservation(v, p); + } + + for (size_t i = 1; i < K.size(); i += 2) { + // mask right cameras + visibility.mask(i-1, i); + } + + for (int i = 0; i < ncameras; i++) { + data.getCamera(i).setIntrinsic(K[i]); + } +} + +void calibrate(const string &fname) { + + Visibility visibility; + CalibrationData data; + + loadData(fname, visibility, data); + + // 2x 15cm squares (ArUco tags) 10cm apart + vector<Point3d> object_points = { + Point3d(0.0, 0.0, 0.0), + Point3d(0.15, 0.0, 0.0), + Point3d(0.15, 0.15, 0.0), + Point3d(0.0, 0.15, 0.0), + + Point3d(0.25, 0.0, 0.0), + Point3d(0.40, 0.0, 0.0), + Point3d(0.40, 0.15, 0.0), + Point3d(0.25, 0.15, 0.0) + }; + + int refcamera = 0; + auto path = visibility.shortestPath(refcamera); + + map<pair<int, int>, pair<Mat, Mat>> transformations; + + // Needs better solution which allows simple access to all estimations. + // Required for calculating average coordinates and to know which points + // are missing. + + vector<tuple<int, vector<Point3d>>> points_all; + + transformations[make_pair(refcamera, refcamera)] = + make_pair(Mat::eye(3, 3, CV_64FC1), Mat::zeros(3, 1, CV_64FC1)); + + for (int i = 0; i < data.ncameras(); i++) { + + // Calculate initial translation T from refcam. Visibility graph is + // used to create a chain of transformations from refcam to i. + + int current = refcamera; + if (i == refcamera) { continue; } + + Mat D = Mat::zeros(1, 5, CV_64FC1); + Mat R = Mat::eye(3, 3, CV_64FC1); + Mat t = Mat::zeros(3, 1, CV_64FC1); + + for (const int &to : path.to(i)) { + auto edge = make_pair(current, to); + + if (transformations.find(edge) == transformations.end()) { + Mat R_; + Mat t_; + vector<Point3d> points; + + auto observations = data.getObservations({current, to}); + double err = computeExtrinsicParameters( + data.getCamera(current).intrinsicMatrix(), + data.getCamera(current).distortionCoefficients(), + data.getCamera(to).intrinsicMatrix(), + data.getCamera(to).distortionCoefficients(), + observations[0], observations[1], + object_points, R_, t_, points); + + LOG(INFO) << current << " -> " << to << " (RMS error: " << err << ")"; + + transformations[edge] = make_pair(R_, t_); + points_all.push_back(make_tuple(current, points)); + } + + const auto [R_update, t_update] = transformations[edge]; + + R = R * R_update; + t = R_update * t + t_update; + + current = to; + } + + transformations[make_pair(refcamera, i)] = make_pair(R.clone(), t.clone()); + + data.getCamera(i).setExtrinsic(R, t); + } + + // TODO: see points_all comment + /* + for (auto& [i, points] : points_all) { + + Mat R = data.getCamera(i).rmat(); + Mat t = data.getCamera(i).tvec(); + transform::inverse(R, t); // R, t: refcam -> i + + CHECK(points.size() == points_ref.size()); + + for (size_t j = 0; j < points.size(); j++) { + Point3d &point = points_ref[j]; + + if (point != Point3d(0,0,0)) { + point = (transform::apply(points[j], R, t) + point) / 2.0; + } + else { + point = transform::apply(points[j], R, t); + } + } + } + */ + vector<int> idx; + BundleAdjustment ba; + + ba.addCameras(data.getCameras()); + + vector<bool> visible(data.ncameras()); + vector<Point2d> observations(data.ncameras()); + + int missing = 0; + for (int i = 0; i < data.npoints(); i++) { + for (int j = 0; j < data.ncameras(); j++) { + visible[j] = data.isVisible(j, i); + observations[j] = data.getObservation(j, i); + } + + // TODO: see points_all comment + if (data.getPoint(i) == Point3d(0.,0.,0.)) { + missing++; + continue; + } + + ba.addPoint(visible, observations, data.getPoint(i)); + } + + LOG(INFO) << "missing points: " << missing; + LOG(INFO) << "Initial reprojection error: " << ba.reprojectionError(); + + BundleAdjustment::Options options; + options.verbose = false; + options.optimize_intrinsic = true; + + ba.run(options); + + LOG(INFO) << "Finale reprojection error: " << ba.reprojectionError(); + + // calibration done, updated values in data +} + +int main(int argc, char* argv[]) { + return 0; +} diff --git a/applications/calibration-ceres/src/optimization.cpp b/applications/calibration-ceres/src/optimization.cpp new file mode 100644 index 0000000000000000000000000000000000000000..aafe2a38a960c3349521a0d2f88369cafb0f8597 --- /dev/null +++ b/applications/calibration-ceres/src/optimization.cpp @@ -0,0 +1,445 @@ +#include "optimization.hpp" +#include "calibration.hpp" + +#include "loguru.hpp" + +#include <algorithm> +#include <unordered_set> + +#include <opencv2/calib3d.hpp> +#include <ceres/rotation.h> + +using std::vector; + +using cv::Mat; + +using cv::Point3d; +using cv::Point2d; + +using cv::Rect; + +using ftl::calibration::BundleAdjustment; +using ftl::calibration::Camera; + +//////////////////////////////////////////////////////////////////////////////// + +struct ReprojectionError { + /** + * Reprojection error. + * + * Camera model has _CAMERA_PARAMETERS parameters: + * + * - rotation and translation: rx, ry, rz, tx, ty, tx + * - focal length: f (fx == fy assumed) + * - pricipal point: cx, cy + * - first three radial distortion coefficients: k1, k2, k3 + * + * Camera model documented in + * https://docs.opencv.org/master/d9/d0c/group__calib3d.html + */ + explicit ReprojectionError(double observed_x, double observed_y) + : observed_x(observed_x), observed_y(observed_y) {} + + template <typename T> + bool operator()(const T* const camera, + const T* const point, + T* residuals) const { + + T p[3]; + + // Apply rotation and translation + ceres::AngleAxisRotatePoint(camera + Camera::Parameter::ROTATION, point, p); + + p[0] += camera[Camera::Parameter::TX]; + p[1] += camera[Camera::Parameter::TY]; + p[2] += camera[Camera::Parameter::TZ]; + + T x = T(p[0]) / p[2]; + T y = T(p[1]) / p[2]; + + // Intrinsic parameters + const T& focal = camera[Camera::Parameter::F]; + const T& cx = camera[Camera::Parameter::CX]; + const T& cy = camera[Camera::Parameter::CY]; + + // Distortion parameters k1, k2, k3 + const T& k1 = camera[Camera::Parameter::K1]; + const T& k2 = camera[Camera::Parameter::K2]; + const T& k3 = camera[Camera::Parameter::K3]; + + const T r2 = x*x + y*y; + const T r4 = r2*r2; + const T r6 = r4*r2; + + T distortion = T(1.0) + k1*r2 + k2*r4 + k3*r6; + + // Projected point position + T predicted_x = focal*x*distortion + cx; + T predicted_y = focal*y*distortion + cy; + + // Error: the difference between the predicted and observed position + residuals[0] = predicted_x - T(observed_x); + residuals[1] = predicted_y - T(observed_y); + + return true; + } + + static ceres::CostFunction* Create( const double observed_x, + const double observed_y) { + return (new ceres::AutoDiffCostFunction<ReprojectionError, 2, _NCAMERA_PARAMETERS, 3>( + new ReprojectionError(observed_x, observed_y))); + } + + static ceres::CostFunction* Create( const Point2d &observed) { + return (new ceres::AutoDiffCostFunction<ReprojectionError, 2, _NCAMERA_PARAMETERS, 3>( + new ReprojectionError(observed.x, observed.y))); + } + + double observed_x; + double observed_y; +}; + +struct LengthError { + explicit LengthError(const double d) : d(d) {} + + template <typename T> + bool operator()(const T* const p1, const T* const p2, T* residual) const { + auto x = p1[0] - p2[0]; + auto y = p1[1] - p2[1]; + auto z = p1[2] - p2[2]; + residual[0] = T(d) - sqrt(x*x + y*y + z*z); + + return true; + } + + static ceres::CostFunction* Create(const double d) { + return (new ceres::AutoDiffCostFunction<LengthError, 1, 3, 3>(new LengthError(d))); + } + + double d; +}; + +struct ScaleError { + ScaleError(const double d, const Point3d& p) : d(d), p(p) {} + + template <typename T> + bool operator()(const T* const s, T* residual) const { + auto x = T(p.x) * s[0]; + auto y = T(p.y) * s[0]; + auto z = T(p.z) * s[0]; + residual[0] = T(d) - sqrt(x*x + y*y + z*z); + + return true; + } + + static ceres::CostFunction* Create(const double d, const Point3d p) { + return (new ceres::AutoDiffCostFunction<ScaleError, 1, 1>(new ScaleError(d, p))); + } + + double d; + Point3d p; +}; + +//////////////////////////////////////////////////////////////////////////////// + +double ftl::calibration::optimizeScale(const vector<Point3d> &object_points, vector<Point3d> &points) { + + // use exceptions instead + CHECK(points.size() % object_points.size() == 0); + CHECK(points.size() % 2 == 0); + + // initial scale guess from first two object points + + double f = 0.0; + double m = 0.0; + + for (size_t i = 0; i < points.size(); i += 2) { + const Point3d &p1 = points[i]; + const Point3d &p2 = points[i+1]; + + Point3d p = p1 - p2; + + double x = sqrt(p.x * p.x + p.y * p.y + p.z * p.z); + f = f + 1.0; + m = m + (x - m) / f; + } + + double scale = norm(object_points[0]-object_points[1]) / m; + + // optimize using all distances between points + + vector<double> d; + ceres::Problem problem; + auto loss_function = new ceres::HuberLoss(1.0); + + // use all pairwise distances + for (size_t i = 0; i < object_points.size(); i++) { + for (size_t j = i + 1; j < object_points.size(); j++) { + d.push_back(norm(object_points[i]-object_points[j])); + } + } + + for (size_t i = 0; i < points.size(); i += object_points.size()) { + size_t i_d = 0; + for (size_t i = 0; i < object_points.size(); i++) { + for (size_t j = i + 1; j < object_points.size(); j++) { + auto cost_function = ScaleError::Create(d[i_d++], points[i]-points[j]); + problem.AddResidualBlock(cost_function, loss_function, &scale); + } + } + } + + ceres::Solver::Options options; + ceres::Solver::Summary summary; + ceres::Solve(options, &problem, &summary); + + for (auto &p : points) { p = p * scale; } + return scale; +} + +//////////////////////////////////////////////////////////////////////////////// + +void BundleAdjustment::addCamera(Camera& camera) { + // cameras can't be added after points + if (points_.size() != 0) { throw std::exception(); } + + cameras_.push_back(&camera); +} + +void BundleAdjustment::addCameras(vector<Camera>& cameras) { + for (auto& camera : cameras) { addCamera(camera); } +} + +void BundleAdjustment::addPoint(const vector<bool>& visibility, const vector<Point2d>& observations, Point3d& point) { + if ((observations.size() != visibility.size()) || + (visibility.size() != cameras_.size())) { throw std::exception(); } + + points_.push_back(BundleAdjustment::Point{visibility, observations, reinterpret_cast<double*>(&point)}); +} + +void BundleAdjustment::addPoints(const vector<vector<bool>>& visibility, const vector<vector<Point2d>>& observations, vector<Point3d>& points) { + if ((observations.size() != points.size()) || + (observations.size() != visibility.size())) { throw std::exception(); } + + for (size_t i = 0; i < points.size(); i++) { + addPoint(visibility[i], observations[i], points[i]); + } +} + +void BundleAdjustment::addPoint(const vector<Point2d>& observations, Point3d& point) { + vector<bool> visibility(observations.size(), true); + addPoint(visibility, observations, point); +} +void BundleAdjustment::addPoints(const vector<vector<Point2d>>& observations, std::vector<Point3d>& points) { + if (observations.size() != points.size()) { throw std::exception(); } + for (size_t i = 0; i < points.size(); i++) { + addPoint(observations[i], points[i]); + } +} + +void BundleAdjustment::addConstraintObject(const vector<Point3d> &object_points) { + if (points_.size() % object_points.size() != 0) { throw std::exception(); } + constraints_object_.push_back(BundleAdjustment::ConstraintObject {0, (int) points_.size(), object_points}); +} + +void BundleAdjustment::_buildBundleAdjustmentProblem(ceres::Problem &problem, const BundleAdjustment::Options &options) { + + ceres::LossFunction *loss_function = nullptr; + + if (options.loss == Options::Loss::HUBER) { + loss_function = new ceres::HuberLoss(1.0); + } + else if (options.loss == Options::Loss::CAUCHY) { + loss_function = new ceres::CauchyLoss(1.0); + } + + for (auto point : points_) { + for (size_t i = 0; i < point.observations.size(); i++) { + if (!point.visibility[i]) { continue; } + ceres::CostFunction* cost_function = + ReprojectionError::Create(point.observations[i]); + + problem.AddResidualBlock(cost_function, + loss_function, + getCameraPtr(i), + point.point); + } + } + + // apply options + + vector<int> constant_camera_parameters; + + // extrinsic paramters + if (!options.optimize_motion) { + for (int i = 0; i < 3; i++) { + constant_camera_parameters.push_back(Camera::Parameter::ROTATION + i); + constant_camera_parameters.push_back(Camera::Parameter::TRANSLATION + i); + } + } + + if (!options.fix_distortion) { + LOG(WARNING) << "Optimization of distortion parameters is not supported" + << "and results may contain invalid values."; + } + + // intrinsic parameters + if (!options.optimize_intrinsic || options.fix_focal) { + constant_camera_parameters.push_back(Camera::Parameter::F); + } + if (!options.optimize_intrinsic || options.fix_principal_point) { + constant_camera_parameters.push_back(Camera::Parameter::CX); + constant_camera_parameters.push_back(Camera::Parameter::CY); + } + + if (!options.optimize_intrinsic || options.fix_distortion) { + constant_camera_parameters.push_back(Camera::Parameter::K1); + constant_camera_parameters.push_back(Camera::Parameter::K2); + constant_camera_parameters.push_back(Camera::Parameter::K3); + } + + if (!options.optimize_motion && !options.optimize_intrinsic) { + // do not optimize any camera parameters + for (size_t i = 0; i < cameras_.size(); i++) { + problem.SetParameterBlockConstant(getCameraPtr(i)); + } + } + else { + std::unordered_set<int> fix_extrinsic( + options.fix_camera_extrinsic.begin(), options.fix_camera_extrinsic.end()); + + std::unordered_set<int> fix_intrinsic( + options.fix_camera_extrinsic.begin(), options.fix_camera_extrinsic.end()); + + for (size_t i = 0; i < cameras_.size(); i++) { + std::unordered_set<int> fixed_parameters( + constant_camera_parameters.begin(), + constant_camera_parameters.end()); + + if (fix_extrinsic.find(i) != fix_extrinsic.end()) { + fixed_parameters.insert({ + Camera::Parameter::RX, Camera::Parameter::RY, + Camera::Parameter::RZ, Camera::Parameter::TX, + Camera::Parameter::TY, Camera::Parameter::TZ + }); + } + + if (fix_intrinsic.find(i) != fix_intrinsic.end()) { + fixed_parameters.insert({ + Camera::Parameter::F, Camera::Parameter::CX, + Camera::Parameter::CY + }); + } + + vector<int> params(fixed_parameters.begin(), fixed_parameters.end()); + + if (params.size() == _NCAMERA_PARAMETERS) { + // Ceres crashes if all parameters are set constant using + // SubsetParameterization() + problem.SetParameterBlockConstant(getCameraPtr(i)); + } + else if (params.size() > 0) { + problem.SetParameterization(getCameraPtr(i), + new ceres::SubsetParameterization(_NCAMERA_PARAMETERS, params)); + } + } + } + + if (!options.optmize_structure) { + // do not optimize points + for (auto &point : points_) { problem.SetParameterBlockConstant(point.point); } + } +} + +void BundleAdjustment::_buildLengthProblem(ceres::Problem &problem, const BundleAdjustment::Options &options) { + + for (auto &constraint : constraints_object_) { + int npoints = constraint.object_points.size(); + auto &object_points = constraint.object_points; + + vector<double> d; + for (int i = 0; i < npoints; i++) { + for (int j = i + 1; j < npoints; j++) { + d.push_back(norm(object_points[i]-object_points[j])); + } + } + + for (int p = constraint.idx_start; p < constraint.idx_end; p += npoints) { + size_t i_d = 0; + for (size_t i = 0; i < object_points.size(); i++) { + for (size_t j = i + 1; j < object_points.size(); j++) { + double* p1 = points_[p+i].point; + double* p2 = points_[p+j].point; + + auto cost_function = LengthError::Create(d[i_d++]); + + problem.AddResidualBlock(cost_function, nullptr, p1, p2); + } + } + } + } +} + +void BundleAdjustment::_buildProblem(ceres::Problem &problem, const BundleAdjustment::Options &options) { + + _buildBundleAdjustmentProblem(problem, options); + _buildLengthProblem(problem, options); +} + +void BundleAdjustment::run(const BundleAdjustment::Options &bundle_adjustment_options) { + ceres::Problem problem; + _buildProblem(problem, bundle_adjustment_options); + + ceres::Solver::Options options; + options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY; + options.minimizer_progress_to_stdout = bundle_adjustment_options.verbose; + + if (bundle_adjustment_options.max_iter > 0) { + options.max_num_iterations = bundle_adjustment_options.max_iter; + } + + if (bundle_adjustment_options.num_threads > 0) { + options.num_threads = bundle_adjustment_options.num_threads; + } + + ceres::Solver::Summary summary; + ceres::Solve(options, &problem, &summary); + + if (bundle_adjustment_options.verbose) { + LOG(INFO) << summary.BriefReport(); + } + else { + DLOG(INFO) << summary.BriefReport(); + } +} + +void BundleAdjustment::run() { + BundleAdjustment::Options options; + run(options); +} + +double BundleAdjustment::reprojectionError(int camera) { + vector<Point2d> observations; + vector<Point3d> points; + + observations.reserve(points_.size()); + points.reserve(points_.size()); + + for (const auto& point : points_) { + if (!point.visibility[camera]) { continue; } + observations.push_back(point.observations[camera]); + points.push_back(Point3d(point.point[0], point.point[1], point.point[2])); + } + + auto K = cameras_[camera]->intrinsicMatrix(); + auto rvec = cameras_[camera]->rvec(); + auto tvec = cameras_[camera]->tvec(); + + return ftl::calibration::reprojectionError(observations, points, K, Mat::zeros(1, 5, CV_64FC1), rvec, tvec); +} + +double BundleAdjustment::reprojectionError() { + double error = 0.0; + for (size_t i = 0; i < cameras_.size(); i++) { error += reprojectionError(i); } + return error * (1.0 / (double) cameras_.size()); +} diff --git a/applications/calibration-ceres/src/optimization.hpp b/applications/calibration-ceres/src/optimization.hpp new file mode 100644 index 0000000000000000000000000000000000000000..3b0716c7b6b73ab6cc25bdcc2cedf65b33a5da22 --- /dev/null +++ b/applications/calibration-ceres/src/optimization.hpp @@ -0,0 +1,171 @@ +#pragma once +#ifndef _FTL_OPTIMIZATION_HPP_ +#define _FTL_OPTIMIZATION_HPP_ + +#include "optimization.hpp" +#include "calibration_data.hpp" + +#include <vector> +#include <functional> + +#include <ceres/ceres.h> +#include <opencv2/core/core.hpp> + +// BundleAdjustment uses Point3d instances via double* +static_assert(sizeof(cv::Point2d) == 2*sizeof(double)); +static_assert(std::is_standard_layout<cv::Point2d>()); +static_assert(sizeof(cv::Point3d) == 3*sizeof(double)); +static_assert(std::is_standard_layout<cv::Point3d>()); + +namespace ftl { +namespace calibration { + +static_assert(std::is_standard_layout<Camera>()); + +/** + * @brief Optimize scale. + * @param object Reference object points + * @param points Points in camera coordinates, points.size() % objects.size() == 0 + * @returns Scale factor + * + * Finds scale factor s which minimizes error between relative distances of points. + */ +double optimizeScale(const std::vector<cv::Point3d>& object, std::vector<cv::Point3d>& points); + +/** + * Bundle adjustment. Optimizes parameters (Camera) and structure (Point3d) in + * place. + * + * Parameters of camera model: + * - rotation and translation rx, ry, rz, tx, ty, tz, + * - focal legth and principal point: f, cx, cy + * - radial distortion (first three cofficients): k1, k2, k3 + * + * @note: Distortion paramters are used in reprojection error, but they are + * not not optimized. + */ +class BundleAdjustment { +public: + /** + * Bundle adjustment options. + */ + struct Options { + enum Loss { + SQUARED, + HUBER, + CAUCHY, + }; + + Loss loss = Loss::SQUARED; + + // fix_camera_extrinsic and fix_camera_intrinsic overlap with some of + // the generic options. The more generic setting is always used, the + // specific extrinsic/intrinsic options are applied on top of those. + + // fix extrinsic paramters for cameras + std::vector<int> fix_camera_extrinsic = {}; + + // fix intrinsic paramters for cameras + std::vector<int> fix_camera_intrinsic = {}; + + bool fix_focal = false; + bool fix_principal_point = false; + + /** + * @todo Radial distortion must be monotonic. This constraint is not + * included in the model, thus distortion parameters are always + * fixed. + */ + // distortion coefficient optimization is not supported + bool fix_distortion = true; + + bool optimize_intrinsic = true; + bool optimize_motion = true; + bool optmize_structure = true; + + int num_threads = -1; + int max_iter = -1; + bool verbose = false; + }; + + /** + * Add camera(s) + */ + void addCamera(Camera &K); + void addCameras(std::vector<Camera> &K); + + /** + * @brief Add points + */ + void addPoint(const std::vector<bool>& visibility, const std::vector<cv::Point2d>& observations, cv::Point3d& point); + void addPoints(const std::vector<std::vector<bool>>& visibility, const std::vector<std::vector<cv::Point2d>>& observations, + std::vector<cv::Point3d>& points); + + /** + * @brief Add points, all assumed visible + */ + void addPoint(const std::vector<cv::Point2d>& observations, cv::Point3d& point); + void addPoints(const std::vector<std::vector<cv::Point2d>>& observations, std::vector<cv::Point3d>& points); + + void addConstraintPlane(int group_size); + void addConstraintObject(const std::vector<cv::Point3d>& object_points); + + /** @brief Perform bundle adjustment with custom options. + */ + void run(const BundleAdjustment::Options& options); + + /** @brief Perform bundle adjustment using default options + */ + void run(); + + /** @brief Calculate MSE error (for one camera) + */ + double reprojectionError(int camera); + + /** @brief Calculate MSE error for all cameras + */ + double reprojectionError(); + +protected: + double* getCameraPtr(int i) { return cameras_[i]->data; } + + void _buildProblem(ceres::Problem& problem, const BundleAdjustment::Options& options); + void _buildBundleAdjustmentProblem(ceres::Problem& problem, const BundleAdjustment::Options& options); + void _buildLengthProblem(ceres::Problem& problem, const BundleAdjustment::Options& options); + +private: + // point to be optimized and corresponding observations + struct Point { + std::vector<bool> visibility; + + // pixel coordinates: x, y + std::vector<cv::Point2d> observations; + + // world coordinates: x, y, z + double* point; + }; + + // object shape based constraint for group of points from idx_start to idx_end + struct ConstraintObject { + int idx_start; + int idx_end; + std::vector<cv::Point3d> object_points; + }; + + // planar constraint for group of points from idx_start to idx_end + struct ConstraintPlane { + int idx_start; + int idx_end; + int group_size; + }; + + // camera paramters (as pointers) + std::vector<Camera*> cameras_; + std::vector<BundleAdjustment::Point> points_; + std::vector<BundleAdjustment::ConstraintObject> constraints_object_; +}; + +} +} + +#endif diff --git a/applications/calibration-ceres/src/visibility.cpp b/applications/calibration-ceres/src/visibility.cpp new file mode 100644 index 0000000000000000000000000000000000000000..c941cbb12c96dbdb5166f0af373cc486af938b2d --- /dev/null +++ b/applications/calibration-ceres/src/visibility.cpp @@ -0,0 +1,226 @@ +#include "visibility.hpp" +#include "loguru.hpp" + +#include <limits> +#include <algorithm> +#include <queue> + +using std::vector; +using std::pair; +using std::make_pair; + +using ftl::calibration::Paths; +using ftl::calibration::Visibility; + +template<typename T> +Paths<T>::Paths(const vector<int> &previous, const vector<T> &distances) : + previous_(previous), distances_(distances) {} + +template<typename T> +vector<int> Paths<T>::from(int i) const { + vector<int> path; + + if (previous_[i] == -1) { return {}; } + + int current = i; + do { + if (distance(i) == std::numeric_limits<T>::max()) { return {}; } // no path + + path.push_back(current); + current = previous_[current]; + } + while (previous_[current] != -1); + + return path; +} + +template<typename T> +vector<int> Paths<T>::to(int i) const { + vector<int> path = from(i); + std::reverse(path.begin(), path.end()); + return path; +} + +template<typename T> +T Paths<T>::distance(int i) const { + return distances_[i]; +} + +template<typename T> +bool Paths<T>::connected() const { + for (const auto &distance : distances_) { + if (distance == std::numeric_limits<T>::max()) { return false; } + } + return true; +} + +template<typename T> +std::string Paths<T>::to_string() const { + std::stringstream sb; + + int node = -1; + for (size_t i = 0; i < distances_.size(); i++) { + if (previous_[i] == -1) { + node = i; + break; + } + } + + for (size_t i = 0; i < distances_.size(); i++) { + sb << node; + + for (const auto &p : to(i)) { + sb << " -> " << p; + } + + sb << " (" << distances_[i] << ")\n"; + } + return sb.str(); +} + +template class Paths<int>; +template class Paths<float>; +template class Paths<double>; + +//////////////////////////////////////////////////////////////////////////////// + +template<typename T> +static bool isValidAdjacencyMatrix(const vector<vector<T>> &graph) { + size_t nrows = graph.size(); + for (const auto &col : graph) { + if (nrows != col.size()) { return false; } + } + + for (size_t r = 0; r < nrows; r++) { + for (size_t c = r; c < nrows; c++) { + if (graph[r][c] != graph[c][r]) { + return false; } + } + } + + return true; +} + +template<typename T> +static vector<int> find_neighbors(int i, const vector<vector<T>> &graph) { + vector<int> res; + + for (size_t j = 0; j < graph.size(); j++) { + if (graph[i][j] > 0) { res.push_back(j); } + } + + return res; +} + +template<typename T> +static pair<vector<int>, vector<T>> dijstra_impl(const int i, const vector<vector<T>> &graph) { + // distance, index + std::priority_queue<pair<T, int>, vector<pair<T, int>>, std::greater<pair<T, int>>> pq; + + pq.push(make_pair(0, i)); + + vector<T> distance_path(graph.size(), std::numeric_limits<T>::max()); + vector<int> previous(graph.size(), -1); + + distance_path[i] = 0; + + while(!pq.empty()) { + int current = pq.top().second; + pq.pop(); + + for (int n : find_neighbors(current, graph)) { + T cost = graph[current][n] + distance_path[current]; + if (distance_path[n] > cost) { + distance_path[n] = cost; + pq.push(make_pair(cost, n)); + previous[n] = current; + } + } + } + + return make_pair(previous, distance_path); +} + +template<typename T> +Paths<T> ftl::calibration::dijstra(const int i, const vector<vector<T>> &graph) { + auto tmp = dijstra_impl(i, graph); + return Paths<T>(tmp.first, tmp.second); +} + +template Paths<int> ftl::calibration::dijstra(const int i, const vector<vector<int>> &graph); +template Paths<float> ftl::calibration::dijstra(const int i, const vector<vector<float>> &graph); +template Paths<double> ftl::calibration::dijstra(const int i, const vector<vector<double>> &graph); + +//////////////////////////////////////////////////////////////////////////////// + +Visibility::Visibility(int n_cameras) : + n_cameras_(n_cameras), + graph_(n_cameras, vector(n_cameras, 0)), + mask_(n_cameras, vector(n_cameras, false)) + {} + +Visibility::Visibility(const vector<vector<int>> &graph) : + n_cameras_(graph.size()), + graph_(graph), + mask_(graph.size(), vector(graph.size(), false)) { + + if (!isValidAdjacencyMatrix(graph)) { + throw std::exception(); + } +} + +void Visibility::init(int n_cameras) { + n_cameras_ = n_cameras; + graph_ = vector(n_cameras, vector(n_cameras, 0)); + mask_ = vector(n_cameras, vector(n_cameras, false)); +} + +template<typename T> +void Visibility::update(const vector<T> &add) { + if ((int) add.size() != n_cameras_) { throw std::exception(); } + + for (int i = 0; i < n_cameras_; i++) { + if (!add[i]) { continue; } + + for (int j = 0; j < n_cameras_; j++) { + if (i == j) { continue; } + if (add[j]) { graph_[i][j] += 1; } + } + } +} + +template void Visibility::update(const std::vector<int> &add); +template void Visibility::update(const std::vector<bool> &add); + +void Visibility::mask(int a, int b) { + mask_[a][b] = true; + mask_[b][a] = true; +} + +void Visibility::unmask(int a, int b) { + mask_[a][b] = false; + mask_[b][a] = false; +} + +int Visibility::distance(int a, int b) const { + return graph_[a][b]; +} + +Paths<float> Visibility::shortestPath(int i) const { + if ((i < 0) || (i >= n_cameras_)) { return Paths<float>({}, {}); /* throw exception */} + + vector<vector<float>> graph(n_cameras_, vector<float>(n_cameras_, 0.0f)); + for (int r = 0; r < n_cameras_; r++) { + for (int c = 0; c < n_cameras_; c++) { + float v = graph_[r][c]; + if ((v != 0) && !mask_[r][c]) { graph[r][c] = 1.0f / v; } + } + } + + auto res = dijstra_impl(i, graph); + for (float &distance : res.second) { + distance = 1.0f / distance; + } + + return Paths<float>(res.first, res.second); +} diff --git a/applications/calibration-ceres/src/visibility.hpp b/applications/calibration-ceres/src/visibility.hpp new file mode 100644 index 0000000000000000000000000000000000000000..31c86dca399e194bc81c7342065c75556461175d --- /dev/null +++ b/applications/calibration-ceres/src/visibility.hpp @@ -0,0 +1,91 @@ +#pragma once +#ifndef _FTL_VISIBILITY_HPP_ +#define _FTL_VISIBILITY_HPP_ + +#include <vector> +#include <string> + +namespace ftl { +namespace calibration { + +/** + * @brief Result from Dijkstra's algorithm. + */ +template<typename T> +class Paths { +public: + Paths(const std::vector<int> &previous, const std::vector<T> &distances); + + /** + * @brief Shortest path from node i. Same as to(i) in reverse order + */ + std::vector<int> from(int i) const; + + /** + * @brief Shortest to node i. Same as from(i) in reverse order. + */ + std::vector<int> to(int i) const; + + /** + * @brief Is graph connected, i.e. all nodes are reachable. + */ + bool connected() const; + + /** + * @brief Distance to node i + */ + T distance(int i) const; + + std::string to_string() const; + +private: + std::vector<int> previous_; + std::vector<T> distances_; +}; + +/** + * @brief Dijstra's algorithm: shortest paths from node i. + * @param i node index + * @param graph adjacency matrix + * + * dijstra<int>(), dijstra<float>() and dijstra<double>() defined. + */ +template<typename T> +Paths<T> dijstra(const int i, const std::vector<std::vector<T>> &graph_); + +class Visibility { + public: + Visibility() {}; + explicit Visibility(int n_cameras); + explicit Visibility(const std::vector<std::vector<int>> &graph); + + void init(int n_cameras); + + template<typename T> + void update(const std::vector<T> &add); + + void mask(int a, int b); + void unmask(int a, int b); + + /** + * @brief Find most visibility shortest path to camera i + */ + Paths<float> shortestPath(int i) const; + + protected: + std::vector<int> neighbors(int i) const; + int distance(int a, int b) const; + + private: + + int n_cameras_; + // adjacency matrix + std::vector<std::vector<int>> graph_; + // masked values (mask_[i][j]) are not used + std::vector<std::vector<bool>> mask_; +}; + +} +} + +#endif diff --git a/applications/calibration-ceres/test/CMakeLists.txt b/applications/calibration-ceres/test/CMakeLists.txt new file mode 100644 index 0000000000000000000000000000000000000000..5f76122ccdb66a999d22974cab932b6ec655b5e9 --- /dev/null +++ b/applications/calibration-ceres/test/CMakeLists.txt @@ -0,0 +1,29 @@ + +#add_library(Catch INTERFACE) +#target_include_directories(Catch INTERFACE ${CATCH_INCLUDE_DIR}) + +add_executable(visibility_unit + ./tests.cpp + ../src/visibility.cpp + ./visibility_unit.cpp +) + +target_include_directories(visibility_unit PUBLIC ../src/) +target_link_libraries(visibility_unit pthread dl ftlcommon) + +add_test(VisibilityTest visibility_unit) + +################################################################################ + +add_executable(calibration_unit + ./tests.cpp + ../src/calibration.cpp + ../src/optimization.cpp + ../src/calibration_data.cpp + ./calibration_unit.cpp +) + +target_include_directories(calibration_unit PUBLIC ../src/) +target_link_libraries(calibration_unit pthread dl ftlcommon Eigen3::Eigen ceres) + +add_test(CalibrationTest calibration_unit WORKING_DIRECTORY ${CMAKE_SOURCE_DIR}) diff --git a/applications/calibration-ceres/test/calibration_unit.cpp b/applications/calibration-ceres/test/calibration_unit.cpp new file mode 100644 index 0000000000000000000000000000000000000000..19e24dc9ff2d9dee317a6433024f4f1f93c92ac5 --- /dev/null +++ b/applications/calibration-ceres/test/calibration_unit.cpp @@ -0,0 +1,42 @@ +#include "catch.hpp" + +#include "calibration.hpp" +#include "optimization.hpp" + +#include <vector> +#include <opencv2/core/core.hpp> + +using std::vector; +using std::string; + +using cv::Mat; +using cv::Point3d; +using cv::Point2d; + +using namespace ftl::calibration; + +void loadData(const string &fname,vector<Mat> &K, vector<vector<int>> &visible, + vector<vector<Point2d>> &points) { + + cv::FileStorage fs(fname, cv::FileStorage::READ); + + fs["K"] >> K; + fs["points2d"] >> points; + fs["visible"] >> visible; + fs.release(); +} + +/* TEST_CASE("Camera calibration and parameter optimization", "") { + + vector<Mat> K; + vector<vector<int>> visible; + vector<vector<Point2d>> observations; + + SECTION("Load data") { + loadData("data/points.yml", K, visible, observations); + //REQUIRE(K.size() != 0); + } + + //int ncameras = K.size(); + //int npoints = observations[0].size(); +}*/ diff --git a/applications/calibration-ceres/test/catch.hpp b/applications/calibration-ceres/test/catch.hpp new file mode 100644 index 0000000000000000000000000000000000000000..b1b2411d24885571e21ec4b3653af58c57011c3e --- /dev/null +++ b/applications/calibration-ceres/test/catch.hpp @@ -0,0 +1,14362 @@ +/* + * Catch v2.5.0 + * Generated: 2018-11-26 20:46:12.165372 + * ---------------------------------------------------------- + * This file has been merged from multiple headers. Please don't edit it directly + * Copyright (c) 2018 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 + + +#define CATCH_VERSION_MAJOR 2 +#define CATCH_VERSION_MINOR 5 +#define CATCH_VERSION_PATCH 0 + +#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 push +# pragma clang diagnostic ignored "-Wpadded" +# pragma clang diagnostic ignored "-Wswitch-enum" +# pragma clang diagnostic ignored "-Wcovered-switch-default" +# endif +#elif defined __GNUC__ + // GCC likes to warn on REQUIREs, and we cannot suppress them + // locally because g++'s support for _Pragma is lacking in older, + // still supported, versions +# pragma GCC diagnostic ignored "-Wparentheses" +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wunused-variable" +# 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_ALL_PARTS +#endif + +// In the impl file, we want to have access to all parts of the headers +// Can also be used to sanely support PCHs +#if defined(CATCH_CONFIG_ALL_PARTS) +# define CATCH_CONFIG_EXTERNAL_INTERFACES +# if defined(CATCH_CONFIG_DISABLE_MATCHERS) +# undef CATCH_CONFIG_DISABLE_MATCHERS +# endif +# if !defined(CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER) +# define CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER +# endif +#endif + +#if !defined(CATCH_CONFIG_IMPL_ONLY) +// start catch_platform.h + +#ifdef __APPLE__ +# include <TargetConditionals.h> +# if TARGET_OS_OSX == 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) || defined(__MINGW32__) +# 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_user_interfaces.h + +namespace Catch { + unsigned int rngSeed(); +} + +// end catch_user_interfaces.h +// 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? +// CATCH_CONFIG_DISABLE_EXCEPTIONS : Are exceptions enabled? +// **************** +// 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) || (defined(_MSVC_LANG) && _MSVC_LANG >= 201402L) +# define CATCH_CPP14_OR_GREATER +# endif + +# if (__cplusplus >= 201703L) || (defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) +# define CATCH_CPP17_OR_GREATER +# endif + +#endif + +#if defined(CATCH_CPP17_OR_GREATER) +# define CATCH_INTERNAL_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS +#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" ) + +# define CATCH_INTERNAL_SUPPRESS_UNUSED_WARNINGS \ + _Pragma( "clang diagnostic push" ) \ + _Pragma( "clang diagnostic ignored \"-Wunused-variable\"" ) +# define CATCH_INTERNAL_UNSUPPRESS_UNUSED_WARNINGS \ + _Pragma( "clang diagnostic pop" ) + +#endif // __clang__ + +//////////////////////////////////////////////////////////////////////////////// +// Assume that non-Windows platforms support posix signals by default +#if !defined(CATCH_PLATFORM_WINDOWS) + #define CATCH_INTERNAL_CONFIG_POSIX_SIGNALS +#endif + +//////////////////////////////////////////////////////////////////////////////// +// We know some environments not to support full POSIX signals +#if defined(__CYGWIN__) || defined(__QNX__) || defined(__EMSCRIPTEN__) || defined(__DJGPP__) + #define CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS +#endif + +#ifdef __OS400__ +# define CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS +# define CATCH_CONFIG_COLOUR_NONE +#endif + +//////////////////////////////////////////////////////////////////////////////// +// Android somehow still does not support std::to_string +#if defined(__ANDROID__) +# define CATCH_INTERNAL_CONFIG_NO_CPP11_TO_STRING +#endif + +//////////////////////////////////////////////////////////////////////////////// +// Not all Windows environments support SEH properly +#if defined(__MINGW32__) +# define CATCH_INTERNAL_CONFIG_NO_WINDOWS_SEH +#endif + +//////////////////////////////////////////////////////////////////////////////// +// PS4 +#if defined(__ORBIS__) +# define CATCH_INTERNAL_CONFIG_NO_NEW_CAPTURE +#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 +// some versions of cygwin (most) do not support std::to_string. Use the libstd check. +// https://gcc.gnu.org/onlinedocs/gcc-4.8.2/libstdc++/api/a01053_source.html line 2812-2813 +# if !((__cplusplus >= 201103L) && defined(_GLIBCXX_USE_C99) \ + && !defined(_GLIBCXX_HAVE_BROKEN_VSWPRINTF)) + +# define CATCH_INTERNAL_CONFIG_NO_CPP11_TO_STRING + +# endif +#endif // __CYGWIN__ + +//////////////////////////////////////////////////////////////////////////////// +// Visual C++ +#ifdef _MSC_VER + +# if _MSC_VER >= 1900 // Visual Studio 2015 or newer +# define CATCH_INTERNAL_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS +# endif + +// 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 + +// MSVC traditional preprocessor needs some workaround for __VA_ARGS__ +// _MSVC_TRADITIONAL == 0 means new conformant preprocessor +// _MSVC_TRADITIONAL == 1 means old traditional non-conformant preprocessor +# if !defined(_MSVC_TRADITIONAL) || (defined(_MSVC_TRADITIONAL) && _MSVC_TRADITIONAL) +# define CATCH_INTERNAL_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR +# endif + +#endif // _MSC_VER + +//////////////////////////////////////////////////////////////////////////////// +// Check if we are compiled with -fno-exceptions or equivalent +#if defined(__EXCEPTIONS) || defined(__cpp_exceptions) || defined(_CPPUNWIND) +# define CATCH_INTERNAL_CONFIG_EXCEPTIONS_ENABLED +#endif + +//////////////////////////////////////////////////////////////////////////////// +// DJGPP +#ifdef __DJGPP__ +# define CATCH_INTERNAL_CONFIG_NO_WCHAR +#endif // __DJGPP__ + +//////////////////////////////////////////////////////////////////////////////// +// Embarcadero C++Build +#if defined(__BORLANDC__) + #define CATCH_INTERNAL_CONFIG_POLYFILL_ISNAN +#endif + +//////////////////////////////////////////////////////////////////////////////// + +// 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 + +//////////////////////////////////////////////////////////////////////////////// +// Check if string_view is available and usable +// The check is split apart to work around v140 (VS2015) preprocessor issue... +#if defined(__has_include) +#if __has_include(<string_view>) && defined(CATCH_CPP17_OR_GREATER) +# define CATCH_INTERNAL_CONFIG_CPP17_STRING_VIEW +#endif +#endif + +//////////////////////////////////////////////////////////////////////////////// +// Check if variant is available and usable +#if defined(__has_include) +# if __has_include(<variant>) && defined(CATCH_CPP17_OR_GREATER) +# if defined(__clang__) && (__clang_major__ < 8) + // work around clang bug with libstdc++ https://bugs.llvm.org/show_bug.cgi?id=31852 + // fix should be in clang 8, workaround in libstdc++ 8.2 +# include <ciso646> +# if defined(__GLIBCXX__) && defined(_GLIBCXX_RELEASE) && (_GLIBCXX_RELEASE < 9) +# define CATCH_CONFIG_NO_CPP17_VARIANT +# else +# define CATCH_INTERNAL_CONFIG_CPP17_VARIANT +# endif // defined(__GLIBCXX__) && defined(_GLIBCXX_RELEASE) && (_GLIBCXX_RELEASE < 9) +# endif // defined(__clang__) && (__clang_major__ < 8) +# endif // __has_include(<variant>) && defined(CATCH_CPP17_OR_GREATER) +#endif // __has_include + +#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) && !defined(CATCH_INTERNAL_CONFIG_NO_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_POSIX_SIGNALS) && !defined(CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS) && !defined(CATCH_CONFIG_NO_POSIX_SIGNALS) && !defined(CATCH_CONFIG_POSIX_SIGNALS) +# define CATCH_CONFIG_POSIX_SIGNALS +#endif +// This is set by default, because we assume that compilers with no wchar_t support are just rare exceptions. +#if !defined(CATCH_INTERNAL_CONFIG_NO_WCHAR) && !defined(CATCH_CONFIG_NO_WCHAR) && !defined(CATCH_CONFIG_WCHAR) +# define CATCH_CONFIG_WCHAR +#endif + +#if !defined(CATCH_INTERNAL_CONFIG_NO_CPP11_TO_STRING) && !defined(CATCH_CONFIG_NO_CPP11_TO_STRING) && !defined(CATCH_CONFIG_CPP11_TO_STRING) +# define CATCH_CONFIG_CPP11_TO_STRING +#endif + +#if defined(CATCH_INTERNAL_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS) && !defined(CATCH_CONFIG_NO_CPP17_UNCAUGHT_EXCEPTIONS) && !defined(CATCH_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS) +# define CATCH_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS +#endif + +#if defined(CATCH_INTERNAL_CONFIG_CPP17_STRING_VIEW) && !defined(CATCH_CONFIG_NO_CPP17_STRING_VIEW) && !defined(CATCH_CONFIG_CPP17_STRING_VIEW) +# define CATCH_CONFIG_CPP17_STRING_VIEW +#endif + +#if defined(CATCH_INTERNAL_CONFIG_CPP17_VARIANT) && !defined(CATCH_CONFIG_NO_CPP17_VARIANT) && !defined(CATCH_CONFIG_CPP17_VARIANT) +# define CATCH_CONFIG_CPP17_VARIANT +#endif + +#if defined(CATCH_CONFIG_EXPERIMENTAL_REDIRECT) +# define CATCH_INTERNAL_CONFIG_NEW_CAPTURE +#endif + +#if defined(CATCH_INTERNAL_CONFIG_NEW_CAPTURE) && !defined(CATCH_INTERNAL_CONFIG_NO_NEW_CAPTURE) && !defined(CATCH_CONFIG_NO_NEW_CAPTURE) && !defined(CATCH_CONFIG_NEW_CAPTURE) +# define CATCH_CONFIG_NEW_CAPTURE +#endif + +#if !defined(CATCH_INTERNAL_CONFIG_EXCEPTIONS_ENABLED) && !defined(CATCH_CONFIG_DISABLE_EXCEPTIONS) +# define CATCH_CONFIG_DISABLE_EXCEPTIONS +#endif + +#if defined(CATCH_INTERNAL_CONFIG_POLYFILL_ISNAN) && !defined(CATCH_CONFIG_NO_POLYFILL_ISNAN) && !defined(CATCH_CONFIG_POLYFILL_ISNAN) +# define CATCH_CONFIG_POLYFILL_ISNAN +#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 +#if !defined(CATCH_INTERNAL_SUPPRESS_UNUSED_WARNINGS) +# define CATCH_INTERNAL_SUPPRESS_UNUSED_WARNINGS +# define CATCH_INTERNAL_UNSUPPRESS_UNUSED_WARNINGS +#endif + +#if defined(CATCH_CONFIG_DISABLE_EXCEPTIONS) +#define CATCH_TRY if ((true)) +#define CATCH_CATCH_ALL if ((false)) +#define CATCH_CATCH_ANON(type) if ((false)) +#else +#define CATCH_TRY try +#define CATCH_CATCH_ALL catch (...) +#define CATCH_CATCH_ANON(type) catch (type) +#endif + +#if defined(CATCH_INTERNAL_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR) && !defined(CATCH_CONFIG_NO_TRADITIONAL_MSVC_PREPROCESSOR) && !defined(CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR) +#define CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR +#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> + +// 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 { + + 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 + : file( _file ), + line( _line ) + {} + + 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 ); + + // Bring in operator<< from global namespace into Catch namespace + // This is necessary because the overload of operator<< above makes + // lookup stop at namespace Catch + using ::operator<<; + + // 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 ) \ + CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \ + namespace{ Catch::RegistrarForTagAliases INTERNAL_CATCH_UNIQUE_NAME( AutoRegisterTagAlias )( alias, spec, CATCH_INTERNAL_LINEINFO ); } \ + CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS + +// 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 { + public: + using size_type = std::size_t; + + private: + friend struct StringRefTestAccess; + + char const* m_start; + size_type m_size; + + char* m_data = nullptr; + + void takeOwnership(); + + static constexpr char const* const s_empty = ""; + + public: // construction/ assignment + StringRef() noexcept + : StringRef( s_empty, 0 ) + {} + + StringRef( StringRef const& other ) noexcept + : m_start( other.m_start ), + m_size( other.m_size ) + {} + + StringRef( StringRef&& other ) noexcept + : m_start( other.m_start ), + m_size( other.m_size ), + m_data( other.m_data ) + { + other.m_data = nullptr; + } + + StringRef( char const* rawChars ) noexcept; + + StringRef( char const* rawChars, size_type size ) noexcept + : m_start( rawChars ), + m_size( size ) + {} + + StringRef( std::string const& stdString ) noexcept + : m_start( stdString.c_str() ), + m_size( stdString.size() ) + {} + + ~StringRef() noexcept { + delete[] m_data; + } + + auto operator = ( StringRef const &other ) noexcept -> StringRef& { + delete[] m_data; + m_data = nullptr; + m_start = other.m_start; + m_size = other.m_size; + return *this; + } + + 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 { + return m_size == 0; + } + auto size() const noexcept -> size_type { + return m_size; + } + + 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; + + // Returns the current start pointer. + // Note that the pointer can change when if the StringRef is a substring + auto currentData() const noexcept -> char const*; + + private: // ownership queries - may not be consistent between calls + auto isOwned() const noexcept -> bool; + auto isSubstring() const noexcept -> bool; + }; + + 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::string& lhs, StringRef const& sr ) -> std::string&; + auto operator << ( std::ostream& os, StringRef const& sr ) -> std::ostream&; + + inline auto operator "" _sr( char const* rawChars, std::size_t size ) noexcept -> StringRef { + return StringRef( rawChars, size ); + } + +} // namespace Catch + +inline auto operator "" _catch_sr( char const* rawChars, std::size_t size ) noexcept -> Catch::StringRef { + return Catch::StringRef( rawChars, size ); +} + +// end catch_stringref.h +// start catch_type_traits.hpp + + +namespace Catch{ + +#ifdef CATCH_CPP17_OR_GREATER + template <typename...> + inline constexpr auto is_unique = std::true_type{}; + + template <typename T, typename... Rest> + inline constexpr auto is_unique<T, Rest...> = std::bool_constant< + (!std::is_same_v<T, Rest> && ...) && is_unique<Rest...> + >{}; +#else + +template <typename...> +struct is_unique : std::true_type{}; + +template <typename T0, typename T1, typename... Rest> +struct is_unique<T0, T1, Rest...> : std::integral_constant +<bool, + !std::is_same<T0, T1>::value + && is_unique<T0, Rest...>::value + && is_unique<T1, Rest...>::value +>{}; + +#endif +} + +// end catch_type_traits.hpp +// start catch_preprocessor.hpp + + +#define CATCH_RECURSION_LEVEL0(...) __VA_ARGS__ +#define CATCH_RECURSION_LEVEL1(...) CATCH_RECURSION_LEVEL0(CATCH_RECURSION_LEVEL0(CATCH_RECURSION_LEVEL0(__VA_ARGS__))) +#define CATCH_RECURSION_LEVEL2(...) CATCH_RECURSION_LEVEL1(CATCH_RECURSION_LEVEL1(CATCH_RECURSION_LEVEL1(__VA_ARGS__))) +#define CATCH_RECURSION_LEVEL3(...) CATCH_RECURSION_LEVEL2(CATCH_RECURSION_LEVEL2(CATCH_RECURSION_LEVEL2(__VA_ARGS__))) +#define CATCH_RECURSION_LEVEL4(...) CATCH_RECURSION_LEVEL3(CATCH_RECURSION_LEVEL3(CATCH_RECURSION_LEVEL3(__VA_ARGS__))) +#define CATCH_RECURSION_LEVEL5(...) CATCH_RECURSION_LEVEL4(CATCH_RECURSION_LEVEL4(CATCH_RECURSION_LEVEL4(__VA_ARGS__))) + +#ifdef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR +#define INTERNAL_CATCH_EXPAND_VARGS(...) __VA_ARGS__ +// MSVC needs more evaluations +#define CATCH_RECURSION_LEVEL6(...) CATCH_RECURSION_LEVEL5(CATCH_RECURSION_LEVEL5(CATCH_RECURSION_LEVEL5(__VA_ARGS__))) +#define CATCH_RECURSE(...) CATCH_RECURSION_LEVEL6(CATCH_RECURSION_LEVEL6(__VA_ARGS__)) +#else +#define CATCH_RECURSE(...) CATCH_RECURSION_LEVEL5(__VA_ARGS__) +#endif + +#define CATCH_REC_END(...) +#define CATCH_REC_OUT + +#define CATCH_EMPTY() +#define CATCH_DEFER(id) id CATCH_EMPTY() + +#define CATCH_REC_GET_END2() 0, CATCH_REC_END +#define CATCH_REC_GET_END1(...) CATCH_REC_GET_END2 +#define CATCH_REC_GET_END(...) CATCH_REC_GET_END1 +#define CATCH_REC_NEXT0(test, next, ...) next CATCH_REC_OUT +#define CATCH_REC_NEXT1(test, next) CATCH_DEFER ( CATCH_REC_NEXT0 ) ( test, next, 0) +#define CATCH_REC_NEXT(test, next) CATCH_REC_NEXT1(CATCH_REC_GET_END test, next) + +#define CATCH_REC_LIST0(f, x, peek, ...) , f(x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST1) ) ( f, peek, __VA_ARGS__ ) +#define CATCH_REC_LIST1(f, x, peek, ...) , f(x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST0) ) ( f, peek, __VA_ARGS__ ) +#define CATCH_REC_LIST2(f, x, peek, ...) f(x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST1) ) ( f, peek, __VA_ARGS__ ) + +#define CATCH_REC_LIST0_UD(f, userdata, x, peek, ...) , f(userdata, x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST1_UD) ) ( f, userdata, peek, __VA_ARGS__ ) +#define CATCH_REC_LIST1_UD(f, userdata, x, peek, ...) , f(userdata, x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST0_UD) ) ( f, userdata, peek, __VA_ARGS__ ) +#define CATCH_REC_LIST2_UD(f, userdata, x, peek, ...) f(userdata, x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST1_UD) ) ( f, userdata, peek, __VA_ARGS__ ) + +// Applies the function macro `f` to each of the remaining parameters, inserts commas between the results, +// and passes userdata as the first parameter to each invocation, +// e.g. CATCH_REC_LIST_UD(f, x, a, b, c) evaluates to f(x, a), f(x, b), f(x, c) +#define CATCH_REC_LIST_UD(f, userdata, ...) CATCH_RECURSE(CATCH_REC_LIST2_UD(f, userdata, __VA_ARGS__, ()()(), ()()(), ()()(), 0)) + +#define CATCH_REC_LIST(f, ...) CATCH_RECURSE(CATCH_REC_LIST2(f, __VA_ARGS__, ()()(), ()()(), ()()(), 0)) + +#define INTERNAL_CATCH_EXPAND1(param) INTERNAL_CATCH_EXPAND2(param) +#define INTERNAL_CATCH_EXPAND2(...) INTERNAL_CATCH_NO## __VA_ARGS__ +#define INTERNAL_CATCH_DEF(...) INTERNAL_CATCH_DEF __VA_ARGS__ +#define INTERNAL_CATCH_NOINTERNAL_CATCH_DEF + +#define INTERNAL_CATCH_REMOVE_PARENS(...) INTERNAL_CATCH_EXPAND1(INTERNAL_CATCH_DEF __VA_ARGS__) + +#define INTERNAL_CATCH_TEMPLATE_UNIQUE_NAME2(Name, ...) INTERNAL_CATCH_TEMPLATE_UNIQUE_NAME3(Name, __VA_ARGS__) +#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR +#define INTERNAL_CATCH_TEMPLATE_UNIQUE_NAME3(Name,...) Name " - " #__VA_ARGS__ +#define INTERNAL_CATCH_TEMPLATE_UNIQUE_NAME(Name,...) INTERNAL_CATCH_TEMPLATE_UNIQUE_NAME2(Name, INTERNAL_CATCH_REMOVE_PARENS(__VA_ARGS__)) +#else +// MSVC is adding extra space and needs more calls to properly remove () +#define INTERNAL_CATCH_TEMPLATE_UNIQUE_NAME3(Name,...) Name " -" #__VA_ARGS__ +#define INTERNAL_CATCH_TEMPLATE_UNIQUE_NAME1(Name, ...) INTERNAL_CATCH_TEMPLATE_UNIQUE_NAME2(Name, __VA_ARGS__) +#define INTERNAL_CATCH_TEMPLATE_UNIQUE_NAME(Name, ...) INTERNAL_CATCH_TEMPLATE_UNIQUE_NAME1(Name, INTERNAL_CATCH_EXPAND_VARGS(INTERNAL_CATCH_REMOVE_PARENS(__VA_ARGS__))) +#endif + +// end catch_preprocessor.hpp +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 const& name_ = StringRef(), StringRef const& tags_ = StringRef() ) noexcept; + StringRef name; + StringRef tags; +}; + +struct AutoReg : NonCopyable { + AutoReg( ITestInvoker* invoker, SourceLineInfo const& lineInfo, StringRef const& 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 : INTERNAL_CATCH_REMOVE_PARENS(ClassName) { \ + void test(); \ + }; \ + } \ + void TestName::test() + #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION( TestName, ... ) \ + template<typename TestType> \ + static void TestName() + #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION( TestName, ClassName, ... ) \ + namespace{ \ + template<typename TestType> \ + struct TestName : INTERNAL_CATCH_REMOVE_PARENS(ClassName <TestType>) { \ + void test(); \ + }; \ + } \ + template<typename TestType> \ + 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::StringRef(), 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 : INTERNAL_CATCH_REMOVE_PARENS(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::StringRef(), Catch::NameAndTags{ __VA_ARGS__ } ); /* NOLINT */ \ + CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS + + /////////////////////////////////////////////////////////////////////////////// + #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_2(TestName, TestFunc, Name, Tags, ... )\ + CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \ + template<typename TestType> \ + static void TestFunc();\ + namespace {\ + template<typename...Types> \ + struct TestName{\ + template<typename...Ts> \ + TestName(Ts...names){\ + CATCH_INTERNAL_CHECK_UNIQUE_TYPES(CATCH_REC_LIST(INTERNAL_CATCH_REMOVE_PARENS, __VA_ARGS__)) \ + using expander = int[];\ + (void)expander{(Catch::AutoReg( Catch::makeTestInvoker( &TestFunc<Types> ), CATCH_INTERNAL_LINEINFO, Catch::StringRef(), Catch::NameAndTags{ names, Tags } ), 0)... };/* NOLINT */ \ + }\ + };\ + INTERNAL_CATCH_TEMPLATE_REGISTRY_INITIATE(TestName, Name, __VA_ARGS__) \ + }\ + CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS \ + template<typename TestType> \ + static void TestFunc() + +#if defined(CATCH_CPP17_OR_GREATER) +#define CATCH_INTERNAL_CHECK_UNIQUE_TYPES(...) static_assert(Catch::is_unique<__VA_ARGS__>,"Duplicate type detected in declaration of template test case"); +#else +#define CATCH_INTERNAL_CHECK_UNIQUE_TYPES(...) static_assert(Catch::is_unique<__VA_ARGS__>::value,"Duplicate type detected in declaration of template test case"); +#endif + +#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR + #define INTERNAL_CATCH_TEMPLATE_TEST_CASE(Name, Tags, ...) \ + INTERNAL_CATCH_TEMPLATE_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, __VA_ARGS__ ) +#else + #define INTERNAL_CATCH_TEMPLATE_TEST_CASE(Name, Tags, ...) \ + INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____F_U_N_C____ ), Name, Tags, __VA_ARGS__ ) ) +#endif + + #define INTERNAL_CATCH_TEMPLATE_REGISTRY_INITIATE(TestName, Name, ...)\ + static int INTERNAL_CATCH_UNIQUE_NAME( globalRegistrar ) = [](){\ + TestName<CATCH_REC_LIST(INTERNAL_CATCH_REMOVE_PARENS, __VA_ARGS__)>(CATCH_REC_LIST_UD(INTERNAL_CATCH_TEMPLATE_UNIQUE_NAME,Name, __VA_ARGS__));\ + return 0;\ + }(); + + #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( TestNameClass, TestName, ClassName, Name, Tags, ... ) \ + CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \ + namespace{ \ + template<typename TestType> \ + struct TestName : INTERNAL_CATCH_REMOVE_PARENS(ClassName <TestType>) { \ + void test();\ + };\ + template<typename...Types> \ + struct TestNameClass{\ + template<typename...Ts> \ + TestNameClass(Ts...names){\ + CATCH_INTERNAL_CHECK_UNIQUE_TYPES(CATCH_REC_LIST(INTERNAL_CATCH_REMOVE_PARENS, __VA_ARGS__)) \ + using expander = int[];\ + (void)expander{(Catch::AutoReg( Catch::makeTestInvoker( &TestName<Types>::test ), CATCH_INTERNAL_LINEINFO, #ClassName, Catch::NameAndTags{ names, Tags } ), 0)... };/* NOLINT */ \ + }\ + };\ + INTERNAL_CATCH_TEMPLATE_REGISTRY_INITIATE(TestNameClass, Name, __VA_ARGS__)\ + }\ + CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS\ + template<typename TestType> \ + void TestName<TestType>::test() + +#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR + #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD( ClassName, Name, Tags,... ) \ + INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____C_L_A_S_S____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ) , ClassName, Name, Tags, __VA_ARGS__ ) +#else + #define INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD( ClassName, Name, Tags,... ) \ + INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____C_L_A_S_S____ ), INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ) , ClassName, Name, Tags, __VA_ARGS__ ) ) +#endif + +// end catch_test_registry.h +// start catch_capture.hpp + +// start catch_assertionhandler.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 ); + inline bool isFalseTest( int flags ) { return ( flags & ResultDisposition::FalseTest ) != 0; } + 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 +// start catch_decomposer.h + +// start catch_tostring.h + +#include <vector> +#include <cstddef> +#include <type_traits> +#include <string> +// start catch_stream.h + +#include <iosfwd> +#include <cstddef> +#include <ostream> + +namespace Catch { + + std::ostream& cout(); + std::ostream& cerr(); + std::ostream& clog(); + + class StringRef; + + struct IStream { + virtual ~IStream(); + virtual std::ostream& stream() const = 0; + }; + + auto makeStream( StringRef const &filename ) -> IStream const*; + + class ReusableStringStream { + std::size_t m_index; + std::ostream* m_oss; + public: + ReusableStringStream(); + ~ReusableStringStream(); + + auto str() const -> std::string; + + template<typename T> + auto operator << ( T const& value ) -> ReusableStringStream& { + *m_oss << value; + return *this; + } + auto get() -> std::ostream& { return *m_oss; } + }; +} + +// end catch_stream.h + +#ifdef CATCH_CONFIG_CPP17_STRING_VIEW +#include <string_view> +#endif + +#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 + +namespace Catch { + 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; + }; + + template<typename E> + std::string convertUnknownEnumToString( E e ); + + template<typename T> + typename std::enable_if< + !std::is_enum<T>::value && !std::is_base_of<std::exception, T>::value, + std::string>::type convertUnstreamable( T const& ) { + return Detail::unprintableString; + } + template<typename T> + typename std::enable_if< + !std::is_enum<T>::value && std::is_base_of<std::exception, T>::value, + std::string>::type convertUnstreamable(T const& ex) { + return ex.what(); + } + + template<typename T> + typename std::enable_if< + std::is_enum<T>::value + , std::string>::type convertUnstreamable( T const& value ) { + return convertUnknownEnumToString( value ); + } + +#if defined(_MANAGED) + //! Convert a CLR string to a utf8 std::string + template<typename T> + std::string clrReferenceToString( T^ ref ) { + if (ref == nullptr) + return std::string("null"); + auto bytes = System::Text::Encoding::UTF8->GetBytes(ref->ToString()); + cli::pin_ptr<System::Byte> p = &bytes[0]; + return std::string(reinterpret_cast<char const *>(p), bytes->Length); + } +#endif + + } // namespace Detail + + // If we decide for C++14, change these to enable_if_ts + template <typename T, typename = void> + struct StringMaker { + template <typename Fake = T> + static + typename std::enable_if<::Catch::Detail::IsStreamInsertable<Fake>::value, std::string>::type + convert(const Fake& value) { + ReusableStringStream rss; + // NB: call using the function-like syntax to avoid ambiguity with + // user-defined templated operator<< under clang. + rss.operator<<(value); + return rss.str(); + } + + template <typename Fake = T> + static + typename std::enable_if<!::Catch::Detail::IsStreamInsertable<Fake>::value, std::string>::type + convert( const Fake& value ) { +#if !defined(CATCH_CONFIG_FALLBACK_STRINGIFIER) + return Detail::convertUnstreamable(value); +#else + return CATCH_CONFIG_FALLBACK_STRINGIFIER(value); +#endif + } + }; + + 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); + } + + template<typename E> + std::string convertUnknownEnumToString( E e ) { + return ::Catch::Detail::stringify(static_cast<typename std::underlying_type<E>::type>(e)); + } + +#if defined(_MANAGED) + template <typename T> + std::string stringify( T^ e ) { + return ::Catch::StringMaker<T^>::convert(e); + } +#endif + + } // namespace Detail + + // Some predefined specializations + + template<> + struct StringMaker<std::string> { + static std::string convert(const std::string& str); + }; + +#ifdef CATCH_CONFIG_CPP17_STRING_VIEW + template<> + struct StringMaker<std::string_view> { + static std::string convert(std::string_view str); + }; +#endif + + template<> + struct StringMaker<char const *> { + static std::string convert(char const * str); + }; + template<> + struct StringMaker<char *> { + static std::string convert(char * str); + }; + +#ifdef CATCH_CONFIG_WCHAR + template<> + struct StringMaker<std::wstring> { + static std::string convert(const std::wstring& wstr); + }; + +# ifdef CATCH_CONFIG_CPP17_STRING_VIEW + template<> + struct StringMaker<std::wstring_view> { + static std::string convert(std::wstring_view str); + }; +# endif + + 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); + }; +#endif + + // TBD: Should we use `strnlen` to ensure that we don't go out of the buffer, + // while keeping string semantics? + template<int SZ> + struct StringMaker<char[SZ]> { + static std::string convert(char const* str) { + return ::Catch::Detail::stringify(std::string{ str }); + } + }; + template<int SZ> + struct StringMaker<signed char[SZ]> { + static std::string convert(signed char const* str) { + return ::Catch::Detail::stringify(std::string{ reinterpret_cast<char const *>(str) }); + } + }; + template<int SZ> + struct StringMaker<unsigned char[SZ]> { + static std::string convert(unsigned char const* str) { + return ::Catch::Detail::stringify(std::string{ reinterpret_cast<char const *>(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"; + } + } + }; + +#if defined(_MANAGED) + template <typename T> + struct StringMaker<T^> { + static std::string convert( T^ ref ) { + return ::Catch::Detail::clrReferenceToString(ref); + } + }; +#endif + + namespace Detail { + template<typename InputIterator> + std::string rangeToString(InputIterator first, InputIterator last) { + ReusableStringStream rss; + rss << "{ "; + if (first != last) { + rss << ::Catch::Detail::stringify(*first); + for (++first; first != last; ++first) + rss << ", " << ::Catch::Detail::stringify(*first); + } + rss << " }"; + return rss.str(); + } + } + +#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_VARIANT_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) { + ReusableStringStream rss; + rss << "{ " + << ::Catch::Detail::stringify(pair.first) + << ", " + << ::Catch::Detail::stringify(pair.second) + << " }"; + return rss.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) { + ReusableStringStream rss; + rss << '{'; + Detail::TupleElementPrinter<std::tuple<Types...>>::print(tuple, rss.get()); + rss << " }"; + return rss.str(); + } + }; +} +#endif // CATCH_CONFIG_ENABLE_TUPLE_STRINGMAKER + +#if defined(CATCH_CONFIG_ENABLE_VARIANT_STRINGMAKER) && defined(CATCH_CONFIG_CPP17_VARIANT) +#include <variant> +namespace Catch { + template<> + struct StringMaker<std::monostate> { + static std::string convert(const std::monostate&) { + return "{ }"; + } + }; + + template<typename... Elements> + struct StringMaker<std::variant<Elements...>> { + static std::string convert(const std::variant<Elements...>& variant) { + if (variant.valueless_by_exception()) { + return "{valueless variant}"; + } else { + return std::visit( + [](const auto& value) { + return ::Catch::Detail::stringify(value); + }, + variant + ); + } + } + }; +} +#endif // CATCH_CONFIG_ENABLE_VARIANT_STRINGMAKER + +namespace Catch { + struct not_this_one {}; // Tag type for detecting which begin/ end are being selected + + // Import begin/ end from std here so they are considered alongside the fallback (...) overloads in this namespace + using std::begin; + using std::end; + + not_this_one begin( ... ); + not_this_one end( ... ); + + template <typename T> + struct is_range { + static const bool value = + !std::is_same<decltype(begin(std::declval<T>())), not_this_one>::value && + !std::is_same<decltype(end(std::declval<T>())), not_this_one>::value; + }; + +#if defined(_MANAGED) // Managed types are never ranges + template <typename T> + struct is_range<T^> { + static const bool value = false; + }; +#endif + + template<typename Range> + std::string rangeToString( Range const& range ) { + return ::Catch::Detail::rangeToString( begin( range ), end( range ) ); + } + + // Handle vector<bool> specially + template<typename Allocator> + std::string rangeToString( std::vector<bool, Allocator> const& v ) { + ReusableStringStream rss; + rss << "{ "; + bool first = true; + for( bool b : v ) { + if( first ) + first = false; + else + rss << ", "; + rss << ::Catch::Detail::stringify( b ); + } + rss << " }"; + return rss.str(); + } + + template<typename R> + struct StringMaker<R, typename std::enable_if<is_range<R>::value && !::Catch::Detail::IsStreamInsertable<R>::value>::type> { + static std::string convert( R const& range ) { + return rangeToString( range ); + } + }; + + template <typename T, int SZ> + struct StringMaker<T[SZ]> { + static std::string convert(T const(&arr)[SZ]) { + return rangeToString(arr); + } + }; + +} // namespace Catch + +// Separate std::chrono::duration specialization +#if defined(CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER) +#include <ctime> +#include <ratio> +#include <chrono> + +namespace Catch { + +template <class Ratio> +struct ratio_string { + static std::string symbol(); +}; + +template <class Ratio> +std::string ratio_string<Ratio>::symbol() { + Catch::ReusableStringStream rss; + rss << '[' << Ratio::num << '/' + << Ratio::den << ']'; + return rss.str(); +} +template <> +struct ratio_string<std::atto> { + static std::string symbol(); +}; +template <> +struct ratio_string<std::femto> { + static std::string symbol(); +}; +template <> +struct ratio_string<std::pico> { + static std::string symbol(); +}; +template <> +struct ratio_string<std::nano> { + static std::string symbol(); +}; +template <> +struct ratio_string<std::micro> { + static std::string symbol(); +}; +template <> +struct ratio_string<std::milli> { + static std::string symbol(); +}; + + //////////// + // 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) { + ReusableStringStream rss; + rss << duration.count() << ' ' << ratio_string<Ratio>::symbol() << 's'; + return rss.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) { + ReusableStringStream rss; + rss << duration.count() << " s"; + return rss.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) { + ReusableStringStream rss; + rss << duration.count() << " m"; + return rss.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) { + ReusableStringStream rss; + rss << duration.count() << " h"; + return rss.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 <iosfwd> + +#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 { + auto isBinaryExpression() const -> bool { return m_isBinaryExpression; } + auto getResult() const -> bool { return m_result; } + virtual void streamReconstructedExpression( std::ostream &os ) const = 0; + + ITransientExpression( bool isBinaryExpression, bool result ) + : m_isBinaryExpression( isBinaryExpression ), + m_result( result ) + {} + + // We don't actually need a virtual destructor, but many static analysers + // complain if it's not here :-( + virtual ~ITransientExpression(); + + bool m_isBinaryExpression; + bool m_result; + + }; + + void formatReconstructedExpression( std::ostream &os, std::string const& lhs, StringRef op, std::string const& rhs ); + + template<typename LhsT, typename RhsT> + class BinaryExpr : public ITransientExpression { + LhsT m_lhs; + StringRef m_op; + RhsT m_rhs; + + 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 ) + : ITransientExpression{ true, comparisonResult }, + m_lhs( lhs ), + m_op( op ), + m_rhs( rhs ) + {} + }; + + template<typename LhsT> + class UnaryExpr : public ITransientExpression { + LhsT m_lhs; + + void streamReconstructedExpression( std::ostream &os ) const override { + os << Catch::Detail::stringify( m_lhs ); + } + + public: + explicit UnaryExpr( LhsT lhs ) + : ITransientExpression{ false, lhs ? true : false }, + 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 static_cast<bool>(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 static_cast<bool>(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: + explicit ExprLhs( LhsT lhs ) : m_lhs( lhs ) {} + + template<typename RhsT> + auto operator == ( RhsT const& rhs ) -> BinaryExpr<LhsT, RhsT const&> const { + return { compareEqual( m_lhs, rhs ), m_lhs, "==", rhs }; + } + auto operator == ( bool rhs ) -> BinaryExpr<LhsT, bool> const { + return { m_lhs == rhs, m_lhs, "==", rhs }; + } + + template<typename RhsT> + auto operator != ( RhsT const& rhs ) -> BinaryExpr<LhsT, RhsT const&> const { + return { compareNotEqual( m_lhs, rhs ), m_lhs, "!=", rhs }; + } + auto operator != ( bool rhs ) -> BinaryExpr<LhsT, bool> const { + return { m_lhs != rhs, m_lhs, "!=", rhs }; + } + + template<typename RhsT> + auto operator > ( RhsT const& rhs ) -> BinaryExpr<LhsT, RhsT const&> const { + return { static_cast<bool>(m_lhs > rhs), m_lhs, ">", rhs }; + } + template<typename RhsT> + auto operator < ( RhsT const& rhs ) -> BinaryExpr<LhsT, RhsT const&> const { + return { static_cast<bool>(m_lhs < rhs), m_lhs, "<", rhs }; + } + template<typename RhsT> + auto operator >= ( RhsT const& rhs ) -> BinaryExpr<LhsT, RhsT const&> const { + return { static_cast<bool>(m_lhs >= rhs), m_lhs, ">=", rhs }; + } + template<typename RhsT> + auto operator <= ( RhsT const& rhs ) -> BinaryExpr<LhsT, RhsT const&> const { + return { static_cast<bool>(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_interfaces_capture.h + +#include <string> + +namespace Catch { + + class AssertionResult; + struct AssertionInfo; + struct SectionInfo; + struct SectionEndInfo; + struct MessageInfo; + struct Counts; + struct BenchmarkInfo; + struct BenchmarkStats; + struct AssertionReaction; + struct SourceLineInfo; + + struct ITransientExpression; + struct IGeneratorTracker; + + struct IResultCapture { + + virtual ~IResultCapture(); + + virtual bool sectionStarted( SectionInfo const& sectionInfo, + Counts& assertions ) = 0; + virtual void sectionEnded( SectionEndInfo const& endInfo ) = 0; + virtual void sectionEndedEarly( SectionEndInfo const& endInfo ) = 0; + + virtual auto acquireGeneratorTracker( SourceLineInfo const& lineInfo ) -> IGeneratorTracker& = 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 void handleFatalErrorCondition( StringRef message ) = 0; + + virtual void handleExpr + ( AssertionInfo const& info, + ITransientExpression const& expr, + AssertionReaction& reaction ) = 0; + virtual void handleMessage + ( AssertionInfo const& info, + ResultWas::OfType resultType, + StringRef const& message, + AssertionReaction& reaction ) = 0; + virtual void handleUnexpectedExceptionNotThrown + ( AssertionInfo const& info, + AssertionReaction& reaction ) = 0; + virtual void handleUnexpectedInflightException + ( AssertionInfo const& info, + std::string const& message, + AssertionReaction& reaction ) = 0; + virtual void handleIncomplete + ( AssertionInfo const& info ) = 0; + virtual void handleNonExpr + ( AssertionInfo const &info, + ResultWas::OfType resultType, + AssertionReaction &reaction ) = 0; + + virtual bool lastAssertionPassed() = 0; + virtual void assertionPassed() = 0; + + // Deprecated, do not use: + virtual std::string getCurrentTestName() const = 0; + virtual const AssertionResult* getLastResult() const = 0; + virtual void exceptionEarlyReported() = 0; + }; + + IResultCapture& getResultCapture(); +} + +// end catch_interfaces_capture.h +namespace Catch { + + struct TestFailureException{}; + struct AssertionResultData; + struct IResultCapture; + class RunContext; + + class LazyExpression { + friend class AssertionHandler; + friend struct AssertionStats; + friend class RunContext; + + 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&; + }; + + struct AssertionReaction { + bool shouldDebugBreak = false; + bool shouldThrow = false; + }; + + class AssertionHandler { + AssertionInfo m_assertionInfo; + AssertionReaction m_reaction; + bool m_completed = false; + IResultCapture& m_resultCapture; + + public: + AssertionHandler + ( StringRef const& macroName, + SourceLineInfo const& lineInfo, + StringRef capturedExpression, + ResultDisposition::Flags resultDisposition ); + ~AssertionHandler() { + if ( !m_completed ) { + m_resultCapture.handleIncomplete( m_assertionInfo ); + } + } + + template<typename T> + void handleExpr( ExprLhs<T> const& expr ) { + handleExpr( expr.makeUnaryExpr() ); + } + void handleExpr( ITransientExpression const& expr ); + + void handleMessage(ResultWas::OfType resultType, StringRef const& message); + + void handleExceptionThrownAsExpected(); + void handleUnexpectedExceptionNotThrown(); + void handleExceptionNotThrownAsExpected(); + void handleThrowingCallSkipped(); + void handleUnexpectedInflightException(); + + void complete(); + void setCompleted(); + + // query + auto allowThrows() const -> bool; + }; + + void handleExceptionMatchExpr( AssertionHandler& handler, std::string const& str, StringRef const& matcherString ); + +} // namespace Catch + +// end catch_assertionhandler.h +// start catch_message.h + +#include <string> +#include <vector> + +namespace Catch { + + struct MessageInfo { + MessageInfo( StringRef const& _macroName, + SourceLineInfo const& _lineInfo, + ResultWas::OfType _type ); + + StringRef 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; + } + + ReusableStringStream m_stream; + }; + + struct MessageBuilder : MessageStream { + MessageBuilder( StringRef 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: + explicit ScopedMessage( MessageBuilder const& builder ); + ~ScopedMessage(); + + MessageInfo m_info; + }; + + class Capturer { + std::vector<MessageInfo> m_messages; + IResultCapture& m_resultCapture = getResultCapture(); + size_t m_captured = 0; + public: + Capturer( StringRef macroName, SourceLineInfo const& lineInfo, ResultWas::OfType resultType, StringRef names ); + ~Capturer(); + + void captureValue( size_t index, std::string const& value ); + + template<typename T> + void captureValues( size_t index, T const& value ) { + captureValue( index, Catch::Detail::stringify( value ) ); + } + + template<typename T, typename... Ts> + void captureValues( size_t index, T const& value, Ts const&... values ) { + captureValue( index, Catch::Detail::stringify(value) ); + captureValues( index+1, values... ); + } + }; + +} // end namespace Catch + +// end catch_message.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) || defined(CATCH_CONFIG_DISABLE_EXCEPTIONS) + +/////////////////////////////////////////////////////////////////////////////// +// Another way to speed-up compilation is to omit local try-catch for REQUIRE* +// macros. +#define INTERNAL_CATCH_TRY +#define INTERNAL_CATCH_CATCH( capturer ) + +#else // CATCH_CONFIG_FAST_COMPILE + +#define INTERNAL_CATCH_TRY try +#define INTERNAL_CATCH_CATCH( handler ) catch(...) { handler.handleUnexpectedInflightException(); } + +#endif + +#define INTERNAL_CATCH_REACT( handler ) handler.complete(); + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_TEST( macroName, resultDisposition, ... ) \ + do { \ + Catch::AssertionHandler catchAssertionHandler( macroName##_catch_sr, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(__VA_ARGS__), resultDisposition ); \ + INTERNAL_CATCH_TRY { \ + CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS \ + catchAssertionHandler.handleExpr( Catch::Decomposer() <= __VA_ARGS__ ); \ + CATCH_INTERNAL_UNSUPPRESS_PARENTHESES_WARNINGS \ + } INTERNAL_CATCH_CATCH( catchAssertionHandler ) \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( (void)0, 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_sr, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(__VA_ARGS__), resultDisposition ); \ + try { \ + static_cast<void>(__VA_ARGS__); \ + catchAssertionHandler.handleExceptionNotThrownAsExpected(); \ + } \ + catch( ... ) { \ + catchAssertionHandler.handleUnexpectedInflightException(); \ + } \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( false ) + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_THROWS( macroName, resultDisposition, ... ) \ + do { \ + Catch::AssertionHandler catchAssertionHandler( macroName##_catch_sr, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(__VA_ARGS__), resultDisposition); \ + if( catchAssertionHandler.allowThrows() ) \ + try { \ + static_cast<void>(__VA_ARGS__); \ + catchAssertionHandler.handleUnexpectedExceptionNotThrown(); \ + } \ + catch( ... ) { \ + catchAssertionHandler.handleExceptionThrownAsExpected(); \ + } \ + else \ + catchAssertionHandler.handleThrowingCallSkipped(); \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( false ) + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_THROWS_AS( macroName, exceptionType, resultDisposition, expr ) \ + do { \ + Catch::AssertionHandler catchAssertionHandler( macroName##_catch_sr, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(expr) ", " CATCH_INTERNAL_STRINGIFY(exceptionType), resultDisposition ); \ + if( catchAssertionHandler.allowThrows() ) \ + try { \ + static_cast<void>(expr); \ + catchAssertionHandler.handleUnexpectedExceptionNotThrown(); \ + } \ + catch( exceptionType const& ) { \ + catchAssertionHandler.handleExceptionThrownAsExpected(); \ + } \ + catch( ... ) { \ + catchAssertionHandler.handleUnexpectedInflightException(); \ + } \ + else \ + catchAssertionHandler.handleThrowingCallSkipped(); \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( false ) + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_MSG( macroName, messageType, resultDisposition, ... ) \ + do { \ + Catch::AssertionHandler catchAssertionHandler( macroName##_catch_sr, CATCH_INTERNAL_LINEINFO, Catch::StringRef(), resultDisposition ); \ + catchAssertionHandler.handleMessage( messageType, ( Catch::MessageStream() << __VA_ARGS__ + ::Catch::StreamEndStop() ).m_stream.str() ); \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( false ) + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_CAPTURE( varName, macroName, ... ) \ + auto varName = Catch::Capturer( macroName, CATCH_INTERNAL_LINEINFO, Catch::ResultWas::Info, #__VA_ARGS__ ); \ + varName.captureValues( 0, __VA_ARGS__ ) + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_INFO( macroName, log ) \ + Catch::ScopedMessage INTERNAL_CATCH_UNIQUE_NAME( scopedMessage )( Catch::MessageBuilder( macroName##_catch_sr, 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_sr, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(__VA_ARGS__) ", " CATCH_INTERNAL_STRINGIFY(matcher), resultDisposition ); \ + if( catchAssertionHandler.allowThrows() ) \ + try { \ + static_cast<void>(__VA_ARGS__); \ + catchAssertionHandler.handleUnexpectedExceptionNotThrown(); \ + } \ + catch( ... ) { \ + Catch::handleExceptionMatchExpr( catchAssertionHandler, matcher, #matcher##_catch_sr ); \ + } \ + else \ + catchAssertionHandler.handleThrowingCallSkipped(); \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( false ) + +#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; + + int error = 0; + Counts assertions; + Counts testCases; + }; +} + +// end catch_totals.h +#include <string> + +namespace Catch { + + struct SectionInfo { + SectionInfo + ( SourceLineInfo const& _lineInfo, + std::string const& _name ); + + // Deprecated + SectionInfo + ( SourceLineInfo const& _lineInfo, + std::string const& _name, + std::string const& ) : SectionInfo( _lineInfo, _name ) {} + + std::string name; + std::string description; // !Deprecated: this will always be empty + SourceLineInfo lineInfo; + }; + + struct SectionEndInfo { + 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 -> uint64_t; + auto getElapsedMicroseconds() const -> uint64_t; + 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( ... ) \ + CATCH_INTERNAL_SUPPRESS_UNUSED_WARNINGS \ + if( Catch::Section const& INTERNAL_CATCH_UNIQUE_NAME( catch_internal_Section ) = Catch::SectionInfo( CATCH_INTERNAL_LINEINFO, __VA_ARGS__ ) ) \ + CATCH_INTERNAL_UNSUPPRESS_UNUSED_WARNINGS + +#define INTERNAL_CATCH_DYNAMIC_SECTION( ... ) \ + CATCH_INTERNAL_SUPPRESS_UNUSED_WARNINGS \ + if( Catch::Section const& INTERNAL_CATCH_UNIQUE_NAME( catch_internal_Section ) = Catch::SectionInfo( CATCH_INTERNAL_LINEINFO, (Catch::ReusableStringStream() << __VA_ARGS__).str() ) ) \ + CATCH_INTERNAL_UNSUPPRESS_UNUSED_WARNINGS + +// 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 const& getExceptionTranslatorRegistry() const = 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 const& 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 ); \ + CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \ + namespace{ Catch::ExceptionTranslatorRegistrar INTERNAL_CATCH_UNIQUE_NAME( catch_internal_ExceptionRegistrar )( &translatorName ); } \ + CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS \ + 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 + +#include <type_traits> + +namespace Catch { +namespace Detail { + + class Approx { + private: + bool equalityComparisonImpl(double other) const; + // Validates the new margin (margin >= 0) + // out-of-line to avoid including stdexcept in the header + void setMargin(double margin); + // Validates the new epsilon (0 < epsilon < 1) + // out-of-line to avoid including stdexcept in the header + void setEpsilon(double epsilon); + + public: + explicit Approx ( double value ); + + static Approx custom(); + + Approx operator-() const; + + 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.m_epsilon = m_epsilon; + approx.m_margin = m_margin; + approx.m_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); + setEpsilon(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); + setMargin(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; + }; +} // end namespace Detail + +namespace literals { + Detail::Approx operator "" _a(long double val); + Detail::Approx operator "" _a(unsigned long long val); +} // end namespace literals + +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; + }; + +#ifdef __clang__ +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wnon-virtual-dtor" +#endif + + template<typename ObjectT> + struct MatcherMethod { + virtual bool match( ObjectT const& arg ) const = 0; + }; + +#ifdef __clang__ +# pragma clang diagnostic pop +#endif + + template<typename T> + struct MatcherBase : MatcherUntypedBase, MatcherMethod<T> { + + MatchAllOf<T> operator && ( MatcherBase const& other ) const; + MatchAnyOf<T> operator || ( MatcherBase const& other ) const; + MatchNotOf<T> 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 T> + MatchAllOf<T> MatcherBase<T>::operator && ( MatcherBase const& other ) const { + return MatchAllOf<T>() && *this && other; + } + template<typename T> + MatchAnyOf<T> MatcherBase<T>::operator || ( MatcherBase const& other ) const { + return MatchAnyOf<T>() || *this || other; + } + template<typename T> + MatchNotOf<T> MatcherBase<T>::operator ! () const { + return MatchNotOf<T>( *this ); + } + + } // namespace Impl + +} // namespace Matchers + +using namespace Matchers; +using Matchers::Impl::MatcherBase; + +} // namespace Catch + +// end catch_matchers.h +// start catch_matchers_floating.h + +#include <type_traits> +#include <cmath> + +namespace Catch { +namespace Matchers { + + namespace Floating { + + enum class FloatingPointKind : uint8_t; + + struct WithinAbsMatcher : MatcherBase<double> { + WithinAbsMatcher(double target, double margin); + bool match(double const& matchee) const override; + std::string describe() const override; + private: + double m_target; + double m_margin; + }; + + struct WithinUlpsMatcher : MatcherBase<double> { + WithinUlpsMatcher(double target, int ulps, FloatingPointKind baseType); + bool match(double const& matchee) const override; + std::string describe() const override; + private: + double m_target; + int m_ulps; + FloatingPointKind m_type; + }; + + } // namespace Floating + + // The following functions create the actual matcher objects. + // This allows the types to be inferred + Floating::WithinUlpsMatcher WithinULP(double target, int maxUlpDiff); + Floating::WithinUlpsMatcher WithinULP(float target, int maxUlpDiff); + Floating::WithinAbsMatcher WithinAbs(double target, double margin); + +} // namespace Matchers +} // namespace Catch + +// end catch_matchers_floating.h +// start catch_matchers_generic.hpp + +#include <functional> +#include <string> + +namespace Catch { +namespace Matchers { +namespace Generic { + +namespace Detail { + std::string finalizeDescription(const std::string& desc); +} + +template <typename T> +class PredicateMatcher : public MatcherBase<T> { + std::function<bool(T const&)> m_predicate; + std::string m_description; +public: + + PredicateMatcher(std::function<bool(T const&)> const& elem, std::string const& descr) + :m_predicate(std::move(elem)), + m_description(Detail::finalizeDescription(descr)) + {} + + bool match( T const& item ) const override { + return m_predicate(item); + } + + std::string describe() const override { + return m_description; + } +}; + +} // namespace Generic + + // The following functions create the actual matcher objects. + // The user has to explicitly specify type to the function, because + // infering std::function<bool(T const&)> is hard (but possible) and + // requires a lot of TMP. + template<typename T> + Generic::PredicateMatcher<T> Predicate(std::function<bool(T const&)> const& predicate, std::string const& description = "") { + return Generic::PredicateMatcher<T>(predicate, description); + } + +} // namespace Matchers +} // namespace Catch + +// end catch_matchers_generic.hpp +// 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; + }; + + struct RegexMatcher : MatcherBase<std::string> { + RegexMatcher( std::string regex, CaseSensitive::Choice caseSensitivity ); + bool match( std::string const& matchee ) const override; + std::string describe() const override; + + private: + std::string m_regex; + CaseSensitive::Choice m_caseSensitivity; + }; + + } // 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 ); + StdString::RegexMatcher Matches( std::string const& regex, CaseSensitive::Choice caseSensitivity = CaseSensitive::Yes ); + +} // namespace Matchers +} // namespace Catch + +// end catch_matchers_string.h +// start catch_matchers_vector.h + +#include <algorithm> + +namespace Catch { +namespace Matchers { + + namespace Vector { + namespace Detail { + template <typename InputIterator, typename T> + size_t count(InputIterator first, InputIterator last, T const& item) { + size_t cnt = 0; + for (; first != last; ++first) { + if (*first == item) { + ++cnt; + } + } + return cnt; + } + template <typename InputIterator, typename T> + bool contains(InputIterator first, InputIterator last, T const& item) { + for (; first != last; ++first) { + if (*first == item) { + return true; + } + } + return false; + } + } + + template<typename T> + struct ContainsElementMatcher : MatcherBase<std::vector<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>> { + + 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>> { + + 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; + }; + + template<typename T> + struct UnorderedEqualsMatcher : MatcherBase<std::vector<T>> { + UnorderedEqualsMatcher(std::vector<T> const& target) : m_target(target) {} + bool match(std::vector<T> const& vec) const override { + // Note: This is a reimplementation of std::is_permutation, + // because I don't want to include <algorithm> inside the common path + if (m_target.size() != vec.size()) { + return false; + } + auto lfirst = m_target.begin(), llast = m_target.end(); + auto rfirst = vec.begin(), rlast = vec.end(); + // Cut common prefix to optimize checking of permuted parts + while (lfirst != llast && *lfirst == *rfirst) { + ++lfirst; ++rfirst; + } + if (lfirst == llast) { + return true; + } + + for (auto mid = lfirst; mid != llast; ++mid) { + // Skip already counted items + if (Detail::contains(lfirst, mid, *mid)) { + continue; + } + size_t num_vec = Detail::count(rfirst, rlast, *mid); + if (num_vec == 0 || Detail::count(lfirst, llast, *mid) != num_vec) { + return false; + } + } + + return true; + } + + std::string describe() const override { + return "UnorderedEquals: " + ::Catch::Detail::stringify(m_target); + } + private: + std::vector<T> const& m_target; + }; + + } // 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 ); + } + + template<typename T> + Vector::UnorderedEqualsMatcher<T> UnorderedEquals(std::vector<T> const& target) { + return Vector::UnorderedEqualsMatcher<T>(target); + } + +} // 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; + public: + MatchExpr( ArgT const& arg, MatcherT const& matcher, StringRef const& matcherString ) + : ITransientExpression{ true, matcher.match( arg ) }, + m_arg( arg ), + m_matcher( matcher ), + m_matcherString( matcherString ) + {} + + 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 const& matcherString ); + + template<typename ArgT, typename MatcherT> + auto makeMatchExpr( ArgT const& arg, MatcherT const& matcher, StringRef const& 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_sr, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(arg) ", " CATCH_INTERNAL_STRINGIFY(matcher), resultDisposition ); \ + INTERNAL_CATCH_TRY { \ + catchAssertionHandler.handleExpr( Catch::makeMatchExpr( arg, matcher, #matcher##_catch_sr ) ); \ + } INTERNAL_CATCH_CATCH( catchAssertionHandler ) \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( false ) + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_THROWS_MATCHES( macroName, exceptionType, resultDisposition, matcher, ... ) \ + do { \ + Catch::AssertionHandler catchAssertionHandler( macroName##_catch_sr, 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.handleUnexpectedExceptionNotThrown(); \ + } \ + catch( exceptionType const& ex ) { \ + catchAssertionHandler.handleExpr( Catch::makeMatchExpr( ex, matcher, #matcher##_catch_sr ) ); \ + } \ + catch( ... ) { \ + catchAssertionHandler.handleUnexpectedInflightException(); \ + } \ + else \ + catchAssertionHandler.handleThrowingCallSkipped(); \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( false ) + +// end catch_capture_matchers.h +#endif +// start catch_generators.hpp + +// start catch_interfaces_generatortracker.h + + +#include <memory> + +namespace Catch { + + namespace Generators { + class GeneratorBase { + protected: + size_t m_size = 0; + + public: + GeneratorBase( size_t size ) : m_size( size ) {} + virtual ~GeneratorBase(); + auto size() const -> size_t { return m_size; } + }; + using GeneratorBasePtr = std::unique_ptr<GeneratorBase>; + + } // namespace Generators + + struct IGeneratorTracker { + virtual ~IGeneratorTracker(); + virtual auto hasGenerator() const -> bool = 0; + virtual auto getGenerator() const -> Generators::GeneratorBasePtr const& = 0; + virtual void setGenerator( Generators::GeneratorBasePtr&& generator ) = 0; + virtual auto getIndex() const -> std::size_t = 0; + }; + +} // namespace Catch + +// end catch_interfaces_generatortracker.h +// start catch_enforce.h + +#include <stdexcept> + +namespace Catch { +#if !defined(CATCH_CONFIG_DISABLE_EXCEPTIONS) + template <typename Ex> + [[noreturn]] + void throw_exception(Ex const& e) { + throw e; + } +#else // ^^ Exceptions are enabled // Exceptions are disabled vv + [[noreturn]] + void throw_exception(std::exception const& e); +#endif +} // namespace Catch; + +#define CATCH_PREPARE_EXCEPTION( type, msg ) \ + type( ( Catch::ReusableStringStream() << msg ).str() ) +#define CATCH_INTERNAL_ERROR( msg ) \ + Catch::throw_exception(CATCH_PREPARE_EXCEPTION( std::logic_error, CATCH_INTERNAL_LINEINFO << ": Internal Catch error: " << msg)) +#define CATCH_ERROR( msg ) \ + Catch::throw_exception(CATCH_PREPARE_EXCEPTION( std::domain_error, msg )) +#define CATCH_RUNTIME_ERROR( msg ) \ + Catch::throw_exception(CATCH_PREPARE_EXCEPTION( std::runtime_error, msg )) +#define CATCH_ENFORCE( condition, msg ) \ + do{ if( !(condition) ) CATCH_ERROR( msg ); } while(false) + +// end catch_enforce.h +#include <memory> +#include <vector> +#include <cassert> + +#include <utility> + +namespace Catch { +namespace Generators { + + // !TBD move this into its own location? + namespace pf{ + template<typename T, typename... Args> + std::unique_ptr<T> make_unique( Args&&... args ) { + return std::unique_ptr<T>(new T(std::forward<Args>(args)...)); + } + } + + template<typename T> + struct IGenerator { + virtual ~IGenerator() {} + virtual auto get( size_t index ) const -> T = 0; + }; + + template<typename T> + class SingleValueGenerator : public IGenerator<T> { + T m_value; + public: + SingleValueGenerator( T const& value ) : m_value( value ) {} + + auto get( size_t ) const -> T override { + return m_value; + } + }; + + template<typename T> + class FixedValuesGenerator : public IGenerator<T> { + std::vector<T> m_values; + + public: + FixedValuesGenerator( std::initializer_list<T> values ) : m_values( values ) {} + + auto get( size_t index ) const -> T override { + return m_values[index]; + } + }; + + template<typename T> + class RangeGenerator : public IGenerator<T> { + T const m_first; + T const m_last; + + public: + RangeGenerator( T const& first, T const& last ) : m_first( first ), m_last( last ) { + assert( m_last > m_first ); + } + + auto get( size_t index ) const -> T override { + // ToDo:: introduce a safe cast to catch potential overflows + return static_cast<T>(m_first+index); + } + }; + + template<typename T> + struct NullGenerator : IGenerator<T> { + auto get( size_t ) const -> T override { + CATCH_INTERNAL_ERROR("A Null Generator is always empty"); + } + }; + + template<typename T> + class Generator { + std::unique_ptr<IGenerator<T>> m_generator; + size_t m_size; + + public: + Generator( size_t size, std::unique_ptr<IGenerator<T>> generator ) + : m_generator( std::move( generator ) ), + m_size( size ) + {} + + auto size() const -> size_t { return m_size; } + auto operator[]( size_t index ) const -> T { + assert( index < m_size ); + return m_generator->get( index ); + } + }; + + std::vector<size_t> randomiseIndices( size_t selectionSize, size_t sourceSize ); + + template<typename T> + class GeneratorRandomiser : public IGenerator<T> { + Generator<T> m_baseGenerator; + + std::vector<size_t> m_indices; + public: + GeneratorRandomiser( Generator<T>&& baseGenerator, size_t numberOfItems ) + : m_baseGenerator( std::move( baseGenerator ) ), + m_indices( randomiseIndices( numberOfItems, m_baseGenerator.size() ) ) + {} + + auto get( size_t index ) const -> T override { + return m_baseGenerator[m_indices[index]]; + } + }; + + template<typename T> + struct RequiresASpecialisationFor; + + template<typename T> + auto all() -> Generator<T> { return RequiresASpecialisationFor<T>(); } + + template<> + auto all<int>() -> Generator<int>; + + template<typename T> + auto range( T const& first, T const& last ) -> Generator<T> { + return Generator<T>( (last-first), pf::make_unique<RangeGenerator<T>>( first, last ) ); + } + + template<typename T> + auto random( T const& first, T const& last ) -> Generator<T> { + auto gen = range( first, last ); + auto size = gen.size(); + + return Generator<T>( size, pf::make_unique<GeneratorRandomiser<T>>( std::move( gen ), size ) ); + } + template<typename T> + auto random( size_t size ) -> Generator<T> { + return Generator<T>( size, pf::make_unique<GeneratorRandomiser<T>>( all<T>(), size ) ); + } + + template<typename T> + auto values( std::initializer_list<T> values ) -> Generator<T> { + return Generator<T>( values.size(), pf::make_unique<FixedValuesGenerator<T>>( values ) ); + } + template<typename T> + auto value( T const& val ) -> Generator<T> { + return Generator<T>( 1, pf::make_unique<SingleValueGenerator<T>>( val ) ); + } + + template<typename T> + auto as() -> Generator<T> { + return Generator<T>( 0, pf::make_unique<NullGenerator<T>>() ); + } + + template<typename... Ts> + auto table( std::initializer_list<std::tuple<Ts...>>&& tuples ) -> Generator<std::tuple<Ts...>> { + return values<std::tuple<Ts...>>( std::forward<std::initializer_list<std::tuple<Ts...>>>( tuples ) ); + } + + template<typename T> + struct Generators : GeneratorBase { + std::vector<Generator<T>> m_generators; + + using type = T; + + Generators() : GeneratorBase( 0 ) {} + + void populate( T&& val ) { + m_size += 1; + m_generators.emplace_back( value( std::move( val ) ) ); + } + template<typename U> + void populate( U&& val ) { + populate( T( std::move( val ) ) ); + } + void populate( Generator<T>&& generator ) { + m_size += generator.size(); + m_generators.emplace_back( std::move( generator ) ); + } + + template<typename U, typename... Gs> + void populate( U&& valueOrGenerator, Gs... moreGenerators ) { + populate( std::forward<U>( valueOrGenerator ) ); + populate( std::forward<Gs>( moreGenerators )... ); + } + + auto operator[]( size_t index ) const -> T { + size_t sizes = 0; + for( auto const& gen : m_generators ) { + auto localIndex = index-sizes; + sizes += gen.size(); + if( index < sizes ) + return gen[localIndex]; + } + CATCH_INTERNAL_ERROR("Index '" << index << "' is out of range (" << sizes << ')'); + } + }; + + template<typename T, typename... Gs> + auto makeGenerators( Generator<T>&& generator, Gs... moreGenerators ) -> Generators<T> { + Generators<T> generators; + generators.m_generators.reserve( 1+sizeof...(Gs) ); + generators.populate( std::move( generator ), std::forward<Gs>( moreGenerators )... ); + return generators; + } + template<typename T> + auto makeGenerators( Generator<T>&& generator ) -> Generators<T> { + Generators<T> generators; + generators.populate( std::move( generator ) ); + return generators; + } + template<typename T, typename... Gs> + auto makeGenerators( T&& val, Gs... moreGenerators ) -> Generators<T> { + return makeGenerators( value( std::forward<T>( val ) ), std::forward<Gs>( moreGenerators )... ); + } + template<typename T, typename U, typename... Gs> + auto makeGenerators( U&& val, Gs... moreGenerators ) -> Generators<T> { + return makeGenerators( value( T( std::forward<U>( val ) ) ), std::forward<Gs>( moreGenerators )... ); + } + + auto acquireGeneratorTracker( SourceLineInfo const& lineInfo ) -> IGeneratorTracker&; + + template<typename L> + // Note: The type after -> is weird, because VS2015 cannot parse + // the expression used in the typedef inside, when it is in + // return type. Yeah, ¯\_(ツ)_/¯ + auto generate( SourceLineInfo const& lineInfo, L const& generatorExpression ) -> decltype(std::declval<decltype(generatorExpression())>()[0]) { + using UnderlyingType = typename decltype(generatorExpression())::type; + + IGeneratorTracker& tracker = acquireGeneratorTracker( lineInfo ); + if( !tracker.hasGenerator() ) + tracker.setGenerator( pf::make_unique<Generators<UnderlyingType>>( generatorExpression() ) ); + + auto const& generator = static_cast<Generators<UnderlyingType> const&>( *tracker.getGenerator() ); + return generator[tracker.getIndex()]; + } + +} // namespace Generators +} // namespace Catch + +#define GENERATE( ... ) \ + Catch::Generators::generate( CATCH_INTERNAL_LINEINFO, []{ using namespace Catch::Generators; return makeGenerators( __VA_ARGS__ ); } ) + +// end catch_generators.hpp + +// 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&& 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, + NameAndTags const& nameAndTags, + 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, NameAndTags( 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, + NoTests = 0x02 + }; }; + + 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 bool warnAboutNoTests() 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 bool hasTestFilters() 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 + +#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; +#ifndef CATCH_CONFIG_DEFAULT_REPORTER +#define CATCH_CONFIG_DEFAULT_REPORTER "console" +#endif + std::string reporterName = CATCH_CONFIG_DEFAULT_REPORTER; +#undef CATCH_CONFIG_DEFAULT_REPORTER + + 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::string const& getReporterName() const; + + std::vector<std::string> const& getTestsOrTags() const; + std::vector<std::string> const& getSectionsToRun() const override; + + virtual TestSpec const& testSpec() const override; + bool hasTestFilters() 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; + bool warnAboutNoTests() 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; + bool m_hasTestFilters = false; + }; + +} // 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; + StringRef 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; + bool shouldReportAllAssertions = 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; + }; + +} // end namespace Catch + +// end catch_interfaces_reporter.h +#include <algorithm> +#include <cstring> +#include <cfloat> +#include <cstdio> +#include <cassert> +#include <memory> +#include <ostream> + +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; + if( !DerivedT::getSupportedVerbosities().count( m_config->verbosity() ) ) + CATCH_ERROR( "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; + if( !DerivedT::getSupportedVerbosities().count( m_config->verbosity() ) ) + CATCH_ERROR( "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 ); + + static std::set<Verbosity> getSupportedVerbosities(); + + 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, + BrightYellow = Bright | Yellow, + + // By intention + FileName = LightGrey, + Warning = BrightYellow, + ResultError = BrightRed, + ResultSuccess = BrightGreen, + ResultExpectedFailure = Warning, + + Error = BrightRed, + Success = Green, + + OriginalExpression = Cyan, + ReconstructedExpression = BrightYellow, + + 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: + + explicit 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 +// Allow users to base their work off existing reporters +// start catch_reporter_compact.h + +namespace Catch { + + struct CompactReporter : StreamingReporterBase<CompactReporter> { + + using StreamingReporterBase::StreamingReporterBase; + + ~CompactReporter() override; + + static std::string getDescription(); + + ReporterPreferences getPreferences() const override; + + void noMatchingTestCases(std::string const& spec) override; + + void assertionStarting(AssertionInfo const&) override; + + bool assertionEnded(AssertionStats const& _assertionStats) override; + + void sectionEnded(SectionStats const& _sectionStats) override; + + void testRunEnded(TestRunStats const& _testRunStats) override; + + }; + +} // end namespace Catch + +// end catch_reporter_compact.h +// start catch_reporter_console.h + +#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 { + // Fwd decls + struct SummaryColumn; + class TablePrinter; + + struct ConsoleReporter : StreamingReporterBase<ConsoleReporter> { + std::unique_ptr<TablePrinter> m_tablePrinter; + + ConsoleReporter(ReporterConfig const& config); + ~ConsoleReporter() override; + static std::string getDescription(); + + void noMatchingTestCases(std::string const& spec) override; + + void assertionStarting(AssertionInfo const&) override; + + bool assertionEnded(AssertionStats const& _assertionStats) override; + + void sectionStarting(SectionInfo const& _sectionInfo) override; + void sectionEnded(SectionStats const& _sectionStats) override; + + void benchmarkStarting(BenchmarkInfo const& info) override; + void benchmarkEnded(BenchmarkStats const& stats) override; + + void testCaseEnded(TestCaseStats const& _testCaseStats) override; + void testGroupEnded(TestGroupStats const& _testGroupStats) override; + void testRunEnded(TestRunStats const& _testRunStats) override; + + private: + + void lazyPrint(); + + void lazyPrintWithoutClosingBenchmarkTable(); + void lazyPrintRunInfo(); + void lazyPrintGroupInfo(); + void printTestCaseAndSectionHeader(); + + void printClosedHeader(std::string const& _name); + void printOpenHeader(std::string const& _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); + + void printTotals(Totals const& totals); + void printSummaryRow(std::string const& label, std::vector<SummaryColumn> const& cols, std::size_t row); + + void printTotalsDivider(Totals const& totals); + void printSummaryDivider(); + + private: + bool m_headerPrinted = false; + }; + +} // end namespace Catch + +#if defined(_MSC_VER) +#pragma warning(pop) +#endif + +// end catch_reporter_console.h +// start catch_reporter_junit.h + +// start catch_xmlwriter.h + +#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 ) { + ReusableStringStream rss; + rss << attribute; + return writeAttribute( name, rss.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; + }; + +} + +// end catch_xmlwriter.h +namespace Catch { + + class JunitReporter : public CumulativeReporterBase<JunitReporter> { + public: + JunitReporter(ReporterConfig const& _config); + + ~JunitReporter() override; + + static std::string getDescription(); + + void noMatchingTestCases(std::string const& /*spec*/) override; + + void testRunStarting(TestRunInfo const& runInfo) override; + + void testGroupStarting(GroupInfo const& groupInfo) override; + + void testCaseStarting(TestCaseInfo const& testCaseInfo) override; + bool assertionEnded(AssertionStats const& assertionStats) override; + + void testCaseEnded(TestCaseStats const& testCaseStats) override; + + void testGroupEnded(TestGroupStats const& testGroupStats) override; + + void testRunEndedCumulative() override; + + void writeGroup(TestGroupNode const& groupNode, double suiteTime); + + void writeTestCase(TestCaseNode const& testCaseNode); + + void writeSection(std::string const& className, + std::string const& rootName, + SectionNode const& sectionNode); + + void writeAssertions(SectionNode const& sectionNode); + void writeAssertion(AssertionStats const& stats); + + XmlWriter xml; + Timer suiteTimer; + std::string stdOutForSuite; + std::string stdErrForSuite; + unsigned int unexpectedExceptions = 0; + bool m_okToFail = false; + }; + +} // end namespace Catch + +// end catch_reporter_junit.h +// start catch_reporter_xml.h + +namespace Catch { + class XmlReporter : public StreamingReporterBase<XmlReporter> { + public: + XmlReporter(ReporterConfig const& _config); + + ~XmlReporter() override; + + static std::string getDescription(); + + virtual std::string getStylesheetRef() const; + + void writeSourceInfo(SourceLineInfo const& sourceInfo); + + public: // StreamingReporterBase + + void noMatchingTestCases(std::string const& s) override; + + void testRunStarting(TestRunInfo const& testInfo) override; + + void testGroupStarting(GroupInfo const& groupInfo) override; + + void testCaseStarting(TestCaseInfo const& testInfo) override; + + void sectionStarting(SectionInfo const& sectionInfo) override; + + void assertionStarting(AssertionInfo const&) override; + + 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; + + private: + Timer m_testCaseTimer; + XmlWriter m_xml; + int m_sectionDepth = 0; + }; + +} // end namespace Catch + +// end catch_reporter_xml.h + +// end catch_external_interfaces.h +#endif + +#endif // ! CATCH_CONFIG_IMPL_ONLY + +#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 + }; + + 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(); + ~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 ); + } + + Approx Approx::operator-() const { + auto temp(*this); + temp.m_value = -temp.m_value; + return temp; + } + + std::string Approx::toString() const { + ReusableStringStream rss; + rss << "Approx( " << ::Catch::Detail::stringify( m_value ) << " )"; + return rss.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))); + } + + void Approx::setMargin(double margin) { + CATCH_ENFORCE(margin >= 0, + "Invalid Approx::margin: " << margin << '.' + << " Approx::Margin has to be non-negative."); + m_margin = margin; + } + + void Approx::setEpsilon(double epsilon) { + CATCH_ENFORCE(epsilon >= 0 && epsilon <= 1.0, + "Invalid Approx::epsilon: " << epsilon << '.' + << " Approx::epsilon has to be in [0, 1]"); + m_epsilon = epsilon; + } + +} // end namespace Detail + +namespace literals { + Detail::Approx operator "" _a(long double val) { + return Detail::Approx(val); + } + Detail::Approx operator "" _a(unsigned long long val) { + return Detail::Approx(val); + } +} // end namespace literals + +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; + struct IMutableContext; + + using IConfigPtr = std::shared_ptr<IConfig const>; + + struct IContext + { + virtual ~IContext(); + + virtual IResultCapture* getResultCapture() = 0; + virtual IRunner* getRunner() = 0; + virtual IConfigPtr const& 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; + + private: + static IMutableContext *currentContext; + friend IMutableContext& getCurrentMutableContext(); + friend void cleanUpContext(); + static void createContext(); + }; + + inline IMutableContext& getCurrentMutableContext() + { + if( !IMutableContext::currentContext ) + IMutableContext::createContext(); + return *IMutableContext::currentContext; + } + + inline IContext& getCurrentContext() + { + return getCurrentMutableContext(); + } + + void cleanUpContext(); +} + +// end catch_context.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 + namespace Catch { + inline void doNothing() {} + } + #define CATCH_BREAK_INTO_DEBUGGER() Catch::doNothing() +#endif + +// end catch_debugger.h +// start catch_run_context.h + +// start catch_fatal_condition.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 +#if defined( CATCH_CONFIG_WINDOWS_SEH ) + +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 + +#elif defined ( CATCH_CONFIG_POSIX_SIGNALS ) + +#include <signal.h> + +namespace Catch { + + struct FatalConditionHandler { + + static bool isSet; + static struct sigaction oldSigActions[]; + static stack_t oldSigStack; + static char altStackMem[]; + + static void handleSignal( int sig ); + + FatalConditionHandler(); + ~FatalConditionHandler(); + static void reset(); + }; + +} // namespace Catch + +#else + +namespace Catch { + struct FatalConditionHandler { + void reset(); + }; +} + +#endif + +// end catch_fatal_condition.h +#include <string> + +namespace Catch { + + struct IMutableContext; + + /////////////////////////////////////////////////////////////////////////// + + class RunContext : public IResultCapture, public IRunner { + + public: + RunContext( RunContext const& ) = delete; + RunContext& operator =( RunContext const& ) = delete; + + explicit RunContext( IConfigPtr const& _config, IStreamingReporterPtr&& reporter ); + + ~RunContext() override; + + 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; + + public: // IResultCapture + + // Assertion handlers + void handleExpr + ( AssertionInfo const& info, + ITransientExpression const& expr, + AssertionReaction& reaction ) override; + void handleMessage + ( AssertionInfo const& info, + ResultWas::OfType resultType, + StringRef const& message, + AssertionReaction& reaction ) override; + void handleUnexpectedExceptionNotThrown + ( AssertionInfo const& info, + AssertionReaction& reaction ) override; + void handleUnexpectedInflightException + ( AssertionInfo const& info, + std::string const& message, + AssertionReaction& reaction ) override; + void handleIncomplete + ( AssertionInfo const& info ) override; + void handleNonExpr + ( AssertionInfo const &info, + ResultWas::OfType resultType, + AssertionReaction &reaction ) override; + + bool sectionStarted( SectionInfo const& sectionInfo, Counts& assertions ) override; + + void sectionEnded( SectionEndInfo const& endInfo ) override; + void sectionEndedEarly( SectionEndInfo const& endInfo ) override; + + auto acquireGeneratorTracker( SourceLineInfo const& lineInfo ) -> IGeneratorTracker& 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; + + public: + // !TBD We need to do this another way! + bool aborting() const final; + + private: + + void runCurrentTest( std::string& redirectedCout, std::string& redirectedCerr ); + void invokeActiveTestCase(); + + void resetAssertionInfo(); + bool testForMissingAssertions( Counts& assertions ); + + void assertionEnded( AssertionResult const& result ); + void reportExpr + ( AssertionInfo const &info, + ResultWas::OfType resultType, + ITransientExpression const *expr, + bool negated ); + + void populateReaction( AssertionReaction& reaction ); + + 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; + bool m_lastAssertionPassed = false; + bool m_shouldReportUnexpected = true; + bool m_includeSuccessfulResults; + }; + +} // end namespace Catch + +// end catch_run_context.h +namespace Catch { + + namespace { + 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 const& macroName, + SourceLineInfo const& lineInfo, + StringRef capturedExpression, + ResultDisposition::Flags resultDisposition ) + : m_assertionInfo{ macroName, lineInfo, capturedExpression, resultDisposition }, + m_resultCapture( getResultCapture() ) + {} + + void AssertionHandler::handleExpr( ITransientExpression const& expr ) { + m_resultCapture.handleExpr( m_assertionInfo, expr, m_reaction ); + } + void AssertionHandler::handleMessage(ResultWas::OfType resultType, StringRef const& message) { + m_resultCapture.handleMessage( m_assertionInfo, resultType, message, m_reaction ); + } + + auto AssertionHandler::allowThrows() const -> bool { + return getCurrentContext().getConfig()->allowThrows(); + } + + void AssertionHandler::complete() { + setCompleted(); + if( m_reaction.shouldDebugBreak ) { + + // If you find your debugger stopping you here then go one level up on the + // call-stack for the code that caused it (typically a failed assertion) + + // (To go back to the test and change execution, jump over the throw, next) + CATCH_BREAK_INTO_DEBUGGER(); + } + if (m_reaction.shouldThrow) { +#if !defined(CATCH_CONFIG_DISABLE_EXCEPTIONS) + throw Catch::TestFailureException(); +#else + CATCH_ERROR( "Test failure requires aborting test!" ); +#endif + } + } + void AssertionHandler::setCompleted() { + m_completed = true; + } + + void AssertionHandler::handleUnexpectedInflightException() { + m_resultCapture.handleUnexpectedInflightException( m_assertionInfo, Catch::translateActiveException(), m_reaction ); + } + + void AssertionHandler::handleExceptionThrownAsExpected() { + m_resultCapture.handleNonExpr(m_assertionInfo, ResultWas::Ok, m_reaction); + } + void AssertionHandler::handleExceptionNotThrownAsExpected() { + m_resultCapture.handleNonExpr(m_assertionInfo, ResultWas::Ok, m_reaction); + } + + void AssertionHandler::handleUnexpectedExceptionNotThrown() { + m_resultCapture.handleUnexpectedExceptionNotThrown( m_assertionInfo, m_reaction ); + } + + void AssertionHandler::handleThrowingCallSkipped() { + m_resultCapture.handleNonExpr(m_assertionInfo, ResultWas::Ok, m_reaction); + } + + // 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 const& 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 ) { + ReusableStringStream rss; + rss << lazyExpression; + reconstructedExpression = rss.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 "!(" + 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; + } + + StringRef 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_assertionhandler.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 const& matcherString ) { + std::string exceptionMessage = Catch::translateActiveException(); + MatchExpr<std::string, StringMatcher const&> expr( exceptionMessage, matcher, matcherString ); + handler.handleExpr( 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 +// Copyright 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) +// +// See https://github.com/philsquared/Clara for more details + +// Clara v1.1.5 + + +#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 + +#ifndef CLARA_CONFIG_OPTIONAL_TYPE +#ifdef __has_include +#if __has_include(<optional>) && __cplusplus >= 201703L +#include <optional> +#define CLARA_CONFIG_OPTIONAL_TYPE std::optional +#endif +#endif +#endif + +// ----------- #included from clara_textflow.hpp ----------- + +// TextFlowCpp +// +// A single-header library for wrapping and laying out basic text, by Phil Nash +// +// Distributed under the Boost Software License, Version 1.0. (See accompanying +// file LICENSE.txt or copy at http://www.boost.org/LICENSE_1_0.txt) +// +// 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: + using difference_type = std::ptrdiff_t; + using value_type = std::string; + using pointer = value_type * ; + using reference = value_type & ; + using iterator_category = std::forward_iterator_tag; + + 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); + return addIndentAndSuffix(line().substr(m_pos, m_len)); + } + + 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: + using difference_type = std::ptrdiff_t; + using value_type = std::string; + using pointer = value_type * ; + using reference = value_type & ; + using iterator_category = std::forward_iterator_tag; + + 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; +} +} + +} +} + +// ----------- end of #include from clara_textflow.hpp ----------- +// ........... back in clara.hpp + +#include <string> +#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 const* const* argv ) + : m_exeName(argv[0]), + m_args(argv + 1, argv + argc) {} + + 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() override { + 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: + void enforceOk() const override { + + // Errors shouldn't reach this point, but if they do + // the actual error message will be in m_errorMessage + assert( m_type != ResultBase::LogicError ); + assert( m_type != ResultBase::RuntimeError ); + if( m_type != ResultBase::Ok ) + std::abort(); + } + + 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 ); + } +#ifdef CLARA_CONFIG_OPTIONAL_TYPE + template<typename T> + inline auto convertInto( std::string const &source, CLARA_CONFIG_OPTIONAL_TYPE<T>& target ) -> ParserResult { + T temp; + auto result = convertInto( source, temp ); + if( result ) + target = std::move(temp); + return result; + } +#endif // CLARA_CONFIG_OPTIONAL_TYPE + + struct NonCopyable { + NonCopyable() = default; + NonCopyable( NonCopyable const & ) = delete; + NonCopyable( NonCopyable && ) = delete; + NonCopyable &operator=( NonCopyable const & ) = delete; + NonCopyable &operator=( NonCopyable && ) = delete; + }; + + struct BoundRef : NonCopyable { + virtual ~BoundRef() = default; + virtual auto isContainer() const -> bool { return false; } + virtual auto isFlag() const -> bool { return false; } + }; + struct BoundValueRefBase : BoundRef { + virtual auto setValue( std::string const &arg ) -> ParserResult = 0; + }; + struct BoundFlagRefBase : BoundRef { + virtual auto setFlag( bool flag ) -> ParserResult = 0; + virtual auto isFlag() const -> bool { return true; } + }; + + template<typename T> + struct BoundValueRef : BoundValueRefBase { + T &m_ref; + + explicit BoundValueRef( T &ref ) : m_ref( ref ) {} + + auto setValue( std::string const &arg ) -> ParserResult override { + return convertInto( arg, m_ref ); + } + }; + + template<typename T> + struct BoundValueRef<std::vector<T>> : BoundValueRefBase { + std::vector<T> &m_ref; + + explicit BoundValueRef( 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; + + 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<BoundRef> m_ref; + std::string m_hint; + std::string m_description; + + explicit ParserRefImpl( std::shared_ptr<BoundRef> const &ref ) : m_ref( ref ) {} + + public: + template<typename T> + ParserRefImpl( T &ref, std::string const &hint ) + : m_ref( std::make_shared<BoundValueRef<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<BoundValueRefBase> m_ref; + + template<typename LambdaT> + static auto makeRef(LambdaT const &lambda) -> std::shared_ptr<BoundValueRefBase> { + 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<BoundValueRef<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 ) ); + + assert( !m_ref->isFlag() ); + auto valueRef = static_cast<detail::BoundValueRefBase*>( m_ref.get() ); + + auto result = valueRef->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 flagRef = static_cast<detail::BoundFlagRefBase*>( m_ref.get() ); + auto result = flagRef->setFlag( true ); + if( !result ) + return InternalParseResult( result ); + if( result.value() == ParseResultType::ShortCircuitAll ) + return InternalParseResult::ok( ParseState( result.value(), remainingTokens ) ); + } else { + auto valueRef = static_cast<detail::BoundValueRefBase*>( m_ref.get() ); + ++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 = valueRef->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; + } + + // Forward deprecated interface with '+' instead of '|' + template<typename T> + auto operator+=( T const &other ) -> Parser & { return operator|=( other ); } + template<typename T> + auto operator+( T const &other ) const -> Parser { return operator|( 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); + + optWidth = (std::min)(optWidth, consoleWidth/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 ) { + auto warningSet = [&]() { + if( warning == "NoAssertions" ) + return WarnAbout::NoAssertions; + + if ( warning == "NoTests" ) + return WarnAbout::NoTests; + + return WarnAbout::Nothing; + }(); + + if (warningSet == WarnAbout::Nothing) + return ParserResult::runtimeError( "Unrecognised warning: '" + warning + "'" ); + config.warnings = static_cast<WarnAbout::What>( config.warnings | warningSet ); + 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 const setReporter = [&]( std::string const& reporter ) { + IReporterRegistry::FactoryMap const& factories = getRegistryHub().getReporterRegistry().getFactories(); + + auto lcReporter = toLower( reporter ); + auto result = factories.find( lcReporter ); + + if( factories.end() != result ) + config.reporterName = lcReporter; + else + return ParserResult::runtimeError( "Unrecognized reporter, '" + reporter + "'. Check available with --list-reporters" ); + 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( setReporter, "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 { + + 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 { + // We can assume that the same file will usually have the same pointer. + // Thus, if the pointers are the same, there is no point in calling the strcmp + return line < other.line || ( line == other.line && file != other.file && (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; + } + + 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() ) + { + TestSpecParser parser(ITagAliasRegistry::get()); + if (data.testsOrTags.empty()) { + parser.parse("~[.]"); // All not hidden tests + } + else { + m_hasTestFilters = true; + 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::string const& Config::getReporterName() const { return m_data.reporterName; } + + std::vector<std::string> const& Config::getTestsOrTags() const { return m_data.testsOrTags; } + std::vector<std::string> const& Config::getSectionsToRun() const { return m_data.sectionsToRun; } + + TestSpec const& Config::testSpec() const { return m_testSpec; } + bool Config::hasTestFilters() const { return m_hasTestFilters; } + + 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); } + bool Config::warnAboutNoTests() const { return !!(m_data.warnings & WarnAbout::NoTests); } + 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() { + return Catch::makeStream(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 +#include <sstream> + +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::BrightYellow: return setTextAttribute( FOREGROUND_INTENSITY | FOREGROUND_RED | FOREGROUND_GREEN ); + + case Colour::Bright: CATCH_INTERNAL_ERROR( "not a colour" ); + + default: + CATCH_ERROR( "Unknown colour requested" ); + } + } + + 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::BrightYellow: return setColour( "[1;33m" ); + + case Colour::Bright: CATCH_INTERNAL_ERROR( "not a colour" ); + default: CATCH_INTERNAL_ERROR( "Unknown colour requested" ); + } + } + 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 +#if !(defined(__DJGPP__) && defined(__STRICT_ANSI__)) + isatty(STDOUT_FILENO) +#else + false +#endif + ; + } + 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 const& 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; + }; + + IMutableContext *IMutableContext::currentContext = nullptr; + + void IMutableContext::createContext() + { + currentContext = new Context(); + } + + void cleanUpContext() { + delete IMutableContext::currentContext; + IMutableContext::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> +# include <cstddef> +# include <ostream> + +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_enforce.cpp + +namespace Catch { +#if defined(CATCH_CONFIG_DISABLE_EXCEPTIONS) && !defined(CATCH_CONFIG_DISABLE_EXCEPTIONS_CUSTOM_HANDLER) + [[noreturn]] + void throw_exception(std::exception const& e) { + Catch::cerr() << "Catch will terminate because it needed to throw an exception.\n" + << "The message was: " << e.what() << '\n'; + std::terminate(); + } +#endif +} // namespace Catch; +// end catch_enforce.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 ) ); + } + +#if !defined(CATCH_CONFIG_DISABLE_EXCEPTIONS) + 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 + // Compiling a mixed mode project with MSVC means that CLR + // exceptions will be caught in (...) as well. However, these + // do not fill-in std::current_exception and thus lead to crash + // when attempting rethrow. + // /EHa switch also causes structured exceptions to be caught + // here, but they fill-in current_exception properly, so + // at worst the output should be a little weird, instead of + // causing a crash. + if (std::current_exception() == nullptr) { + return "Non C++ exception. Possibly a CLR exception."; + } + 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"; + } + } + +#else // ^^ Exceptions are enabled // Exceptions are disabled vv + std::string ExceptionTranslatorRegistry::translateActiveException() const { + CATCH_INTERNAL_ERROR("Attempted to translate active exception under CATCH_CONFIG_DISABLE_EXCEPTIONS!"); + } +#endif + + 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 + +#if defined(__GNUC__) +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wmissing-field-initializers" +#endif + +#if defined( CATCH_CONFIG_WINDOWS_SEH ) || defined( CATCH_CONFIG_POSIX_SIGNALS ) + +namespace { + // Report the error condition + void reportFatal( char const * const message ) { + Catch::getCurrentContext().getResultCapture()->handleFatalErrorCondition( message ); + } +} + +#endif // signals/SEH handling + +#if defined( CATCH_CONFIG_WINDOWS_SEH ) + +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) { + 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 + +#elif defined( CATCH_CONFIG_POSIX_SIGNALS ) + +namespace Catch { + + struct SignalDefs { + int id; + const char* name; + }; + + // 32kb for the alternate stack seems to be sufficient. However, this value + // is experimentally determined, so that's not guaranteed. + constexpr static std::size_t sigStackSize = 32768 >= MINSIGSTKSZ ? 32768 : MINSIGSTKSZ; + + 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 = sigStackSize; + 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[sigStackSize] = {}; + +} // namespace Catch + +#else + +namespace Catch { + void FatalConditionHandler::reset() {} +} + +#endif // signals/SEH handling + +#if defined(__GNUC__) +# pragma GCC diagnostic pop +#endif +// end catch_fatal_condition.cpp +// start catch_generators.cpp + +// start catch_random_number_generator.h + +#include <algorithm> +#include <random> + +namespace Catch { + + struct IConfig; + + std::mt19937& rng(); + void seedRng( IConfig const& config ); + unsigned int rngSeed(); + +} + +// end catch_random_number_generator.h +#include <limits> +#include <set> + +namespace Catch { + +IGeneratorTracker::~IGeneratorTracker() {} + +namespace Generators { + + GeneratorBase::~GeneratorBase() {} + + std::vector<size_t> randomiseIndices( size_t selectionSize, size_t sourceSize ) { + + assert( selectionSize <= sourceSize ); + std::vector<size_t> indices; + indices.reserve( selectionSize ); + std::uniform_int_distribution<size_t> uid( 0, sourceSize-1 ); + + std::set<size_t> seen; + // !TBD: improve this algorithm + while( indices.size() < selectionSize ) { + auto index = uid( rng() ); + if( seen.insert( index ).second ) + indices.push_back( index ); + } + return indices; + } + + auto acquireGeneratorTracker( SourceLineInfo const& lineInfo ) -> IGeneratorTracker& { + return getResultCapture().acquireGeneratorTracker( lineInfo ); + } + + template<> + auto all<int>() -> Generator<int> { + return range( std::numeric_limits<int>::min(), std::numeric_limits<int>::max() ); + } + +} // namespace Generators +} // namespace Catch +// end catch_generators.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_listening.h + +namespace Catch { + + class ListeningReporter : public IStreamingReporter { + using Reporters = std::vector<IStreamingReporterPtr>; + Reporters m_listeners; + IStreamingReporterPtr m_reporter = nullptr; + ReporterPreferences m_preferences; + + public: + ListeningReporter(); + + void addListener( IStreamingReporterPtr&& listener ); + void addReporter( 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_listening.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; + +} // 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 + +#ifdef CATCH_CONFIG_WINDOWS_CRTDBG +#include <crtdbg.h> + +namespace Catch { + + 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 + + Catch::LeakDetector::LeakDetector() {} + +#endif + +Catch::LeakDetector::~LeakDetector() { + Catch::cleanUp(); +} +// 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(); + + 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.hasTestFilters() ) + Catch::cout() << "Matching test cases:\n"; + else { + Catch::cout() << "All available test cases:\n"; + } + + 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.hasTestFilters() ) + 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(); + 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.hasTestFilters() ) + Catch::cout() << "Tags for matching test cases:\n"; + else { + Catch::cout() << "All available tags:\n"; + } + + 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 ) { + ReusableStringStream rss; + rss << " " << std::setw(2) << tagCount.second.count << " "; + auto str = rss.str(); + auto wrapper = Column( tagCount.second.all() ) + .initialIndent( 0 ) + .indent( str.size() ) + .width( CATCH_CONFIG_CONSOLE_WIDTH-10 ); + Catch::cout() << str << wrapper << '\n'; + } + Catch::cout() << pluralise( tagCounts.size(), "tag" ) << '\n' << std::endl; + return tagCounts.size(); + } + + std::size_t listReporters() { + 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(); + 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_floating.cpp + +// start catch_polyfills.hpp + +namespace Catch { + bool isnan(float f); + bool isnan(double d); +} + +// end catch_polyfills.hpp +// start catch_to_string.hpp + +#include <string> + +namespace Catch { + template <typename T> + std::string to_string(T const& t) { +#if defined(CATCH_CONFIG_CPP11_TO_STRING) + return std::to_string(t); +#else + ReusableStringStream rss; + rss << t; + return rss.str(); +#endif + } +} // end namespace Catch + +// end catch_to_string.hpp +#include <cstdlib> +#include <cstdint> +#include <cstring> + +namespace Catch { +namespace Matchers { +namespace Floating { +enum class FloatingPointKind : uint8_t { + Float, + Double +}; +} +} +} + +namespace { + +template <typename T> +struct Converter; + +template <> +struct Converter<float> { + static_assert(sizeof(float) == sizeof(int32_t), "Important ULP matcher assumption violated"); + Converter(float f) { + std::memcpy(&i, &f, sizeof(f)); + } + int32_t i; +}; + +template <> +struct Converter<double> { + static_assert(sizeof(double) == sizeof(int64_t), "Important ULP matcher assumption violated"); + Converter(double d) { + std::memcpy(&i, &d, sizeof(d)); + } + int64_t i; +}; + +template <typename T> +auto convert(T t) -> Converter<T> { + return Converter<T>(t); +} + +template <typename FP> +bool almostEqualUlps(FP lhs, FP rhs, int maxUlpDiff) { + // Comparison with NaN should always be false. + // This way we can rule it out before getting into the ugly details + if (Catch::isnan(lhs) || Catch::isnan(rhs)) { + return false; + } + + auto lc = convert(lhs); + auto rc = convert(rhs); + + if ((lc.i < 0) != (rc.i < 0)) { + // Potentially we can have +0 and -0 + return lhs == rhs; + } + + auto ulpDiff = std::abs(lc.i - rc.i); + return ulpDiff <= maxUlpDiff; +} + +} + +namespace Catch { +namespace Matchers { +namespace Floating { + WithinAbsMatcher::WithinAbsMatcher(double target, double margin) + :m_target{ target }, m_margin{ margin } { + CATCH_ENFORCE(margin >= 0, "Invalid margin: " << margin << '.' + << " Margin has to be non-negative."); + } + + // Performs equivalent check of std::fabs(lhs - rhs) <= margin + // But without the subtraction to allow for INFINITY in comparison + bool WithinAbsMatcher::match(double const& matchee) const { + return (matchee + m_margin >= m_target) && (m_target + m_margin >= matchee); + } + + std::string WithinAbsMatcher::describe() const { + return "is within " + ::Catch::Detail::stringify(m_margin) + " of " + ::Catch::Detail::stringify(m_target); + } + + WithinUlpsMatcher::WithinUlpsMatcher(double target, int ulps, FloatingPointKind baseType) + :m_target{ target }, m_ulps{ ulps }, m_type{ baseType } { + CATCH_ENFORCE(ulps >= 0, "Invalid ULP setting: " << ulps << '.' + << " ULPs have to be non-negative."); + } + +#if defined(__clang__) +#pragma clang diagnostic push +// Clang <3.5 reports on the default branch in the switch below +#pragma clang diagnostic ignored "-Wunreachable-code" +#endif + + bool WithinUlpsMatcher::match(double const& matchee) const { + switch (m_type) { + case FloatingPointKind::Float: + return almostEqualUlps<float>(static_cast<float>(matchee), static_cast<float>(m_target), m_ulps); + case FloatingPointKind::Double: + return almostEqualUlps<double>(matchee, m_target, m_ulps); + default: + CATCH_INTERNAL_ERROR( "Unknown FloatingPointKind value" ); + } + } + +#if defined(__clang__) +#pragma clang diagnostic pop +#endif + + std::string WithinUlpsMatcher::describe() const { + return "is within " + Catch::to_string(m_ulps) + " ULPs of " + ::Catch::Detail::stringify(m_target) + ((m_type == FloatingPointKind::Float)? "f" : ""); + } + +}// namespace Floating + +Floating::WithinUlpsMatcher WithinULP(double target, int maxUlpDiff) { + return Floating::WithinUlpsMatcher(target, maxUlpDiff, Floating::FloatingPointKind::Double); +} + +Floating::WithinUlpsMatcher WithinULP(float target, int maxUlpDiff) { + return Floating::WithinUlpsMatcher(target, maxUlpDiff, Floating::FloatingPointKind::Float); +} + +Floating::WithinAbsMatcher WithinAbs(double target, double margin) { + return Floating::WithinAbsMatcher(target, margin); +} + +} // namespace Matchers +} // namespace Catch + +// end catch_matchers_floating.cpp +// start catch_matchers_generic.cpp + +std::string Catch::Matchers::Generic::Detail::finalizeDescription(const std::string& desc) { + if (desc.empty()) { + return "matches undescribed predicate"; + } else { + return "matches predicate: \"" + desc + '"'; + } +} +// end catch_matchers_generic.cpp +// start catch_matchers_string.cpp + +#include <regex> + +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 ); + } + + RegexMatcher::RegexMatcher(std::string regex, CaseSensitive::Choice caseSensitivity): m_regex(std::move(regex)), m_caseSensitivity(caseSensitivity) {} + + bool RegexMatcher::match(std::string const& matchee) const { + auto flags = std::regex::ECMAScript; // ECMAScript is the default syntax option anyway + if (m_caseSensitivity == CaseSensitive::Choice::No) { + flags |= std::regex::icase; + } + auto reg = std::regex(m_regex, flags); + return std::regex_match(matchee, reg); + } + + std::string RegexMatcher::describe() const { + return "matches " + ::Catch::Detail::stringify(m_regex) + ((m_caseSensitivity == CaseSensitive::Choice::Yes)? " case sensitively" : " case insensitively"); + } + + } // 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) ); + } + + StdString::RegexMatcher Matches(std::string const& regex, CaseSensitive::Choice caseSensitivity) { + return StdString::RegexMatcher(regex, caseSensitivity); + } + +} // namespace Matchers +} // namespace Catch +// end catch_matchers_string.cpp +// start catch_message.cpp + +// start catch_uncaught_exceptions.h + +namespace Catch { + bool uncaught_exceptions(); +} // end namespace Catch + +// end catch_uncaught_exceptions.h +#include <cassert> +#include <stack> + +namespace Catch { + + MessageInfo::MessageInfo( StringRef 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( StringRef 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 ( !uncaught_exceptions() ){ + getResultCapture().popScopedMessage(m_info); + } + } + + Capturer::Capturer( StringRef macroName, SourceLineInfo const& lineInfo, ResultWas::OfType resultType, StringRef names ) { + auto trimmed = [&] (size_t start, size_t end) { + while (names[start] == ',' || isspace(names[start])) { + ++start; + } + while (names[end] == ',' || isspace(names[end])) { + --end; + } + return names.substr(start, end - start + 1); + }; + + size_t start = 0; + std::stack<char> openings; + for (size_t pos = 0; pos < names.size(); ++pos) { + char c = names[pos]; + switch (c) { + case '[': + case '{': + case '(': + // It is basically impossible to disambiguate between + // comparison and start of template args in this context +// case '<': + openings.push(c); + break; + case ']': + case '}': + case ')': +// case '>': + openings.pop(); + break; + case ',': + if (start != pos && openings.size() == 0) { + m_messages.emplace_back(macroName, lineInfo, resultType); + m_messages.back().message = trimmed(start, pos); + m_messages.back().message += " := "; + start = pos; + } + } + } + assert(openings.size() == 0 && "Mismatched openings"); + m_messages.emplace_back(macroName, lineInfo, resultType); + m_messages.back().message = trimmed(start, names.size() - 1); + m_messages.back().message += " := "; + } + Capturer::~Capturer() { + if ( !uncaught_exceptions() ){ + assert( m_captured == m_messages.size() ); + for( size_t i = 0; i < m_captured; ++i ) + m_resultCapture.popScopedMessage( m_messages[i] ); + } + } + + void Capturer::captureValue( size_t index, std::string const& value ) { + assert( index < m_messages.size() ); + m_messages[index].message += value; + m_resultCapture.pushScopedMessage( m_messages[index] ); + m_captured++; + } + +} // end namespace Catch +// end catch_message.cpp +// start catch_output_redirect.cpp + +// start catch_output_redirect.h +#ifndef TWOBLUECUBES_CATCH_OUTPUT_REDIRECT_H +#define TWOBLUECUBES_CATCH_OUTPUT_REDIRECT_H + +#include <cstdio> +#include <iosfwd> +#include <string> + +namespace Catch { + + class RedirectedStream { + std::ostream& m_originalStream; + std::ostream& m_redirectionStream; + std::streambuf* m_prevBuf; + + public: + RedirectedStream( std::ostream& originalStream, std::ostream& redirectionStream ); + ~RedirectedStream(); + }; + + class RedirectedStdOut { + ReusableStringStream m_rss; + RedirectedStream m_cout; + public: + RedirectedStdOut(); + auto str() const -> std::string; + }; + + // 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 + class RedirectedStdErr { + ReusableStringStream m_rss; + RedirectedStream m_cerr; + RedirectedStream m_clog; + public: + RedirectedStdErr(); + auto str() const -> std::string; + }; + +#if defined(CATCH_CONFIG_NEW_CAPTURE) + + // Windows's implementation of std::tmpfile is terrible (it tries + // to create a file inside system folder, thus requiring elevated + // privileges for the binary), so we have to use tmpnam(_s) and + // create the file ourselves there. + class TempFile { + public: + TempFile(TempFile const&) = delete; + TempFile& operator=(TempFile const&) = delete; + TempFile(TempFile&&) = delete; + TempFile& operator=(TempFile&&) = delete; + + TempFile(); + ~TempFile(); + + std::FILE* getFile(); + std::string getContents(); + + private: + std::FILE* m_file = nullptr; + #if defined(_MSC_VER) + char m_buffer[L_tmpnam] = { 0 }; + #endif + }; + + class OutputRedirect { + public: + OutputRedirect(OutputRedirect const&) = delete; + OutputRedirect& operator=(OutputRedirect const&) = delete; + OutputRedirect(OutputRedirect&&) = delete; + OutputRedirect& operator=(OutputRedirect&&) = delete; + + OutputRedirect(std::string& stdout_dest, std::string& stderr_dest); + ~OutputRedirect(); + + private: + int m_originalStdout = -1; + int m_originalStderr = -1; + TempFile m_stdoutFile; + TempFile m_stderrFile; + std::string& m_stdoutDest; + std::string& m_stderrDest; + }; + +#endif + +} // end namespace Catch + +#endif // TWOBLUECUBES_CATCH_OUTPUT_REDIRECT_H +// end catch_output_redirect.h +#include <cstdio> +#include <cstring> +#include <fstream> +#include <sstream> +#include <stdexcept> + +#if defined(CATCH_CONFIG_NEW_CAPTURE) + #if defined(_MSC_VER) + #include <io.h> //_dup and _dup2 + #define dup _dup + #define dup2 _dup2 + #define fileno _fileno + #else + #include <unistd.h> // dup and dup2 + #endif +#endif + +namespace Catch { + + RedirectedStream::RedirectedStream( std::ostream& originalStream, std::ostream& redirectionStream ) + : m_originalStream( originalStream ), + m_redirectionStream( redirectionStream ), + m_prevBuf( m_originalStream.rdbuf() ) + { + m_originalStream.rdbuf( m_redirectionStream.rdbuf() ); + } + + RedirectedStream::~RedirectedStream() { + m_originalStream.rdbuf( m_prevBuf ); + } + + RedirectedStdOut::RedirectedStdOut() : m_cout( Catch::cout(), m_rss.get() ) {} + auto RedirectedStdOut::str() const -> std::string { return m_rss.str(); } + + RedirectedStdErr::RedirectedStdErr() + : m_cerr( Catch::cerr(), m_rss.get() ), + m_clog( Catch::clog(), m_rss.get() ) + {} + auto RedirectedStdErr::str() const -> std::string { return m_rss.str(); } + +#if defined(CATCH_CONFIG_NEW_CAPTURE) + +#if defined(_MSC_VER) + TempFile::TempFile() { + if (tmpnam_s(m_buffer)) { + CATCH_RUNTIME_ERROR("Could not get a temp filename"); + } + if (fopen_s(&m_file, m_buffer, "w")) { + char buffer[100]; + if (strerror_s(buffer, errno)) { + CATCH_RUNTIME_ERROR("Could not translate errno to a string"); + } + CATCH_RUNTIME_ERROR("Coul dnot open the temp file: '" << m_buffer << "' because: " << buffer); + } + } +#else + TempFile::TempFile() { + m_file = std::tmpfile(); + if (!m_file) { + CATCH_RUNTIME_ERROR("Could not create a temp file."); + } + } + +#endif + + TempFile::~TempFile() { + // TBD: What to do about errors here? + std::fclose(m_file); + // We manually create the file on Windows only, on Linux + // it will be autodeleted +#if defined(_MSC_VER) + std::remove(m_buffer); +#endif + } + + FILE* TempFile::getFile() { + return m_file; + } + + std::string TempFile::getContents() { + std::stringstream sstr; + char buffer[100] = {}; + std::rewind(m_file); + while (std::fgets(buffer, sizeof(buffer), m_file)) { + sstr << buffer; + } + return sstr.str(); + } + + OutputRedirect::OutputRedirect(std::string& stdout_dest, std::string& stderr_dest) : + m_originalStdout(dup(1)), + m_originalStderr(dup(2)), + m_stdoutDest(stdout_dest), + m_stderrDest(stderr_dest) { + dup2(fileno(m_stdoutFile.getFile()), 1); + dup2(fileno(m_stderrFile.getFile()), 2); + } + + OutputRedirect::~OutputRedirect() { + Catch::cout() << std::flush; + fflush(stdout); + // Since we support overriding these streams, we flush cerr + // even though std::cerr is unbuffered + Catch::cerr() << std::flush; + Catch::clog() << std::flush; + fflush(stderr); + + dup2(m_originalStdout, 1); + dup2(m_originalStderr, 2); + + m_stdoutDest += m_stdoutFile.getContents(); + m_stderrDest += m_stderrFile.getContents(); + } + +#endif // CATCH_CONFIG_NEW_CAPTURE + +} // namespace Catch + +#if defined(CATCH_CONFIG_NEW_CAPTURE) + #if defined(_MSC_VER) + #undef dup + #undef dup2 + #undef fileno + #endif +#endif +// end catch_output_redirect.cpp +// start catch_polyfills.cpp + +#include <cmath> + +namespace Catch { + +#if !defined(CATCH_CONFIG_POLYFILL_ISNAN) + bool isnan(float f) { + return std::isnan(f); + } + bool isnan(double d) { + return std::isnan(d); + } +#else + // For now we only use this for embarcadero + bool isnan(float f) { + return std::_isnan(f); + } + bool isnan(double d) { + return std::_isnan(d); + } +#endif + +} // end namespace Catch +// end catch_polyfills.cpp +// start catch_random_number_generator.cpp + +namespace Catch { + + std::mt19937& rng() { + static std::mt19937 s_rng; + return s_rng; + } + + void seedRng( IConfig const& config ) { + if( config.rngSeed() != 0 ) { + std::srand( config.rngSeed() ); + rng().seed( config.rngSeed() ); + } + } + + unsigned int rngSeed() { + return getCurrentContext().getConfig()->rngSeed(); + } +} +// 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( StringRef 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 +// start catch_singletons.hpp + +namespace Catch { + + struct ISingleton { + virtual ~ISingleton(); + }; + + void addSingleton( ISingleton* singleton ); + void cleanupSingletons(); + + template<typename SingletonImplT, typename InterfaceT = SingletonImplT, typename MutableInterfaceT = InterfaceT> + class Singleton : SingletonImplT, public ISingleton { + + static auto getInternal() -> Singleton* { + static Singleton* s_instance = nullptr; + if( !s_instance ) { + s_instance = new Singleton; + addSingleton( s_instance ); + } + return s_instance; + } + + public: + static auto get() -> InterfaceT const& { + return *getInternal(); + } + static auto getMutable() -> MutableInterfaceT& { + return *getInternal(); + } + }; + +} // namespace Catch + +// end catch_singletons.hpp +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 const& getExceptionTranslatorRegistry() const 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; + }; + } + + using RegistryHubSingleton = Singleton<RegistryHub, IRegistryHub, IMutableRegistryHub>; + + IRegistryHub const& getRegistryHub() { + return RegistryHubSingleton::get(); + } + IMutableRegistryHub& getMutableRegistryHub() { + return RegistryHubSingleton::getMutable(); + } + void cleanUp() { + cleanupSingletons(); + 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 shouldSuppressFailure( int flags ) { return ( flags & ResultDisposition::SuppressFail ) != 0; } + +} // end namespace Catch +// end catch_result_type.cpp +// start catch_run_context.cpp + +#include <cassert> +#include <algorithm> +#include <sstream> + +namespace Catch { + + namespace Generators { + struct GeneratorTracker : TestCaseTracking::TrackerBase, IGeneratorTracker { + size_t m_index = static_cast<size_t>( -1 ); + GeneratorBasePtr m_generator; + + GeneratorTracker( TestCaseTracking::NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent ) + : TrackerBase( nameAndLocation, ctx, parent ) + {} + ~GeneratorTracker(); + + static GeneratorTracker& acquire( TrackerContext& ctx, TestCaseTracking::NameAndLocation const& nameAndLocation ) { + std::shared_ptr<GeneratorTracker> tracker; + + ITracker& currentTracker = ctx.currentTracker(); + if( TestCaseTracking::ITrackerPtr childTracker = currentTracker.findChild( nameAndLocation ) ) { + assert( childTracker ); + assert( childTracker->isIndexTracker() ); + tracker = std::static_pointer_cast<GeneratorTracker>( childTracker ); + } + else { + tracker = std::make_shared<GeneratorTracker>( nameAndLocation, ctx, ¤tTracker ); + currentTracker.addChild( tracker ); + } + + if( !ctx.completedCycle() && !tracker->isComplete() ) { + if( tracker->m_runState != ExecutingChildren && tracker->m_runState != NeedsAnotherRun ) + tracker->moveNext(); + tracker->open(); + } + + return *tracker; + } + + void moveNext() { + m_index++; + m_children.clear(); + } + + // TrackerBase interface + bool isIndexTracker() const override { return true; } + auto hasGenerator() const -> bool override { + return !!m_generator; + } + void close() override { + TrackerBase::close(); + if( m_runState == CompletedSuccessfully && m_index < m_generator->size()-1 ) + m_runState = Executing; + } + + // IGeneratorTracker interface + auto getGenerator() const -> GeneratorBasePtr const& override { + return m_generator; + } + void setGenerator( GeneratorBasePtr&& generator ) override { + m_generator = std::move( generator ); + } + auto getIndex() const -> size_t override { + return m_index; + } + }; + GeneratorTracker::~GeneratorTracker() {} + } + + RunContext::RunContext(IConfigPtr const& _config, IStreamingReporterPtr&& reporter) + : m_runInfo(_config->name()), + m_context(getCurrentMutableContext()), + m_config(_config), + m_reporter(std::move(reporter)), + m_lastAssertionInfo{ StringRef(), SourceLineInfo("",0), StringRef(), ResultDisposition::Normal }, + m_includeSuccessfulResults( m_config->includeSuccessfulResults() || m_reporter->getPreferences().shouldReportAllAssertions ) + { + 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; + + auto const& 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::assertionEnded(AssertionResult const & result) { + if (result.getResultType() == ResultWas::Ok) { + m_totals.assertions.passed++; + m_lastAssertionPassed = true; + } else if (!result.isOk()) { + m_lastAssertionPassed = false; + if( m_activeTestCase->getTestCaseInfo().okToFail() ) + m_totals.assertions.failedButOk++; + else + m_totals.assertions.failed++; + } + else { + m_lastAssertionPassed = true; + } + + // 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 + resetAssertionInfo(); + m_lastResult = result; + } + void RunContext::resetAssertionInfo() { + m_lastAssertionInfo.macroName = StringRef(); + m_lastAssertionInfo.capturedExpression = "{Unknown expression after the reported line}"_sr; + } + + 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; + } + auto RunContext::acquireGeneratorTracker( SourceLineInfo const& lineInfo ) -> IGeneratorTracker& { + using namespace Generators; + GeneratorTracker& tracker = GeneratorTracker::acquire( m_trackerContext, TestCaseTracking::NameAndLocation( "generator", lineInfo ) ); + assert( tracker.isOpen() ); + m_lastAssertionInfo.lineInfo = lineInfo; + return tracker; + } + + 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); + + 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); + + 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_lastAssertionPassed; + } + + void RunContext::assertionPassed() { + m_lastAssertionPassed = true; + ++m_totals.assertions.passed; + resetAssertionInfo(); + } + + 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); + m_reporter->sectionStarting(testCaseSection); + Counts prevAssertions = m_totals.assertions; + double duration = 0; + m_shouldReportUnexpected = true; + m_lastAssertionInfo = { "TEST_CASE"_sr, testCaseInfo.lineInfo, StringRef(), ResultDisposition::Normal }; + + seedRng(*m_config); + + Timer timer; + CATCH_TRY { + if (m_reporter->getPreferences().shouldRedirectStdOut) { +#if !defined(CATCH_CONFIG_EXPERIMENTAL_REDIRECT) + RedirectedStdOut redirectedStdOut; + RedirectedStdErr redirectedStdErr; + + timer.start(); + invokeActiveTestCase(); + redirectedCout += redirectedStdOut.str(); + redirectedCerr += redirectedStdErr.str(); +#else + OutputRedirect r(redirectedCout, redirectedCerr); + timer.start(); + invokeActiveTestCase(); +#endif + } else { + timer.start(); + invokeActiveTestCase(); + } + duration = timer.getElapsedSeconds(); + } CATCH_CATCH_ANON (TestFailureException&) { + // This just means the test was aborted due to failure + } CATCH_CATCH_ALL { + // Under CATCH_CONFIG_FAST_COMPILE, unexpected exceptions under REQUIRE assertions + // are reported without translation at the point of origin. + if( m_shouldReportUnexpected ) { + AssertionReaction dummyReaction; + handleUnexpectedInflightException( m_lastAssertionInfo, translateActiveException(), dummyReaction ); + } + } + Counts assertions = m_totals.assertions - prevAssertions; + bool missingAssertions = testForMissingAssertions(assertions); + + m_testCaseTracker->close(); + handleUnfinishedSections(); + m_messages.clear(); + + 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(); + } + + void RunContext::handleExpr( + AssertionInfo const& info, + ITransientExpression const& expr, + AssertionReaction& reaction + ) { + m_reporter->assertionStarting( info ); + + bool negated = isFalseTest( info.resultDisposition ); + bool result = expr.getResult() != negated; + + if( result ) { + if (!m_includeSuccessfulResults) { + assertionPassed(); + } + else { + reportExpr(info, ResultWas::Ok, &expr, negated); + } + } + else { + reportExpr(info, ResultWas::ExpressionFailed, &expr, negated ); + populateReaction( reaction ); + } + } + void RunContext::reportExpr( + AssertionInfo const &info, + ResultWas::OfType resultType, + ITransientExpression const *expr, + bool negated ) { + + m_lastAssertionInfo = info; + AssertionResultData data( resultType, LazyExpression( negated ) ); + + AssertionResult assertionResult{ info, data }; + assertionResult.m_resultData.lazyExpression.m_transientExpression = expr; + + assertionEnded( assertionResult ); + } + + void RunContext::handleMessage( + AssertionInfo const& info, + ResultWas::OfType resultType, + StringRef const& message, + AssertionReaction& reaction + ) { + m_reporter->assertionStarting( info ); + + m_lastAssertionInfo = info; + + AssertionResultData data( resultType, LazyExpression( false ) ); + data.message = message; + AssertionResult assertionResult{ m_lastAssertionInfo, data }; + assertionEnded( assertionResult ); + if( !assertionResult.isOk() ) + populateReaction( reaction ); + } + void RunContext::handleUnexpectedExceptionNotThrown( + AssertionInfo const& info, + AssertionReaction& reaction + ) { + handleNonExpr(info, Catch::ResultWas::DidntThrowException, reaction); + } + + void RunContext::handleUnexpectedInflightException( + AssertionInfo const& info, + std::string const& message, + AssertionReaction& reaction + ) { + m_lastAssertionInfo = info; + + AssertionResultData data( ResultWas::ThrewException, LazyExpression( false ) ); + data.message = message; + AssertionResult assertionResult{ info, data }; + assertionEnded( assertionResult ); + populateReaction( reaction ); + } + + void RunContext::populateReaction( AssertionReaction& reaction ) { + reaction.shouldDebugBreak = m_config->shouldDebugBreak(); + reaction.shouldThrow = aborting() || (m_lastAssertionInfo.resultDisposition & ResultDisposition::Normal); + } + + void RunContext::handleIncomplete( + AssertionInfo const& info + ) { + m_lastAssertionInfo = info; + + AssertionResultData data( ResultWas::ThrewException, LazyExpression( false ) ); + data.message = "Exception translation was disabled by CATCH_CONFIG_FAST_COMPILE"; + AssertionResult assertionResult{ info, data }; + assertionEnded( assertionResult ); + } + void RunContext::handleNonExpr( + AssertionInfo const &info, + ResultWas::OfType resultType, + AssertionReaction &reaction + ) { + m_lastAssertionInfo = info; + + AssertionResultData data( resultType, LazyExpression( false ) ); + AssertionResult assertionResult{ info, data }; + assertionEnded( assertionResult ); + + if( !assertionResult.isOk() ) + populateReaction( reaction ); + } + + 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(); + } + + Section::~Section() { + if( m_sectionIncluded ) { + SectionEndInfo endInfo{ m_info, m_assertions, m_timer.getElapsedSeconds() }; + if( uncaught_exceptions() ) + getResultCapture().sectionEndedEarly( endInfo ); + else + getResultCapture().sectionEnded( endInfo ); + } + } + + // 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 ) + : name( _name ), + lineInfo( _lineInfo ) + {} + +} // 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 const * const * argv ); + #if defined(CATCH_CONFIG_WCHAR) && defined(WIN32) && defined(UNICODE) + int applyCommandLine( int argc, wchar_t const * const * argv ); + #endif + + void useConfigData( ConfigData const& configData ); + + template<typename CharT> + int run(int argc, CharT const * const argv[]) { + if (m_startupExceptions) + return 1; + int returnCode = applyCommandLine(argc, argv); + if (returnCode == 0) + returnCode = run(); + return returnCode; + } + + 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 Catch { + + namespace { + const int MaxExitCode = 255; + + 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; + } + + IStreamingReporterPtr makeReporter(std::shared_ptr<Config> const& config) { + if (Catch::getRegistryHub().getReporterRegistry().getListeners().empty()) { + return createReporter(config->getReporterName(), config); + } + + auto multi = std::unique_ptr<ListeningReporter>(new ListeningReporter); + + auto const& listeners = Catch::getRegistryHub().getReporterRegistry().getListeners(); + for (auto const& listener : listeners) { + multi->addListener(listener->create(Catch::ReporterConfig(config))); + } + multi->addReporter(createReporter(config->getReporterName(), config)); + return std::move(multi); + } + + Catch::Totals runTests(std::shared_ptr<Config> const& config) { + auto reporter = makeReporter(config); + + RunContext context(config, std::move(reporter)); + + Totals totals; + + context.testGroupStarting(config->name(), 1, 1); + + TestSpec testSpec = config->testSpec(); + + 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); + } + + if (config->warnAboutNoTests() && totals.testCases.total() == 0) { + ReusableStringStream testConfig; + + bool first = true; + for (const auto& input : config->getTestsOrTags()) { + if (!first) { testConfig << ' '; } + first = false; + testConfig << input; + } + + context.reporter().noMatchingTestCases(testConfig.str()); + totals.error = -1; + } + + context.testGroupEnded(config->name(), totals, 1, 1); + return totals; + } + + void applyFilenamesAsTags(Catch::IConfig const& config) { + 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); + } + } + + } // anon namespace + + Session::Session() { + static bool alreadyInstantiated = false; + if( alreadyInstantiated ) { + CATCH_TRY { CATCH_INTERNAL_ERROR( "Only one instance of Catch::Session can ever be used" ); } + CATCH_CATCH_ALL { getMutableRegistryHub().registerStartupException(); } + } + + // There cannot be exceptions at startup in no-exception mode. +#if !defined(CATCH_CONFIG_DISABLE_EXCEPTIONS) + const auto& exceptions = getRegistryHub().getStartupExceptionRegistry().getExceptions(); + if ( !exceptions.empty() ) { + m_startupExceptions = true; + Colour colourGuard( Colour::Red ); + Catch::cerr() << "Errors occurred 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'; + } + } + } +#endif + + 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 const * const * 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; + } + +#if defined(CATCH_CONFIG_WCHAR) && defined(WIN32) && defined(UNICODE) + int Session::applyCommandLine( int argc, wchar_t const * 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 = applyCommandLine( argc, utf8Argv ); + + for ( int i = 0; i < argc; ++i ) + delete [] utf8Argv[ i ]; + + delete [] utf8Argv; + + return returnCode; + } +#endif + + void Session::useConfigData( ConfigData const& configData ) { + m_configData = configData; + m_config.reset(); + } + + 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; + } + + CATCH_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 ); + + auto totals = runTests( m_config ); + // Note that on unices only the lower 8 bits are usually used, clamping + // the return value to 255 prevents false negative when some multiple + // of 256 tests has failed + return (std::min) (MaxExitCode, (std::max) (totals.error, static_cast<int>(totals.assertions.failed))); + } +#if !defined(CATCH_CONFIG_DISABLE_EXCEPTIONS) + catch( std::exception& ex ) { + Catch::cerr() << ex.what() << std::endl; + return MaxExitCode; + } +#endif + } + +} // end namespace Catch +// end catch_session.cpp +// start catch_singletons.cpp + +#include <vector> + +namespace Catch { + + namespace { + static auto getSingletons() -> std::vector<ISingleton*>*& { + static std::vector<ISingleton*>* g_singletons = nullptr; + if( !g_singletons ) + g_singletons = new std::vector<ISingleton*>(); + return g_singletons; + } + } + + ISingleton::~ISingleton() {} + + void addSingleton(ISingleton* singleton ) { + getSingletons()->push_back( singleton ); + } + void cleanupSingletons() { + auto& singletons = getSingletons(); + for( auto singleton : *singletons ) + delete singleton; + delete singletons; + singletons = nullptr; + } + +} // namespace Catch +// end catch_singletons.cpp +// start catch_startup_exception_registry.cpp + +namespace Catch { +void StartupExceptionRegistry::add( std::exception_ptr const& exception ) noexcept { + CATCH_TRY { + m_exceptions.push_back(exception); + } CATCH_CATCH_ALL { + // 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 <cstdio> +#include <iostream> +#include <fstream> +#include <sstream> +#include <vector> +#include <memory> + +namespace Catch { + + Catch::IStream::~IStream() = default; + + namespace detail { namespace { + template<typename WriterF, std::size_t bufferSize=256> + class StreamBufImpl : public std::streambuf { + 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; + } + }; + + /////////////////////////////////////////////////////////////////////////// + + struct OutputDebugWriter { + + void operator()( std::string const&str ) { + writeToDebugConsole( str ); + } + }; + + /////////////////////////////////////////////////////////////////////////// + + class FileStream : public IStream { + mutable std::ofstream m_ofs; + public: + FileStream( StringRef filename ) { + m_ofs.open( filename.c_str() ); + CATCH_ENFORCE( !m_ofs.fail(), "Unable to open file: '" << filename << "'" ); + } + ~FileStream() override = default; + public: // IStream + std::ostream& stream() const override { + return m_ofs; + } + }; + + /////////////////////////////////////////////////////////////////////////// + + class CoutStream : public IStream { + mutable std::ostream m_os; + public: + // Store the streambuf from cout up-front because + // cout may get redirected when running tests + CoutStream() : m_os( Catch::cout().rdbuf() ) {} + ~CoutStream() override = default; + + public: // IStream + std::ostream& stream() const override { return m_os; } + }; + + /////////////////////////////////////////////////////////////////////////// + + class DebugOutStream : public IStream { + std::unique_ptr<StreamBufImpl<OutputDebugWriter>> m_streamBuf; + mutable std::ostream m_os; + public: + DebugOutStream() + : m_streamBuf( new StreamBufImpl<OutputDebugWriter>() ), + m_os( m_streamBuf.get() ) + {} + + ~DebugOutStream() override = default; + + public: // IStream + std::ostream& stream() const override { return m_os; } + }; + + }} // namespace anon::detail + + /////////////////////////////////////////////////////////////////////////// + + auto makeStream( StringRef const &filename ) -> IStream const* { + if( filename.empty() ) + return new detail::CoutStream(); + else if( filename[0] == '%' ) { + if( filename == "%debug" ) + return new detail::DebugOutStream(); + else + CATCH_ERROR( "Unrecognised stream: '" << filename << "'" ); + } + else + return new detail::FileStream( filename ); + } + + // This class encapsulates the idea of a pool of ostringstreams that can be reused. + struct StringStreams { + std::vector<std::unique_ptr<std::ostringstream>> m_streams; + std::vector<std::size_t> m_unused; + std::ostringstream m_referenceStream; // Used for copy state/ flags from + + auto add() -> std::size_t { + if( m_unused.empty() ) { + m_streams.push_back( std::unique_ptr<std::ostringstream>( new std::ostringstream ) ); + return m_streams.size()-1; + } + else { + auto index = m_unused.back(); + m_unused.pop_back(); + return index; + } + } + + void release( std::size_t index ) { + m_streams[index]->copyfmt( m_referenceStream ); // Restore initial flags and other state + m_unused.push_back(index); + } + }; + + ReusableStringStream::ReusableStringStream() + : m_index( Singleton<StringStreams>::getMutable().add() ), + m_oss( Singleton<StringStreams>::getMutable().m_streams[m_index].get() ) + {} + + ReusableStringStream::~ReusableStringStream() { + static_cast<std::ostringstream*>( m_oss )->str(""); + m_oss->clear(); + Singleton<StringStreams>::getMutable().release( m_index ); + } + + auto ReusableStringStream::str() const -> std::string { + return static_cast<std::ostringstream*>( m_oss )->str(); + } + + /////////////////////////////////////////////////////////////////////////// + +#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_string_manip.cpp + +#include <algorithm> +#include <ostream> +#include <cstring> +#include <cctype> + +namespace Catch { + + namespace { + char toLowerCh(char c) { + return static_cast<char>( std::tolower( c ) ); + } + } + + 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; + } + 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 <cstring> +#include <cstdint> + +namespace { + const uint32_t byte_2_lead = 0xC0; + const uint32_t byte_3_lead = 0xE0; + const uint32_t byte_4_lead = 0xF0; +} + +namespace Catch { + StringRef::StringRef( char const* rawChars ) noexcept + : StringRef( rawChars, static_cast<StringRef::size_type>(std::strlen(rawChars) ) ) + {} + + 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::currentData() 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::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 & byte_2_lead ) == byte_2_lead ) { + noChars--; + if (( c & byte_3_lead ) == byte_3_lead ) + noChars--; + if( ( c & byte_4_lead ) == byte_4_lead ) + noChars--; + } + } + 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.write(str.currentData(), str.size()); + } + + auto operator+=( std::string& lhs, StringRef const& rhs ) -> std::string& { + lhs.append(rhs.currentData(), rhs.size()); + return lhs; + } + +} // 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) { + CATCH_TRY { + getMutableRegistryHub().registerTagAlias(alias, tag, lineInfo); + } CATCH_CATCH_ALL { + // 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 + +#include <sstream> + +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> +#include <sstream> + +namespace Catch { + + namespace { + 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( static_cast<unsigned char>(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, + NameAndTags const& nameAndTags, + SourceLineInfo const& _lineInfo ) + { + bool isHidden = false; + + // Parse out tags + std::vector<std::string> tags; + std::string desc, tag; + bool inTag = false; + std::string _descOrTags = nameAndTags.tags; + 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( nameAndTags.name, _className, desc, tags, _lineInfo ); + return TestCase( _testCase, std::move(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&& info ) : TestCaseInfo( std::move(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 ); + std::shuffle( sorted.begin(), sorted.end(), rng() ); + 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() ) { + ReusableStringStream rss; + rss << "Anonymous test case " << ++m_unnamedCount; + return registerTest( testCase.withName( rss.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( StringRef 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 <cassert> +#include <stdexcept> +#include <memory> +#include <sstream> + +#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::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(), + [&nameAndLocation]( ITrackerPtr const& tracker ){ + return + tracker->nameAndLocation().location == nameAndLocation.location && + tracker->nameAndLocation().name == nameAndLocation.name; + } ); + 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 const& name_ , StringRef const& tags_ ) noexcept : name( name_ ), tags( tags_ ) {} + + AutoReg::AutoReg( ITestInvoker* invoker, SourceLineInfo const& lineInfo, StringRef const& classOrMethod, NameAndTags const& nameAndTags ) noexcept { + CATCH_TRY { + getMutableRegistryHub() + .registerTest( + makeTestCase( + invoker, + extractClassName( classOrMethod ), + nameAndTags, + lineInfo)); + } CATCH_CATCH_ALL { + // 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> + +static const uint64_t nanosecondsInSecond = 1000000000; + +namespace Catch { + + auto getCurrentNanosecondsSinceEpoch() -> uint64_t { + return std::chrono::duration_cast<std::chrono::nanoseconds>( std::chrono::high_resolution_clock::now().time_since_epoch() ).count(); + } + + namespace { + auto estimateClockResolution() -> uint64_t { + uint64_t sum = 0; + static const uint64_t iterations = 1000000; + + auto startTime = getCurrentNanosecondsSinceEpoch(); + + 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; + + // If we have been calibrating for over 3 seconds -- the clock + // is terrible and we should move on. + // TBD: How to signal that the measured resolution is probably wrong? + if (ticks > startTime + 3 * nanosecondsInSecond) { + return sum / i; + } + } + + // 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 -> uint64_t { + return getCurrentNanosecondsSinceEpoch() - m_nanoseconds; + } + auto Timer::getElapsedMicroseconds() const -> uint64_t { + return 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 + +// Enable specific decls locally +#if !defined(CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER) +#define CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER +#endif + +#include <cmath> +#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); + ReusableStringStream rss; + rss << "0x" << std::setfill('0') << std::hex; + for( ; i != end; i += inc ) + rss << std::setw(2) << static_cast<unsigned>(bytes[i]); + return rss.str(); + } +} + +template<typename T> +std::string fpToString( T value, int precision ) { + if (Catch::isnan(value)) { + return "nan"; + } + + ReusableStringStream rss; + rss << std::setprecision( precision ) + << std::fixed + << value; + std::string d = rss.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; +} + +#ifdef CATCH_CONFIG_CPP17_STRING_VIEW +std::string StringMaker<std::string_view>::convert(std::string_view str) { + return ::Catch::Detail::stringify(std::string{ str }); +} +#endif + +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}" }; + } +} + +#ifdef CATCH_CONFIG_WCHAR +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); +} + +# ifdef CATCH_CONFIG_CPP17_STRING_VIEW +std::string StringMaker<std::wstring_view>::convert(std::wstring_view str) { + return StringMaker<std::wstring>::convert(std::wstring(str)); +} +# endif + +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}" }; + } +} +#endif + +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) { + ReusableStringStream rss; + rss << value; + if (value > Detail::hexThreshold) { + rss << " (0x" << std::hex << value << ')'; + } + return rss.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) { + ReusableStringStream rss; + rss << value; + if (value > Detail::hexThreshold) { + rss << " (0x" << std::hex << value << ')'; + } + return rss.str(); +} + +std::string StringMaker<bool>::convert(bool b) { + return b ? "true" : "false"; +} + +std::string StringMaker<signed char>::convert(signed 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<char>::convert(char c) { + return ::Catch::Detail::stringify(static_cast<signed 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); +} + +std::string ratio_string<std::atto>::symbol() { return "a"; } +std::string ratio_string<std::femto>::symbol() { return "f"; } +std::string ratio_string<std::pico>::symbol() { return "p"; } +std::string ratio_string<std::nano>::symbol() { return "n"; } +std::string ratio_string<std::micro>::symbol() { return "u"; } +std::string ratio_string<std::milli>::symbol() { return "m"; } + +} // 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_uncaught_exceptions.cpp + +#include <exception> + +namespace Catch { + bool uncaught_exceptions() { +#if defined(CATCH_CONFIG_CPP17_UNCAUGHT_EXCEPTIONS) + return std::uncaught_exceptions() > 0; +#else + return std::uncaught_exception(); +#endif + } +} // end namespace Catch +// end catch_uncaught_exceptions.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, 5, 0, "", 0 ); + return version; + } + +} +// end catch_version.cpp +// start catch_wildcard_pattern.cpp + +#include <sstream> + +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 + +#include <iomanip> + +using uchar = unsigned char; + +namespace Catch { + +namespace { + + size_t trailingBytes(unsigned char c) { + if ((c & 0xE0) == 0xC0) { + return 2; + } + if ((c & 0xF0) == 0xE0) { + return 3; + } + if ((c & 0xF8) == 0xF0) { + return 4; + } + CATCH_INTERNAL_ERROR("Invalid multibyte utf-8 start byte encountered"); + } + + uint32_t headerValue(unsigned char c) { + if ((c & 0xE0) == 0xC0) { + return c & 0x1F; + } + if ((c & 0xF0) == 0xE0) { + return c & 0x0F; + } + if ((c & 0xF8) == 0xF0) { + return c & 0x07; + } + CATCH_INTERNAL_ERROR("Invalid multibyte utf-8 start byte encountered"); + } + + void hexEscapeChar(std::ostream& os, unsigned char c) { + os << "\\x" + << std::uppercase << std::hex << std::setfill('0') << std::setw(2) + << static_cast<int>(c); + } + +} // anonymous namespace + + 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 idx = 0; idx < m_str.size(); ++ idx ) { + uchar c = m_str[idx]; + switch (c) { + case '<': os << "<"; break; + case '&': os << "&"; break; + + case '>': + // See: http://www.w3.org/TR/xml/#syntax + if (idx > 2 && m_str[idx - 1] == ']' && m_str[idx - 2] == ']') + os << ">"; + else + os << c; + break; + + case '\"': + if (m_forWhat == ForAttributes) + os << """; + else + os << c; + break; + + default: + // Check for control characters and invalid utf-8 + + // Escape control characters in standard ascii + // see http://stackoverflow.com/questions/404107/why-are-control-characters-illegal-in-xml-1-0 + if (c < 0x09 || (c > 0x0D && c < 0x20) || c == 0x7F) { + hexEscapeChar(os, c); + break; + } + + // Plain ASCII: Write it to stream + if (c < 0x7F) { + os << c; + break; + } + + // UTF-8 territory + // Check if the encoding is valid and if it is not, hex escape bytes. + // Important: We do not check the exact decoded values for validity, only the encoding format + // First check that this bytes is a valid lead byte: + // This means that it is not encoded as 1111 1XXX + // Or as 10XX XXXX + if (c < 0xC0 || + c >= 0xF8) { + hexEscapeChar(os, c); + break; + } + + auto encBytes = trailingBytes(c); + // Are there enough bytes left to avoid accessing out-of-bounds memory? + if (idx + encBytes - 1 >= m_str.size()) { + hexEscapeChar(os, c); + break; + } + // The header is valid, check data + // The next encBytes bytes must together be a valid utf-8 + // This means: bitpattern 10XX XXXX and the extracted value is sane (ish) + bool valid = true; + uint32_t value = headerValue(c); + for (std::size_t n = 1; n < encBytes; ++n) { + uchar nc = m_str[idx + n]; + valid &= ((nc & 0xC0) == 0x80); + value = (value << 6) | (nc & 0x3F); + } + + if ( + // Wrong bit pattern of following bytes + (!valid) || + // Overlong encodings + (value < 0x80) || + (0x80 <= value && value < 0x800 && encBytes > 2) || + (0x800 < value && value < 0x10000 && encBytes > 3) || + // Encoded value out of range + (value >= 0x110000) + ) { + hexEscapeChar(os, c); + break; + } + + // If we got here, this is in fact a valid(ish) utf-8 sequence + for (std::size_t n = 0; n < encBytes; ++n) { + os << m_str[idx + n]; + } + idx += encBytes - 1; + break; + } + } + } + + 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 <cassert> +#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) {} + + std::set<Verbosity> TestEventListenerBase::getSupportedVerbosities() { + return { Verbosity::Quiet, Verbosity::Normal, Verbosity::High }; + } + + 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 " ; + } + +} // anon namespace + +namespace Catch { +namespace { +// 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(std::ostream& out, const Totals& totals) { + if (totals.testCases.total() == 0) { + out << "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(); + out << + "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) { + out << + "Passed " << bothOrAll(totals.testCases.total()) + << pluralise(totals.testCases.total(), "test case") + << " (no assertions)."; + } else if (totals.assertions.failed) { + Colour colour(Colour::ResultError); + out << + "Failed " << pluralise(totals.testCases.failed, "test case") << ", " + "failed " << pluralise(totals.assertions.failed, "assertion") << '.'; + } else { + Colour colour(Colour::ResultSuccess); + out << + "Passed " << bothOrAll(totals.testCases.passed) + << pluralise(totals.testCases.passed, "test case") << + " with " << pluralise(totals.assertions.passed, "assertion") << '.'; + } +} + +// Implementation of CompactReporter formatting +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; +}; + +} // anon namespace + + std::string CompactReporter::getDescription() { + return "Reports test results on a single line, suitable for IDEs"; + } + + ReporterPreferences CompactReporter::getPreferences() const { + return m_reporterPrefs; + } + + void CompactReporter::noMatchingTestCases( std::string const& spec ) { + stream << "No test cases matched '" << spec << '\'' << std::endl; + } + + void CompactReporter::assertionStarting( AssertionInfo const& ) {} + + bool CompactReporter::assertionEnded( AssertionStats const& _assertionStats ) { + 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 CompactReporter::sectionEnded(SectionStats const& _sectionStats) { + if (m_config->showDurations() == ShowDurations::Always) { + stream << getFormattedDuration(_sectionStats.durationInSeconds) << " s: " << _sectionStats.sectionInfo.name << std::endl; + } + } + + void CompactReporter::testRunEnded( TestRunStats const& _testRunStats ) { + printTotals( stream, _testRunStats.totals ); + stream << '\n' << std::endl; + StreamingReporterBase::testRunEnded( _testRunStats ); + } + + 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 { + +// Formatter impl for ConsoleReporter +class ConsoleAssertionPrinter { +public: + ConsoleAssertionPrinter& operator= (ConsoleAssertionPrinter const&) = delete; + ConsoleAssertionPrinter(ConsoleAssertionPrinter const&) = delete; + ConsoleAssertionPrinter(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) { + 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; +}; + +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 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: + explicit 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 + +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> columnInfos ) + : m_os( os ), + m_columnInfos( std::move( 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; + } +}; + +ConsoleReporter::ConsoleReporter(ReporterConfig const& config) + : StreamingReporterBase(config), + m_tablePrinter(new 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::~ConsoleReporter() = default; + +std::string ConsoleReporter::getDescription() { + return "Reports test results as plain lines of text"; +} + +void ConsoleReporter::noMatchingTestCases(std::string const& spec) { + stream << "No test cases matched '" << spec << '\'' << std::endl; +} + +void ConsoleReporter::assertionStarting(AssertionInfo const&) {} + +bool ConsoleReporter::assertionEnded(AssertionStats const& _assertionStats) { + 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(); + + ConsoleAssertionPrinter printer(stream, _assertionStats, includeResults); + printer.print(); + stream << std::endl; + return true; +} + +void ConsoleReporter::sectionStarting(SectionInfo const& _sectionInfo) { + m_headerPrinted = false; + StreamingReporterBase::sectionStarting(_sectionInfo); +} +void ConsoleReporter::sectionEnded(SectionStats const& _sectionStats) { + 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 ConsoleReporter::benchmarkStarting(BenchmarkInfo const& info) { + lazyPrintWithoutClosingBenchmarkTable(); + + auto nameCol = Column( info.name ).width( static_cast<std::size_t>( 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 ConsoleReporter::benchmarkEnded(BenchmarkStats const& stats) { + Duration average(stats.elapsedTimeInNanoseconds / stats.iterations); + (*m_tablePrinter) + << stats.iterations << ColumnBreak() + << stats.elapsedTimeInNanoseconds << ColumnBreak() + << average << ColumnBreak(); +} + +void ConsoleReporter::testCaseEnded(TestCaseStats const& _testCaseStats) { + m_tablePrinter->close(); + StreamingReporterBase::testCaseEnded(_testCaseStats); + m_headerPrinted = false; +} +void ConsoleReporter::testGroupEnded(TestGroupStats const& _testGroupStats) { + if (currentGroupInfo.used) { + printSummaryDivider(); + stream << "Summary for group '" << _testGroupStats.groupInfo.name << "':\n"; + printTotals(_testGroupStats.totals); + stream << '\n' << std::endl; + } + StreamingReporterBase::testGroupEnded(_testGroupStats); +} +void ConsoleReporter::testRunEnded(TestRunStats const& _testRunStats) { + printTotalsDivider(_testRunStats.totals); + printTotals(_testRunStats.totals); + stream << std::endl; + StreamingReporterBase::testRunEnded(_testRunStats); +} + +void ConsoleReporter::lazyPrint() { + + m_tablePrinter->close(); + lazyPrintWithoutClosingBenchmarkTable(); +} + +void ConsoleReporter::lazyPrintWithoutClosingBenchmarkTable() { + + if (!currentTestRunInfo.used) + lazyPrintRunInfo(); + if (!currentGroupInfo.used) + lazyPrintGroupInfo(); + + if (!m_headerPrinted) { + printTestCaseAndSectionHeader(); + m_headerPrinted = true; + } +} +void ConsoleReporter::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 ConsoleReporter::lazyPrintGroupInfo() { + if (!currentGroupInfo->name.empty() && currentGroupInfo->groupsCounts > 1) { + printClosedHeader("Group: " + currentGroupInfo->name); + currentGroupInfo.used = true; + } +} +void ConsoleReporter::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 ConsoleReporter::printClosedHeader(std::string const& _name) { + printOpenHeader(_name); + stream << getLineOfChars<'.'>() << '\n'; +} +void ConsoleReporter::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 ConsoleReporter::printHeaderString(std::string const& _string, std::size_t indent) { + 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 _label, Colour::Code _colour ) + : label( std::move( _label ) ), + colour( _colour ) {} + SummaryColumn addRow( std::size_t count ) { + ReusableStringStream rss; + rss << count; + std::string row = rss.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 ConsoleReporter::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 ConsoleReporter::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 ConsoleReporter::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 ConsoleReporter::printSummaryDivider() { + stream << getLineOfChars<'-'>() << '\n'; +} + +CATCH_REGISTER_REPORTER("console", ConsoleReporter) + +} // end namespace Catch + +#if defined(_MSC_VER) +#pragma warning(pop) +#endif +// end catch_reporter_console.cpp +// start catch_reporter_junit.cpp + +#include <cassert> +#include <sstream> +#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(); + } + } // anonymous namespace + + JunitReporter::JunitReporter( ReporterConfig const& _config ) + : CumulativeReporterBase( _config ), + xml( _config.stream() ) + { + m_reporterPrefs.shouldRedirectStdOut = true; + m_reporterPrefs.shouldReportAllAssertions = true; + } + + JunitReporter::~JunitReporter() {} + + std::string JunitReporter::getDescription() { + return "Reports test results in an XML format that looks like Ant's junitreport target"; + } + + void JunitReporter::noMatchingTestCases( std::string const& /*spec*/ ) {} + + void JunitReporter::testRunStarting( TestRunInfo const& runInfo ) { + CumulativeReporterBase::testRunStarting( runInfo ); + xml.startElement( "testsuites" ); + } + + void JunitReporter::testGroupStarting( GroupInfo const& groupInfo ) { + suiteTimer.start(); + stdOutForSuite.clear(); + stdErrForSuite.clear(); + unexpectedExceptions = 0; + CumulativeReporterBase::testGroupStarting( groupInfo ); + } + + void JunitReporter::testCaseStarting( TestCaseInfo const& testCaseInfo ) { + m_okToFail = testCaseInfo.okToFail(); + } + + bool JunitReporter::assertionEnded( AssertionStats const& assertionStats ) { + if( assertionStats.assertionResult.getResultType() == ResultWas::ThrewException && !m_okToFail ) + unexpectedExceptions++; + return CumulativeReporterBase::assertionEnded( assertionStats ); + } + + void JunitReporter::testCaseEnded( TestCaseStats const& testCaseStats ) { + stdOutForSuite += testCaseStats.stdOut; + stdErrForSuite += testCaseStats.stdErr; + CumulativeReporterBase::testCaseEnded( testCaseStats ); + } + + void JunitReporter::testGroupEnded( TestGroupStats const& testGroupStats ) { + double suiteTime = suiteTimer.getElapsedSeconds(); + CumulativeReporterBase::testGroupEnded( testGroupStats ); + writeGroup( *m_testGroups.back(), suiteTime ); + } + + void JunitReporter::testRunEndedCumulative() { + xml.endElement(); + } + + void JunitReporter::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 ), false ); + xml.scopedElement( "system-err" ).writeText( trim( stdErrForSuite ), false ); + } + + void JunitReporter::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 JunitReporter::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 JunitReporter::writeAssertions( SectionNode const& sectionNode ) { + for( auto const& assertion : sectionNode.assertions ) + writeAssertion( assertion ); + } + + void JunitReporter::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() ); + + ReusableStringStream rss; + if( !result.getMessage().empty() ) + rss << result.getMessage() << '\n'; + for( auto const& msg : stats.infoMessages ) + if( msg.type == ResultWas::Info ) + rss << msg.message << '\n'; + + rss << "at " << result.getSourceInfo(); + xml.writeText( rss.str(), false ); + } + } + + CATCH_REGISTER_REPORTER( "junit", JunitReporter ) + +} // end namespace Catch +// end catch_reporter_junit.cpp +// start catch_reporter_listening.cpp + +#include <cassert> + +namespace Catch { + + ListeningReporter::ListeningReporter() { + // We will assume that listeners will always want all assertions + m_preferences.shouldReportAllAssertions = true; + } + + void ListeningReporter::addListener( IStreamingReporterPtr&& listener ) { + m_listeners.push_back( std::move( listener ) ); + } + + void ListeningReporter::addReporter(IStreamingReporterPtr&& reporter) { + assert(!m_reporter && "Listening reporter can wrap only 1 real reporter"); + m_reporter = std::move( reporter ); + m_preferences.shouldRedirectStdOut = m_reporter->getPreferences().shouldRedirectStdOut; + } + + ReporterPreferences ListeningReporter::getPreferences() const { + return m_preferences; + } + + std::set<Verbosity> ListeningReporter::getSupportedVerbosities() { + return std::set<Verbosity>{ }; + } + + void ListeningReporter::noMatchingTestCases( std::string const& spec ) { + for ( auto const& listener : m_listeners ) { + listener->noMatchingTestCases( spec ); + } + m_reporter->noMatchingTestCases( spec ); + } + + void ListeningReporter::benchmarkStarting( BenchmarkInfo const& benchmarkInfo ) { + for ( auto const& listener : m_listeners ) { + listener->benchmarkStarting( benchmarkInfo ); + } + m_reporter->benchmarkStarting( benchmarkInfo ); + } + void ListeningReporter::benchmarkEnded( BenchmarkStats const& benchmarkStats ) { + for ( auto const& listener : m_listeners ) { + listener->benchmarkEnded( benchmarkStats ); + } + m_reporter->benchmarkEnded( benchmarkStats ); + } + + void ListeningReporter::testRunStarting( TestRunInfo const& testRunInfo ) { + for ( auto const& listener : m_listeners ) { + listener->testRunStarting( testRunInfo ); + } + m_reporter->testRunStarting( testRunInfo ); + } + + void ListeningReporter::testGroupStarting( GroupInfo const& groupInfo ) { + for ( auto const& listener : m_listeners ) { + listener->testGroupStarting( groupInfo ); + } + m_reporter->testGroupStarting( groupInfo ); + } + + void ListeningReporter::testCaseStarting( TestCaseInfo const& testInfo ) { + for ( auto const& listener : m_listeners ) { + listener->testCaseStarting( testInfo ); + } + m_reporter->testCaseStarting( testInfo ); + } + + void ListeningReporter::sectionStarting( SectionInfo const& sectionInfo ) { + for ( auto const& listener : m_listeners ) { + listener->sectionStarting( sectionInfo ); + } + m_reporter->sectionStarting( sectionInfo ); + } + + void ListeningReporter::assertionStarting( AssertionInfo const& assertionInfo ) { + for ( auto const& listener : m_listeners ) { + listener->assertionStarting( assertionInfo ); + } + m_reporter->assertionStarting( assertionInfo ); + } + + // The return value indicates if the messages buffer should be cleared: + bool ListeningReporter::assertionEnded( AssertionStats const& assertionStats ) { + for( auto const& listener : m_listeners ) { + static_cast<void>( listener->assertionEnded( assertionStats ) ); + } + return m_reporter->assertionEnded( assertionStats ); + } + + void ListeningReporter::sectionEnded( SectionStats const& sectionStats ) { + for ( auto const& listener : m_listeners ) { + listener->sectionEnded( sectionStats ); + } + m_reporter->sectionEnded( sectionStats ); + } + + void ListeningReporter::testCaseEnded( TestCaseStats const& testCaseStats ) { + for ( auto const& listener : m_listeners ) { + listener->testCaseEnded( testCaseStats ); + } + m_reporter->testCaseEnded( testCaseStats ); + } + + void ListeningReporter::testGroupEnded( TestGroupStats const& testGroupStats ) { + for ( auto const& listener : m_listeners ) { + listener->testGroupEnded( testGroupStats ); + } + m_reporter->testGroupEnded( testGroupStats ); + } + + void ListeningReporter::testRunEnded( TestRunStats const& testRunStats ) { + for ( auto const& listener : m_listeners ) { + listener->testRunEnded( testRunStats ); + } + m_reporter->testRunEnded( testRunStats ); + } + + void ListeningReporter::skipTest( TestCaseInfo const& testInfo ) { + for ( auto const& listener : m_listeners ) { + listener->skipTest( testInfo ); + } + m_reporter->skipTest( testInfo ); + } + + bool ListeningReporter::isMulti() const { + return true; + } + +} // end namespace Catch +// end catch_reporter_listening.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 { + XmlReporter::XmlReporter( ReporterConfig const& _config ) + : StreamingReporterBase( _config ), + m_xml(_config.stream()) + { + m_reporterPrefs.shouldRedirectStdOut = true; + m_reporterPrefs.shouldReportAllAssertions = true; + } + + XmlReporter::~XmlReporter() = default; + + std::string XmlReporter::getDescription() { + return "Reports test results as an XML document"; + } + + std::string XmlReporter::getStylesheetRef() const { + return std::string(); + } + + void XmlReporter::writeSourceInfo( SourceLineInfo const& sourceInfo ) { + m_xml + .writeAttribute( "filename", sourceInfo.file ) + .writeAttribute( "line", sourceInfo.line ); + } + + void XmlReporter::noMatchingTestCases( std::string const& s ) { + StreamingReporterBase::noMatchingTestCases( s ); + } + + void XmlReporter::testRunStarting( TestRunInfo const& testInfo ) { + 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() ); + if( m_config->rngSeed() != 0 ) + m_xml.scopedElement( "Randomness" ) + .writeAttribute( "seed", m_config->rngSeed() ); + } + + void XmlReporter::testGroupStarting( GroupInfo const& groupInfo ) { + StreamingReporterBase::testGroupStarting( groupInfo ); + m_xml.startElement( "Group" ) + .writeAttribute( "name", groupInfo.name ); + } + + void XmlReporter::testCaseStarting( TestCaseInfo const& testInfo ) { + 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 XmlReporter::sectionStarting( SectionInfo const& sectionInfo ) { + StreamingReporterBase::sectionStarting( sectionInfo ); + if( m_sectionDepth++ > 0 ) { + m_xml.startElement( "Section" ) + .writeAttribute( "name", trim( sectionInfo.name ) ); + writeSourceInfo( sectionInfo.lineInfo ); + m_xml.ensureTagClosed(); + } + } + + void XmlReporter::assertionStarting( AssertionInfo const& ) { } + + bool XmlReporter::assertionEnded( AssertionStats const& assertionStats ) { + + AssertionResult const& result = assertionStats.assertionResult; + + bool includeResults = m_config->includeSuccessfulResults() || !result.isOk(); + + if( includeResults || result.getResultType() == ResultWas::Warning ) { + // Print any info messages in <Info> tags. + for( auto const& msg : assertionStats.infoMessages ) { + if( msg.type == ResultWas::Info && includeResults ) { + 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 XmlReporter::sectionEnded( SectionStats const& sectionStats ) { + 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 XmlReporter::testCaseEnded( TestCaseStats const& testCaseStats ) { + 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 XmlReporter::testGroupEnded( TestGroupStats const& testGroupStats ) { + 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 XmlReporter::testRunEnded( TestRunStats const& testRunStats ) { + 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(); + } + + 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(CATCH_CONFIG_WCHAR) && 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 + +#if !defined(CATCH_CONFIG_IMPL_ONLY) + +#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( ... ) INTERNAL_CATCH_CAPTURE( INTERNAL_CATCH_UNIQUE_NAME(capturer), "CATCH_CAPTURE",__VA_ARGS__ ) + +#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_DYNAMIC_SECTION( ... ) INTERNAL_CATCH_DYNAMIC_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() + +#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR +#define CATCH_TEMPLATE_TEST_CASE( ... ) INTERNAL_CATCH_TEMPLATE_TEST_CASE( __VA_ARGS__ ) +#define CATCH_TEMPLATE_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD( className, __VA_ARGS__ ) +#else +#define CATCH_TEMPLATE_TEST_CASE( ... ) INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE( __VA_ARGS__ ) ) +#define CATCH_TEMPLATE_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD( className, __VA_ARGS__ ) ) +#endif + +#if !defined(CATCH_CONFIG_RUNTIME_STATIC_REQUIRE) +#define CATCH_STATIC_REQUIRE( ... ) static_assert( __VA_ARGS__ , #__VA_ARGS__ ); CATCH_SUCCEED( #__VA_ARGS__ ) +#define CATCH_STATIC_REQUIRE_FALSE( ... ) static_assert( !(__VA_ARGS__), "!(" #__VA_ARGS__ ")" ); CATCH_SUCCEED( #__VA_ARGS__ ) +#else +#define CATCH_STATIC_REQUIRE( ... ) CATCH_REQUIRE( __VA_ARGS__ ) +#define CATCH_STATIC_REQUIRE_FALSE( ... ) CATCH_REQUIRE_FALSE( __VA_ARGS__ ) +#endif + +// "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 ) INTERNAL_CATCH_DYNAMIC_SECTION( " Given: " << desc ) +#define CATCH_AND_GIVEN( desc ) INTERNAL_CATCH_DYNAMIC_SECTION( "And given: " << desc ) +#define CATCH_WHEN( desc ) INTERNAL_CATCH_DYNAMIC_SECTION( " When: " << desc ) +#define CATCH_AND_WHEN( desc ) INTERNAL_CATCH_DYNAMIC_SECTION( " And when: " << desc ) +#define CATCH_THEN( desc ) INTERNAL_CATCH_DYNAMIC_SECTION( " Then: " << desc ) +#define CATCH_AND_THEN( desc ) INTERNAL_CATCH_DYNAMIC_SECTION( " 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( ... ) INTERNAL_CATCH_CAPTURE( INTERNAL_CATCH_UNIQUE_NAME(capturer), "CAPTURE",__VA_ARGS__ ) + +#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 DYNAMIC_SECTION( ... ) INTERNAL_CATCH_DYNAMIC_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() + +#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR +#define TEMPLATE_TEST_CASE( ... ) INTERNAL_CATCH_TEMPLATE_TEST_CASE( __VA_ARGS__ ) +#define TEMPLATE_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD( className, __VA_ARGS__ ) +#else +#define TEMPLATE_TEST_CASE( ... ) INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE( __VA_ARGS__ ) ) +#define TEMPLATE_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD( className, __VA_ARGS__ ) ) +#endif + +#if !defined(CATCH_CONFIG_RUNTIME_STATIC_REQUIRE) +#define STATIC_REQUIRE( ... ) static_assert( __VA_ARGS__, #__VA_ARGS__ ); SUCCEED( #__VA_ARGS__ ) +#define STATIC_REQUIRE_FALSE( ... ) static_assert( !(__VA_ARGS__), "!(" #__VA_ARGS__ ")" ); SUCCEED( "!(" #__VA_ARGS__ ")" ) +#else +#define STATIC_REQUIRE( ... ) REQUIRE( __VA_ARGS__ ) +#define STATIC_REQUIRE_FALSE( ... ) REQUIRE_FALSE( __VA_ARGS__ ) +#endif + +#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 ) INTERNAL_CATCH_DYNAMIC_SECTION( " Given: " << desc ) +#define AND_GIVEN( desc ) INTERNAL_CATCH_DYNAMIC_SECTION( "And given: " << desc ) +#define WHEN( desc ) INTERNAL_CATCH_DYNAMIC_SECTION( " When: " << desc ) +#define AND_WHEN( desc ) INTERNAL_CATCH_DYNAMIC_SECTION( " And when: " << desc ) +#define THEN( desc ) INTERNAL_CATCH_DYNAMIC_SECTION( " Then: " << desc ) +#define AND_THEN( desc ) INTERNAL_CATCH_DYNAMIC_SECTION( " And: " << desc ) + +using Catch::Detail::Approx; + +#else // 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( ... ) (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_DYNAMIC_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____ )) + +#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR +#define CATCH_TEMPLATE_TEST_CASE( ... ) INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ) ) +#define CATCH_TEMPLATE_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), className ) +#else +#define CATCH_TEMPLATE_TEST_CASE( ... ) INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ) ) ) +#define CATCH_TEMPLATE_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), className ) ) +#endif + +// "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_AND_GIVEN( desc ) +#define CATCH_WHEN( desc ) +#define CATCH_AND_WHEN( desc ) +#define CATCH_THEN( desc ) +#define CATCH_AND_THEN( desc ) + +#define CATCH_STATIC_REQUIRE( ... ) (void)(0) +#define CATCH_STATIC_REQUIRE_FALSE( ... ) (void)(0) + +// 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 DYNAMIC_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____ )) + +#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR +#define TEMPLATE_TEST_CASE( ... ) INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ) ) +#define TEMPLATE_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), className ) +#else +#define TEMPLATE_TEST_CASE( ... ) INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ) ) ) +#define TEMPLATE_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_EXPAND_VARGS( INTERNAL_CATCH_TEMPLATE_TEST_CASE_METHOD_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_M_P_L_A_T_E____T_E_S_T____ ), className ) ) +#endif + +#define STATIC_REQUIRE( ... ) (void)(0) +#define STATIC_REQUIRE_FALSE( ... ) (void)(0) + +#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 AND_GIVEN( desc ) +#define WHEN( desc ) +#define AND_WHEN( desc ) +#define THEN( desc ) +#define AND_THEN( desc ) + +using Catch::Detail::Approx; + +#endif + +#endif // ! CATCH_CONFIG_IMPL_ONLY + +// 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/applications/calibration-ceres/test/tests.cpp b/applications/calibration-ceres/test/tests.cpp new file mode 100644 index 0000000000000000000000000000000000000000..49d9bf522ea5c5ba028e1e38be57f5174cff0f67 --- /dev/null +++ b/applications/calibration-ceres/test/tests.cpp @@ -0,0 +1,3 @@ +#define CATCH_CONFIG_MAIN + +#include "catch.hpp" \ No newline at end of file diff --git a/applications/calibration-ceres/test/visibility_unit.cpp b/applications/calibration-ceres/test/visibility_unit.cpp new file mode 100644 index 0000000000000000000000000000000000000000..ebdfc178b7fc465f1114620e46a3587865f91180 --- /dev/null +++ b/applications/calibration-ceres/test/visibility_unit.cpp @@ -0,0 +1,47 @@ +#include "catch.hpp" +#include "visibility.hpp" + +using std::vector; +using ftl::calibration::dijstra; + +/// https://www.geeksforgeeks.org/dijkstras-shortest-path-algorithm-greedy-algo-7/ +static const vector<vector<int>> graph1 = { + {0, 4, 0, 0, 0, 0, 0, 8, 0}, + {4, 0, 8, 0, 0, 0, 0,11, 0}, + {0, 8, 0, 7, 0, 4, 0, 0, 2}, + {0, 0, 7, 0, 9,14, 0, 0, 0}, + {0, 0, 0, 9, 0,10, 0, 0, 0}, + {0, 0, 4,14,10, 0, 2, 0, 0}, + {0, 0, 0, 0, 0, 2, 0, 1, 6}, + {8,11, 0, 0, 0, 0, 1, 0, 7}, + {0, 0, 2, 0, 0, 0, 6, 7, 0} +}; + +TEST_CASE("Dijstra's Algorithm", "") { + SECTION("Find shortest paths") { + auto path = dijstra(0, graph1); + + REQUIRE(path.distance(1) == 4); + REQUIRE(path.distance(2) == 12); + REQUIRE(path.distance(3) == 19); + REQUIRE(path.distance(4) == 21); + REQUIRE(path.distance(5) == 11); + REQUIRE(path.distance(6) == 9); + REQUIRE(path.distance(7) == 8); + REQUIRE(path.distance(8) == 14); + + REQUIRE((path.to(1) == vector {1})); + REQUIRE((path.to(2) == vector {1, 2})); + REQUIRE((path.to(3) == vector {1, 2, 3})); + REQUIRE((path.to(4) == vector {7, 6, 5, 4})); + REQUIRE((path.to(5) == vector {7, 6, 5})); + REQUIRE((path.to(6) == vector {7, 6})); + REQUIRE((path.to(7) == vector {7})); + REQUIRE((path.to(8) == vector {1, 2, 8})); + } + + SECTION("Check connectivity") { + auto path = dijstra(0, graph1); + REQUIRE(path.connected()); + } +} diff --git a/applications/calibration-multi/CMakeLists.txt b/applications/calibration-multi/CMakeLists.txt index d14704e2ada4943f18d35cb792c682fa3dd01a25..135d48adfea1a7114868baa0d3fc7bfe7680160a 100644 --- a/applications/calibration-multi/CMakeLists.txt +++ b/applications/calibration-multi/CMakeLists.txt @@ -3,10 +3,13 @@ set(CALIBMULTI src/visibility.cpp src/util.cpp src/multicalibrate.cpp + ../calibration-ceres/src/optimization.cpp + ../calibration-ceres/src/calibration.cpp + ../calibration-ceres/src/calibration_data.cpp ) add_executable(ftl-calibrate-multi ${CALIBMULTI}) -target_include_directories(ftl-calibrate-multi PRIVATE src) +target_include_directories(ftl-calibrate-multi PRIVATE src ../calibration-ceres/src) -target_link_libraries(ftl-calibrate-multi ftlcommon ftlnet ftlrgbd ftlstreams Threads::Threads ${OpenCV_LIBS} ${cvsba_LIBS}) +target_link_libraries(ftl-calibrate-multi ftlcommon ftlnet ftlrgbd ftlstreams Threads::Threads ${OpenCV_LIBS} ceres) diff --git a/applications/calibration-multi/src/main.cpp b/applications/calibration-multi/src/main.cpp index a9ce6ad4e07b3066a80f891bb468c15e2d5cc7dc..4cbd5f28466d52e6cbdf55f774e85f9cbad94925 100644 --- a/applications/calibration-multi/src/main.cpp +++ b/applications/calibration-multi/src/main.cpp @@ -10,6 +10,7 @@ #include <ftl/streams/netstream.hpp> #include <opencv2/core.hpp> +#include <opencv2/calib3d.hpp> #include <opencv2/aruco.hpp> #include <opencv2/core/eigen.hpp> #include <opencv2/opencv.hpp> @@ -44,6 +45,18 @@ using ftl::net::Universe; using ftl::rgbd::Source; using ftl::codecs::Channel; +vector<Point3d> calibration_target = { + Point3d(0.0, 0.0, 0.0), + Point3d(0.15, 0.0, 0.0), + Point3d(0.15, 0.15, 0.0), + Point3d(0.0, 0.15, 0.0), + + Point3d(0.25, 0.0, 0.0), + Point3d(0.40, 0.0, 0.0), + Point3d(0.40, 0.15, 0.0), + Point3d(0.25, 0.15, 0.0) +}; + Mat createCameraMatrix(const ftl::rgbd::Camera ¶meters) { Mat m = (cv::Mat_<double>(3,3) << parameters.fx, 0.0, -parameters.cx, @@ -62,6 +75,7 @@ struct CalibrationParams { int reference_camera = -1; double alpha = 0.0; Size size; + bool offline = false; }; //////////////////////////////////////////////////////////////////////////////// @@ -204,8 +218,8 @@ void calibrateRPC( ftl::net::Universe* net, // calculate extrinsics from rectified parameters Mat _t = Mat(Size(1, 3), CV_64FC1, Scalar(0.0)); - Rt_out[c] = getMat4x4(R[c], t[c]) * getMat4x4(R1, _t).inv(); - Rt_out[c + 1] = getMat4x4(R[c + 1], t[c + 1]) * getMat4x4(R2, _t).inv(); + //Rt_out[c] = getMat4x4(R[c], t[c]) * getMat4x4(R1, _t).inv(); + //Rt_out[c + 1] = getMat4x4(R[c + 1], t[c + 1]) * getMat4x4(R2, _t).inv(); LOG(INFO) << K1; LOG(INFO) << K2; @@ -218,10 +232,11 @@ void calibrateRPC( ftl::net::Universe* net, while(true) { try { if (params.optimize_intrinsic) { - setIntrinsicsRPC(net, nstream, params.size, {K1, K2}, {D1, D2}); + // never update distortion during extrinsic calibration + setIntrinsicsRPC(net, nstream, params.size, {K1, K2}, {Mat(0, 0, CV_64FC1), Mat(0, 0, CV_64FC1)}); } setExtrinsicsRPC(net, nstream, R_c1c2, T_c1c2); - setPoseRPC(net, nstream, Rt_out[c]); + setPoseRPC(net, nstream, getMat4x4(R[c], t[c])); saveCalibrationRPC(net, nstream); LOG(INFO) << "CALIBRATION SENT"; break; @@ -242,6 +257,46 @@ void calibrateRPC( ftl::net::Universe* net, } } +std::vector<cv::Point2d> findCalibrationTarget(const cv::Mat &im, const cv::Mat &K) { + // check input type + std::vector<std::vector<cv::Point2f>> corners; + std::vector<int> ids; + + auto params = cv::aruco::DetectorParameters::create(); + params->cornerRefinementMinAccuracy = 0.01; + params->cornerRefinementMethod = cv::aruco::CORNER_REFINE_CONTOUR; + cv::aruco::detectMarkers(im, cv::aruco::getPredefinedDictionary(cv::aruco::DICT_5X5_100), corners, ids, params, cv::noArray(), K); + + if (corners.size() > 2) { LOG(ERROR) << "Too many ArUco tags in image"; } + if (corners.size() != 2) { return {}; } + + const size_t ncorners = 4; + const size_t ntags = ids.size(); + + std::vector<cv::Point2d> points; + + if (ids[0] == 1) { + std::swap(ids[0], ids[1]); + std::swap(corners[0], corners[1]); + } + + if (ids[0] != 0) { + LOG(ERROR) << "Tags ID0 and ID1 expected"; + return {}; + } + + points.reserve(ntags*ncorners); + + for (size_t i = 0; i < ntags; i++) { + for (size_t j = 0; j < ncorners; j++) { + points.push_back(corners[i][j]); + } + } + + return points; +} + + void runCameraCalibration( ftl::Configurable* root, int n_views, int min_visible, string path, string filename, @@ -374,8 +429,9 @@ void runCameraCalibration( ftl::Configurable* root, // TODO: parameter for calibration target type auto calib = MultiCameraCalibrationNew( n_cameras, reference_camera, - params.size, CalibrationTarget(0.250) + params.size, CalibrationTarget(0.15) ); + calib.object_points_ = calibration_target; int iter = 0; Mat show; @@ -408,8 +464,21 @@ void runCameraCalibration( ftl::Configurable* root, } visible.clear(); - int n_found = findCorrespondingPoints(rgb, points, visible); + visible.resize(n_cameras, 0); + int n_found = 0; + for (size_t i = 0; i < n_cameras; i++) { + auto new_points = findCalibrationTarget(rgb[i], camera_parameters[i]); + if (new_points.size() == 0) { + points[i] = vector(8, Point2d(0.0,0.0)); + } + else { + points[i] = new_points; + visible[i] = 1; + n_found++; + } + } + if (n_found >= min_visible) { calib.addPoints(points, visible); @@ -423,10 +492,11 @@ void runCameraCalibration( ftl::Configurable* root, for (size_t i = 0; i < n_cameras; i++) { if (visible[i]) { - cv::drawMarker( rgb[i], points[i][0], - Scalar(42, 255, 42), cv::MARKER_TILTED_CROSS, 25, 2); - cv::drawMarker( rgb[i], points[i][1], - Scalar(42, 42, 255), cv::MARKER_TILTED_CROSS, 25, 2); + for (int j = 0; j < points[i].size(); j++) { + cv::drawMarker( rgb[i], points[i][j], Scalar(42, 255, 42), cv::MARKER_CROSS, 25, 1); + cv::putText(rgb[i], std::to_string(j), Point2i(points[i][j]), + cv::FONT_HERSHEY_COMPLEX_SMALL, 1.0, Scalar(64, 64, 255), 1); + } } // index @@ -523,6 +593,201 @@ void runCameraCalibration( ftl::Configurable* root, ftl::pool.stop(true); } +void runCameraCalibrationPath( ftl::Configurable* root, + string path, string filename, + CalibrationParams ¶ms) +{ + Universe *net = ftl::create<Universe>(root, "net"); + ftl::ctrl::Master ctrl(root, net); + + net->start(); + net->waitConnections(); + + ftl::stream::Muxer *stream = ftl::create<ftl::stream::Muxer>(root, "muxstream"); + ftl::stream::Receiver *gen = ftl::create<ftl::stream::Receiver>(root, "receiver"); + gen->setStream(stream); + auto stream_uris = net->findAll<std::string>("list_streams"); + std::sort(stream_uris.begin(), stream_uris.end()); + std::vector<ftl::stream::Net*> nstreams; + + int count = 0; + for (auto &s : stream_uris) { + LOG(INFO) << " --- found stream: " << s; + auto *nstream = ftl::create<ftl::stream::Net>(stream, std::to_string(count), net); + std::string name = *(nstream->get<std::string>("name")); + nstream->set("uri", s); + nstreams.push_back(nstream); + stream->add(nstream); + + ++count; + } + + const size_t n_sources = nstreams.size(); + const size_t n_cameras = n_sources * 2; + size_t reference_camera = 0; + + std::mutex mutex; + std::atomic<bool> new_frames = false; + vector<Mat> rgb_(n_cameras), rgb_new(n_cameras); + vector<Mat> camera_parameters(n_cameras); + Size res; + + gen->onFrameSet([stream, &mutex, &new_frames, &rgb_new, &camera_parameters, &res](ftl::rgbd::FrameSet &fs) { + stream->select(fs.id, Channel::Left + Channel::Right); + if (fs.frames.size() != (rgb_new.size()/2)) { + // nstreams.size() == (rgb_new.size()/2) + LOG(ERROR) << "frames.size() != nstreams.size(), " + << fs.frames.size() << " != " << (rgb_new.size()/2); + } + + UNIQUE_LOCK(mutex, CALLBACK); + bool good = true; + try { + for (size_t i = 0; i < fs.frames.size(); i ++) { + if (!fs.frames[i].hasChannel(Channel::Left)) { + good = false; + LOG(ERROR) << "No left channel"; + break; + } + + if (!fs.frames[i].hasChannel(Channel::Right)) { + good = false; + LOG(ERROR) << "No right channel"; + break; + } + + auto idx = stream->originStream(0, i); + CHECK(idx >= 0) << "negative index"; + + fs.frames[i].download(Channel::Left+Channel::Right); + Mat &left = fs.frames[i].get<Mat>(Channel::Left); + Mat &right = fs.frames[i].get<Mat>(Channel::Right); + + CHECK(!left.empty() && !right.empty()); + + cv::cvtColor(left, rgb_new[2*idx], cv::COLOR_BGRA2BGR); + cv::cvtColor(right, rgb_new[2*idx+1], cv::COLOR_BGRA2BGR); + + camera_parameters[2*idx] = createCameraMatrix(fs.frames[i].getLeftCamera()); + camera_parameters[2*idx+1] = createCameraMatrix(fs.frames[i].getRightCamera()); + if (res.empty()) res = rgb_new[2*idx].size(); + } + } + catch (std::exception ex) { + LOG(ERROR) << "exception: " << ex.what(); + good = false; + } + catch (...) { + LOG(ERROR) << "unknown exception"; + good = false; + } + new_frames = good; + return true; + }); + + stream->begin(); + ftl::timer::start(false); + + while(true) { + if (!res.empty()) { + LOG(INFO) << "Camera resolution: " << params.size; + break; + } + std::this_thread::sleep_for(std::chrono::seconds(1)); + } + + for (auto *nstream: nstreams) { + bool res = true; + while(res) { + try { res = setRectifyRPC(net, nstream, false); } + catch (...) {} + + if (res) { + LOG(ERROR) << "set_rectify() failed for " << *(nstream->get<string>("uri")); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + else { + LOG(INFO) << "rectification disabled for " << *(nstream->get<string>("uri")); + } + } + } + + // TODO: parameter for calibration target type + auto calib = MultiCameraCalibrationNew( n_cameras, reference_camera, + params.size, CalibrationTarget(0.150) + ); + calib.object_points_ = calibration_target; + + cv::FileStorage fs(path + filename, cv::FileStorage::READ); + fs["resolution"] >> params.size; + params.idx_cameras.resize(n_cameras); + std::iota(params.idx_cameras.begin(), params.idx_cameras.end(), 0); + calib.loadInput(path + filename, params.idx_cameras); + + for (size_t i = 0; i < nstreams.size(); i++) { + while(true) { + try { + if (camera_parameters[2*i].empty() || camera_parameters[2*i+1].empty()) { + std::this_thread::sleep_for(std::chrono::seconds(1)); + continue; + } + vector<Mat> D = getDistortionParametersRPC(net, nstreams[i]); + LOG(INFO) << "K[" << 2*i << "] = \n" << camera_parameters[2*i]; + LOG(INFO) << "D[" << 2*i << "] = " << D[0]; + LOG(INFO) << "K[" << 2*i+1 << "] = \n" << camera_parameters[2*i+1]; + LOG(INFO) << "D[" << 2*i+1 << "] = " << D[1]; + calib.setCameraParameters(2*i, camera_parameters[2*i], D[0]); + calib.setCameraParameters(2*i+1, camera_parameters[2*i+1], D[1]); + break; + } + catch (...) {} + } + } + + + Mat out; + vector<Mat> map1, map2; + vector<cv::Rect> roi; + vector<size_t> idx; + calibrateRPC(net, calib, params, nstreams, map1, map2, roi); + + + vector<Mat> rgb(n_cameras); + + // visualize + while(cv::waitKey(10) != 27) { + + while (!new_frames) { + if (cv::waitKey(50) != -1) { ftl::running = false; } + } + + { + UNIQUE_LOCK(mutex, LOCK) + rgb.swap(rgb_new); + new_frames = false; + } + + visualizeCalibration(calib, out, rgb, map1, map2, roi); + cv::namedWindow("Calibration", cv::WINDOW_KEEPRATIO | cv::WINDOW_NORMAL); + cv::imshow("Calibration", out); + } + + for (size_t i = 0; i < nstreams.size(); i++) { + while(true) { + try { + setRectifyRPC(net, nstreams[i], true); + break; + } + catch (...) {} + } + } + + ftl::running = false; + ftl::timer::stop(); + ftl::pool.stop(true); +} + + int main(int argc, char **argv) { auto options = ftl::config::read_options(&argv, &argc); auto root = ftl::configure(argc, argv, "registration_default"); @@ -551,7 +816,10 @@ int main(int argc, char **argv) { // location where extrinsic calibration files saved const string output_directory = root->value<string>("output_directory", "./"); + const bool offline = root->value<bool>("offline", false); + CalibrationParams params; + params.offline = offline; params.save_extrinsic = save_extrinsic; params.save_intrinsic = save_intrinsic; params.optimize_intrinsic = optimize_intrinsic; @@ -576,7 +844,7 @@ int main(int argc, char **argv) { << "\n"; if (load_input) { - LOG(FATAL) << "TODO"; + runCameraCalibrationPath(root, calibration_data_dir, calibration_data_file, params); } else { runCameraCalibration(root, n_views, min_visible, calibration_data_dir, calibration_data_file, save_input, params); diff --git a/applications/calibration-multi/src/multicalibrate.cpp b/applications/calibration-multi/src/multicalibrate.cpp index 071b6778d29fe1795621dc502244286ebab2637b..b9627ce252211ef9075e165270d6d88376038814 100644 --- a/applications/calibration-multi/src/multicalibrate.cpp +++ b/applications/calibration-multi/src/multicalibrate.cpp @@ -1,9 +1,12 @@ #include "multicalibrate.hpp" +#include "calibration_data.hpp" +#include "calibration.hpp" +#include "optimization.hpp" + #include <opencv2/core.hpp> #include <opencv2/calib3d.hpp> -#include <cvsba/cvsba.h> #include <loguru.hpp> #include <map> @@ -143,9 +146,9 @@ Mat MultiCameraCalibrationNew::getDistCoeffs(size_t idx) { } void MultiCameraCalibrationNew::setCameraParameters(size_t idx, const Mat &K, const Mat &distCoeffs) { - DCHECK(idx < n_cameras_); - DCHECK(K.size() == Size(3, 3)); - DCHECK(distCoeffs.size() == Size(5, 1)); + CHECK(idx < n_cameras_); + CHECK(K.size() == Size(3, 3)); + CHECK(distCoeffs.total() == 5); K.convertTo(K_[idx], CV_64FC1); distCoeffs.convertTo(dist_coeffs_[idx], CV_64FC1); } @@ -185,6 +188,7 @@ void MultiCameraCalibrationNew::saveInput(const string &filename) { void MultiCameraCalibrationNew::saveInput(cv::FileStorage &fs) { fs << "resolution" << resolution_; fs << "K" << K_; + fs << "D" << dist_coeffs_; fs << "points2d" << points2d_; fs << "visible" << visible_; } @@ -195,12 +199,14 @@ void MultiCameraCalibrationNew::loadInput(const std::string &filename, const vec points3d_optimized_.clear(); visible_.clear(); inlier_.clear(); - + K_.clear(); + dist_coeffs_.clear(); cv::FileStorage fs(filename, cv::FileStorage::READ); vector<Mat> K; vector<vector<Point2d>> points2d; vector<vector<int>> visible; fs["K"] >> K; + fs["D"] >> dist_coeffs_; fs["points2d"] >> points2d; fs["visible"] >> visible; fs["resolution"] >> resolution_; @@ -225,6 +231,7 @@ void MultiCameraCalibrationNew::loadInput(const std::string &filename, const vec for (auto const &c : cameras) { K_.push_back(K[c]); + LOG(INFO) << K[c]; } for (size_t c = 0; c < n_cameras_; c++) { points2d_[c].reserve(visible[0].size()); @@ -235,7 +242,6 @@ void MultiCameraCalibrationNew::loadInput(const std::string &filename, const vec visibility_graph_ = Visibility(n_cameras_); dist_coeffs_.resize(n_cameras_); - for (auto &d : dist_coeffs_ ) { d = Mat(Size(5, 1), CV_64FC1, Scalar(0.0)); } vector<vector<Point2d>> points2d_add(n_cameras_, vector<Point2d>()); vector<int> visible_add(n_cameras_); @@ -372,6 +378,7 @@ void MultiCameraCalibrationNew::getVisiblePoints( double MultiCameraCalibrationNew::calibratePair(size_t camera_from, size_t camera_to, Mat &rmat, Mat &tvec) { + vector<size_t> idx; vector<Point2d> points1, points2; { @@ -386,10 +393,10 @@ double MultiCameraCalibrationNew::calibratePair(size_t camera_from, size_t camer // cameras possibly lack line of sight? DCHECK(points1.size() > 8); - + Mat &K1 = K_[camera_from]; Mat &K2 = K_[camera_to]; - + /* vector<uchar> inliers; Mat F, E; F = cv::findFundamentalMat(points1, points2, fm_method_, fm_ransac_threshold_, fm_confidence_, inliers); @@ -467,8 +474,7 @@ double MultiCameraCalibrationNew::calibratePair(size_t camera_from, size_t camer // Estimate and apply scale factor { - double scale = target_.estimateScale(points3d); - for (auto &p : points3d) { p = p * scale; } + double scale = ftl::calibration::optimizeScale(object_points_, points3d); t1 = t1 * scale; t2 = t2 * scale; } @@ -489,45 +495,44 @@ double MultiCameraCalibrationNew::calibratePair(size_t camera_from, size_t camer } // Bundle Adjustment - // vector<Point3d> points3d_triangulated; - // points3d_triangulated.insert(points3d_triangulated.begin(), points3d.begin(), points3d.end()); double err = INFINITY; - cvsba::Sba sba; { - sba.setParams(cvsba::Sba::Params(cvsba::Sba::TYPE::MOTIONSTRUCTURE, 200, 1.0e-30, 5, 5, false)); - - Mat rvec1, rvec2; - cv::Rodrigues(R1, rvec1); - cv::Rodrigues(R2, rvec2); - - auto points2d = vector<vector<Point2d>> { points1, points2 }; - auto K = vector<Mat> { K1, K2 }; - auto r = vector<Mat> { rvec1, rvec2 }; - auto t = vector<Mat> { t1, t2 }; - auto dcoeffs = vector<Mat> { dist_coeffs_[camera_from], dist_coeffs_[camera_to] }; - - sba.run(points3d, - vector<vector<Point2d>> { points1, points2 }, - vector<vector<int>>(2, vector<int>(points1.size(), 1)), - K, r, t, dcoeffs - ); - - cv::Rodrigues(r[0], R1); - cv::Rodrigues(r[1], R2); - t1 = t[0]; - t2 = t[1]; + auto cameras = vector<ftl::calibration::Camera> { + ftl::calibration::Camera(K1, dist_coeffs_[camera_from], R1, t1), + ftl::calibration::Camera(K2, dist_coeffs_[camera_to], R2, t2) + }; + + ftl::calibration::BundleAdjustment ba; + ba.addCameras(cameras); + for (size_t i = 0; i < points3d.size(); i++) { + ba.addPoint({points1[i], points2[i]}, points3d[i]); + } + + ftl::calibration::BundleAdjustment::Options options; + options.fix_camera_extrinsic = {0}; + options.optimize_intrinsic = false; - // intrinsic parameters should only be optimized at final BA - //K1 = K[0]; - //K2 = K[1]; + ba.run(options); + // TODO: ... + err = sqrt(ba.reprojectionError(0) * ba.reprojectionError(1)); - err = sba.getFinalReprjError(); - LOG(INFO) << "SBA reprojection error before BA " << sba.getInitialReprjError(); - LOG(INFO) << "SBA reprojection error after BA " << err; + R2 = cameras[1].rmat(); + t2 = Mat(cameras[1].tvec()); } calculateTransform(R2, t2, R1, t1, rmat, tvec); + */ + + Mat R1, R2, t1, t2; + R1 = Mat::eye(Size(3, 3), CV_64FC1); + t1 = Mat(Size(1, 3), CV_64FC1, Scalar(0.0)); + + vector<Point3d> points3d; + + double err = ftl::calibration::computeExtrinsicParameters(K1, dist_coeffs_[camera_from], K2, dist_coeffs_[camera_to], points1, points2, object_points_, R2, t2, points3d); + calculateTransform(R2, t2, R1, t1, rmat, tvec); + // Store and average 3D points for both cameras (skip garbage) if (err < 10.0) { @@ -698,20 +703,20 @@ double MultiCameraCalibrationNew::calibrateAll(int reference_camera) { } double err; - cvsba::Sba sba; { - sba.setParams(cvsba::Sba::Params(cvsba::Sba::TYPE::MOTIONSTRUCTURE, 200, 1.0e-24, fix_intrinsics_, fix_intrinsics_, false)); + auto cameras = vector<ftl::calibration::Camera>(); + + for (size_t i = 0; i < n_cameras_; i++) { + calculateInverse(R_[i], t_[i], R_[i], t_[i]); + cameras.push_back(ftl::calibration::Camera(K_[i], dist_coeffs_[i], R_[i], t_[i])); + } - vector<Mat> rvecs(R_.size()); - vector<vector<int>> visible(R_.size()); - vector<Point3d> points3d; - vector<vector<Point2d>> points2d(R_.size()); - vector<size_t> idx; - idx.reserve(points3d_optimized_.size()); + ftl::calibration::BundleAdjustment ba; + ba.addCameras(cameras); for (size_t i = 0; i < points3d_optimized_.size(); i++) { - auto p = points3d_optimized_[i]; + auto &p = points3d_optimized_[i]; DCHECK(!isnanl(p.x) && !isnanl(p.y) && !isnanl(p.z)); int count = 0; @@ -720,53 +725,36 @@ double MultiCameraCalibrationNew::calibrateAll(int reference_camera) { } if (count < 2) continue; - - points3d.push_back(p); - idx.push_back(i); + + vector<bool> visible(n_cameras_); + vector<Point2d> points2d(n_cameras_); for (size_t c = 0; c < n_cameras_; c++) { bool good = isVisible(c, i) && isValid(c, i); - visible[c].push_back(good ? 1 : 0); - points2d[c].push_back(points2d_[c][i]); + visible[c] = good; + points2d[c] = points2d_[c][i]; } - } - for (size_t i = 0; i < rvecs.size(); i++) { - calculateInverse(R_[i], t_[i], R_[i], t_[i]); - cv::Rodrigues(R_[i], rvecs[i]); + ba.addPoint(visible, points2d, p); } - DCHECK(points2d.size() == n_cameras_); - DCHECK(visible.size() == n_cameras_); - for (size_t c = 0; c < n_cameras_; c++) { - DCHECK(points3d.size() == points2d[c].size()); - DCHECK(points3d.size() == visible[c].size()); - } - - LOG(INFO) << "number of points used: " << points3d.size(); - sba.run(points3d, points2d, visible, - K_, rvecs, t_, dist_coeffs_ - ); - - for (size_t i = 0; i < rvecs.size(); i++) { - cv::Rodrigues(rvecs[i], R_[i]); + ftl::calibration::BundleAdjustment::Options options; + options.optimize_intrinsic = !fix_intrinsics_; + options.fix_distortion = true; + options.max_iter = 50; + options.fix_camera_extrinsic = {reference_camera}; + options.verbose = true; + + err = ba.reprojectionError(); + ba.run(options); + + for (size_t i = 0; i < n_cameras_; i++) { + R_[i] = cameras[i].rmat(); + t_[i] = cameras[i].tvec(); + K_[i] = cameras[i].intrinsicMatrix(); + //dist_coeffs_[i] = D; // not updated calculateInverse(R_[i], t_[i], R_[i], t_[i]); } - - // save optimized points - { - size_t l = points3d.size(); - points3d_optimized_.clear(); - points3d_optimized_.resize(l, Point3d(NAN, NAN, NAN)); - - for (size_t i = 0; i < points3d.size(); i++) { - points3d_optimized_[idx[i]] = points3d[i]; - } - } - - err = sba.getFinalReprjError(); - LOG(INFO) << "SBA reprojection error before final BA " << sba.getInitialReprjError(); - LOG(INFO) << "SBA reprojection error after final BA " << err; } for (size_t c_from = 0; c_from < n_cameras_; c_from++) { diff --git a/applications/calibration-multi/src/multicalibrate.hpp b/applications/calibration-multi/src/multicalibrate.hpp index 707e9d4e7739f81f969ed212685c7157f0166555..f696e6328d69126cc864c9df97909b9f3154e841 100644 --- a/applications/calibration-multi/src/multicalibrate.hpp +++ b/applications/calibration-multi/src/multicalibrate.hpp @@ -69,6 +69,8 @@ public: void projectPointsOriginal(size_t camera_src, size_t camera_dst, size_t idx, vector<Point2d> &points); void projectPointsOptimized(size_t camera_dst, size_t idx, vector<Point2d> &points); + std::vector<cv::Point3d> object_points_; + protected: bool isVisible(size_t camera, size_t idx); bool isValid(size_t camera, size_t idx); @@ -127,6 +129,7 @@ protected: /* @brief Remove old calibration data calculated by calibrateAll */ void reset(); + private: CalibrationTarget target_; Visibility visibility_graph_; diff --git a/applications/calibration/src/lens.cpp b/applications/calibration/src/lens.cpp index bc675d3659041a3598695ef3924566b7135a84e1..b9a01581582b4ef12482932d839a0caccaf1367e 100644 --- a/applications/calibration/src/lens.cpp +++ b/applications/calibration/src/lens.cpp @@ -2,6 +2,7 @@ #include "lens.hpp" #include <ftl/config.h> +#include <ftl/calibration.hpp> #include <loguru.hpp> @@ -35,7 +36,7 @@ void ftl::calibration::intrinsic(map<string, string> &opt) { const Size image_size = Size( getOptionInt(opt, "width", 1920), getOptionInt(opt, "height", 1080)); const int n_cameras = getOptionInt(opt, "n_cameras", 2); - const int iter = getOptionInt(opt, "iter", 40); + const int iter = getOptionInt(opt, "iter", 20); const int delay = getOptionInt(opt, "delay", 1000); const double aperture_width = getOptionDouble(opt, "aperture_width", 6.2); const double aperture_height = getOptionDouble(opt, "aperture_height", 4.6); @@ -59,44 +60,43 @@ void ftl::calibration::intrinsic(map<string, string> &opt) { LOG(INFO) << "-----------------------------------"; - int calibrate_flags = cv::CALIB_ZERO_TANGENT_DIST | cv::CALIB_FIX_ASPECT_RATIO; - if (use_guess) { calibrate_flags |= cv::CALIB_USE_INTRINSIC_GUESS; } - // cv::CALIB_FIX_PRINCIPAL_POINT; - // PARAMETERS - + // assume no tangential and thin prism distortion and only estimate first + // three radial distortion coefficients + + int calibrate_flags = cv::CALIB_FIX_K4 | cv::CALIB_FIX_K5 | cv::CALIB_FIX_K6 | + cv::CALIB_ZERO_TANGENT_DIST | cv::CALIB_FIX_S1_S2_S3_S4 | cv::CALIB_FIX_ASPECT_RATIO; vector<Mat> camera_matrix(n_cameras), dist_coeffs(n_cameras); - for (Mat &d : dist_coeffs) - { - d = Mat(Size(5, 1), CV_64FC1, cv::Scalar(0.0)); + for (Mat &d : dist_coeffs) { + d = Mat(Size(8, 1), CV_64FC1, cv::Scalar(0.0)); } - if (use_guess) - { + if (use_guess) { camera_matrix.clear(); vector<Mat> tmp; Size tmp_size; loadIntrinsics(filename_intrinsics, camera_matrix, tmp, tmp_size); - CHECK(camera_matrix.size() == static_cast<unsigned int>(n_cameras)); // (camera_matrix.size() == dist_coeffs.size()) - if ((tmp_size != image_size) && (!tmp_size.empty())) - { - Mat scale = Mat::eye(Size(3, 3), CV_64FC1); - scale.at<double>(0, 0) = ((double) image_size.width) / ((double) tmp_size.width); - scale.at<double>(1, 1) = ((double) image_size.height) / ((double) tmp_size.height); - for (Mat &K : camera_matrix) { K = scale * K; } + CHECK(camera_matrix.size() == static_cast<unsigned int>(n_cameras)); + + if ((tmp_size != image_size) && (!tmp_size.empty())) { + for (Mat &K : camera_matrix) { + K = ftl::calibration::scaleCameraMatrix(K, image_size, tmp_size); + } } - if (tmp_size.empty()) - { - use_guess = false; - LOG(FATAL) << "No valid calibration found."; + if (tmp_size.empty()) { + LOG(ERROR) << "No valid calibration found."; + } + else { + calibrate_flags |= cv::CALIB_USE_INTRINSIC_GUESS; } } vector<cv::VideoCapture> cameras; cameras.reserve(n_cameras); + for (int c = 0; c < n_cameras; c++) { cameras.emplace_back(c); } for (auto &camera : cameras) { @@ -116,37 +116,32 @@ void ftl::calibration::intrinsic(map<string, string> &opt) { vector<int> count(n_cameras, 0); Mat display(Size(image_size.width * n_cameras, image_size.height), CV_8UC3); - for (int c = 0; c < n_cameras; c++) - { + for (int c = 0; c < n_cameras; c++) { img_display[c] = Mat(display, cv::Rect(c * image_size.width, 0, image_size.width, image_size.height)); } std::mutex m; std::atomic<bool> ready = false; - auto capture = std::thread([n_cameras, delay, &m, &ready, &count, &calib, &img, &image_points, &object_points]() - { + auto capture = std::thread( + [n_cameras, delay, &m, &ready, &count, &calib, &img, &image_points, &object_points]() { + vector<Mat> tmp(n_cameras); - while(true) - { - if (!ready) - { + while(true) { + if (!ready) { std::this_thread::sleep_for(std::chrono::milliseconds(delay)); continue; } m.lock(); ready = false; - for (int c = 0; c < n_cameras; c++) - { + for (int c = 0; c < n_cameras; c++) { img[c].copyTo(tmp[c]); } m.unlock(); - for (int c = 0; c < n_cameras; c++) - { + for (int c = 0; c < n_cameras; c++) { vector<Vec2f> points; - if (calib.findPoints(tmp[c], points)) - { + if (calib.findPoints(tmp[c], points)) { count[c]++; } else { continue; } @@ -162,14 +157,11 @@ void ftl::calibration::intrinsic(map<string, string> &opt) { } }); - while (iter > *std::min_element(count.begin(), count.end())) - { - if (m.try_lock()) - { + while (iter > *std::min_element(count.begin(), count.end())) { + if (m.try_lock()) { for (auto &camera : cameras) { camera.grab(); } - for (int c = 0; c < n_cameras; c++) - { + for (int c = 0; c < n_cameras; c++) { cameras[c].retrieve(img[c]); } @@ -177,16 +169,13 @@ void ftl::calibration::intrinsic(map<string, string> &opt) { m.unlock(); } - for (int c = 0; c < n_cameras; c++) - { + for (int c = 0; c < n_cameras; c++) { img[c].copyTo(img_display[c]); m.lock(); - if (image_points[c].size() > 0) - { + if (image_points[c].size() > 0) { - for (auto &points : image_points[c]) - { + for (auto &points : image_points[c]) { calib.drawCorners(img_display[c], points); } @@ -203,9 +192,10 @@ void ftl::calibration::intrinsic(map<string, string> &opt) { } cv::destroyAllWindows(); + + bool calib_ok = true; - for (int c = 0; c < n_cameras; c++) - { + for (int c = 0; c < n_cameras; c++) { LOG(INFO) << "Calculating intrinsic paramters for camera " << std::to_string(c); vector<Mat> rvecs, tvecs; @@ -217,6 +207,21 @@ void ftl::calibration::intrinsic(map<string, string> &opt) { LOG(INFO) << "final reprojection RMS error: " << rms; + if (!ftl::calibration::validate::distortionCoefficients(dist_coeffs[c], image_size)) { + LOG(ERROR) << "Calibration failed: invalid distortion coefficients:\n" + << dist_coeffs[c]; + + LOG(WARNING) << "Estimating only intrinsic parameters for camera " << std::to_string(c); + + dist_coeffs[c] = Mat(Size(8, 1), CV_64FC1, cv::Scalar(0.0)); + calibrate_flags |= cv::CALIB_FIX_K1 | cv::CALIB_FIX_K2 | cv::CALIB_FIX_K3; + c--; + continue; + } + + calib_ok = true; + calibrate_flags &= ~cv::CALIB_FIX_K1 & ~cv::CALIB_FIX_K2 & ~cv::CALIB_FIX_K3; + double fovx, fovy, focal_length, aspect_ratio; cv::Point2d principal_point; diff --git a/applications/calibration/src/main.cpp b/applications/calibration/src/main.cpp index 698c7c9027513d8cea532f0b324f329adf5a6a08..4bdf85396d969d069e6f44d47de93ff22f5f1a75 100644 --- a/applications/calibration/src/main.cpp +++ b/applications/calibration/src/main.cpp @@ -16,15 +16,7 @@ int main(int argc, char **argv) { // Process Arguments auto options = ftl::config::read_options(&argv, &argc); - if (options.find("intrinsic") != options.end()) { - ftl::calibration::intrinsic(options); - } else if (options.find("stereo") != options.end()) { - ftl::calibration::stereo(options); - } else if (options.find("align") != options.end()) { - ftl::calibration::align(options); - } else { - LOG(ERROR) << "Must have one of: --intrinsic --stereo or --align"; - } + ftl::calibration::intrinsic(options); return 0; } diff --git a/components/codecs/include/ftl/codecs/channels.hpp b/components/codecs/include/ftl/codecs/channels.hpp index 370908195cf1590fcf5caa61400238dd6f2a42d4..fea88edf3eea2f0d2a77aae2d8edb655cc657d2f 100644 --- a/components/codecs/include/ftl/codecs/channels.hpp +++ b/components/codecs/include/ftl/codecs/channels.hpp @@ -31,8 +31,10 @@ enum struct Channel : int { Segmentation = 15, // 32S? ColourNormals = 16, // 8UC4 ColourHighRes = 17, // 8UC3 or 8UC4 + LeftHighRes = 17, // 8UC3 or 8UC4 Disparity = 18, Smoothing = 19, // 32F + RightHighRes = 20, // 8UC3 or 8UC4 Audio = 32, AudioLeft = 32, diff --git a/components/common/cpp/CMakeLists.txt b/components/common/cpp/CMakeLists.txt index 57ec51ace3ab13823105f2c5936e419e020809a6..49eaac5738ce8caff4d102d15bc8030c6798721c 100644 --- a/components/common/cpp/CMakeLists.txt +++ b/components/common/cpp/CMakeLists.txt @@ -11,6 +11,7 @@ set(COMMONSRC src/ctpl_stl.cpp src/timer.cpp src/profiler.cpp + src/calibration.cpp ) check_function_exists(uriParseSingleUriA HAVE_URIPARSESINGLE) diff --git a/components/common/cpp/include/ftl/calibration.hpp b/components/common/cpp/include/ftl/calibration.hpp new file mode 100644 index 0000000000000000000000000000000000000000..00662685237cdabf5e9d8a855ced5d1493f4a4e5 --- /dev/null +++ b/components/common/cpp/include/ftl/calibration.hpp @@ -0,0 +1,50 @@ +#pragma once +#ifndef _FTL_COMMON_CALIBRATION_HPP_ +#define _FTL_COMMON_CALIBRATION_HPP_ + +#include <opencv2/core/core.hpp> + +namespace ftl { +namespace calibration { + +namespace validate { + +/** + * @brief Valid translation for stereo camera. + */ +bool translationStereo(const cv::Mat &t); + +bool rotationMatrix(const cv::Mat &M); + +bool pose(const cv::Mat &M); + +bool cameraMatrix(const cv::Mat &M); + +/** + * @brief Check if D contains valid distortion coefficients. + * @param D distortion coefficients + * @param size resolution + * @note Tangential and prism distortion coefficients are not validated. + * + * Radial distortion is always monotonic for real lenses and distortion + * function has to be bijective. This is verified by evaluating the distortion + * function for integer values from 0 to sqrt(width^2+height^2). + * + * Camera model documented in + * https://docs.opencv.org/master/d9/d0c/group__calib3d.html#details + */ +bool distortionCoefficients(const cv::Mat &D, cv::Size size); + +} + +/** + * @brief Scale camera intrinsic matrix + * @param size_new New resolution + * @param size_old Original (camera matrix) resolution + */ +cv::Mat scaleCameraMatrix(const cv::Mat &K, const cv::Size &size_new, const cv::Size &size_old); + +} +} + +#endif diff --git a/components/common/cpp/src/calibration.cpp b/components/common/cpp/src/calibration.cpp new file mode 100644 index 0000000000000000000000000000000000000000..6a6bd8fa31197b72bec301a510a603c8b45213f1 --- /dev/null +++ b/components/common/cpp/src/calibration.cpp @@ -0,0 +1,145 @@ +#include "ftl/calibration.hpp" + +using cv::Mat; +using cv::Size; + +using namespace ftl::calibration; + +bool validate::translationStereo(const Mat &t) { + if (t.type() != CV_64F) { return false; } + if (t.channels() != 1) { return false; } + if (t.size() != Size(1, 3)) { return false; } + if (cv::norm(t, cv::NORM_L2) == 0) { return false; } + return true; +} + +bool validate::rotationMatrix(const Mat &M) { + if (M.type() != CV_64F) { return false; } + if (M.channels() != 1) { return false; } + if (M.size() != Size(3, 3)) { return false; } + + double det = cv::determinant(M); + if (abs(abs(det)-1.0) > 0.00001) { return false; } + + // TODO: floating point errors (result not exactly identity matrix) + // rotation matrix is orthogonal: M.T * M == M * M.T == I + //if (cv::countNonZero((M.t() * M) != Mat::eye(Size(3, 3), CV_64FC1)) != 0) + // { return false; } + + return true; +} + +bool validate::pose(const Mat &M) { + if (M.size() != Size(4, 4)) { return false; } + if (!validate::rotationMatrix(M(cv::Rect(0 , 0, 3, 3)))) + { return false; } + if (!( (M.at<double>(3, 0) == 0.0) && + (M.at<double>(3, 1) == 0.0) && + (M.at<double>(3, 2) == 0.0) && + (M.at<double>(3, 3) == 1.0))) { return false; } + + return true; +} + +bool validate::cameraMatrix(const Mat &M) { + if (M.type() != CV_64F) { return false; } + if (M.channels() != 1) { return false; } + if (M.size() != Size(3, 3)) { return false; } + + if (!( (M.at<double>(2, 0) == 0.0) && + (M.at<double>(2, 1) == 0.0) && + (M.at<double>(2, 2) == 1.0))) { return false; } + + return true; +} + +bool ftl::calibration::validate::distortionCoefficients(const Mat &D, Size size) { + if (D.type() != CV_64FC1) { return false; } + if (!( + (D.total() == 4) || + (D.total() == 5) || + (D.total() == 8) || + (D.total() == 12))) { return false; } + + for (int i = 0; i < D.total(); i++) { + if (!std::isfinite(D.at<double>(i))) { return false; } + } + + double k[6] = {0.0}; + //double p[2] = {0.0}; + //double s[4] = {0.0}; + + switch(D.total()) { + case 12: + /* + s[0] = D.at<double>(8); + s[1] = D.at<double>(9); + s[2] = D.at<double>(10); + s[3] = D.at<double>(11); + */ + [[fallthrough]]; + + case 8: + k[3] = D.at<double>(5); + k[4] = D.at<double>(6); + k[5] = D.at<double>(7); + [[fallthrough]]; + + case 5: + k[2] = D.at<double>(4); + [[fallthrough]]; + + default: + k[0] = D.at<double>(0); + k[1] = D.at<double>(1); + /* + p[0] = D.at<double>(2); + p[1] = D.at<double>(3); + */ + } + + int diagonal = sqrt(size.width*size.width+size.height*size.height) + 1.0; + + bool is_n = true; + bool is_p = true; + + double dist_prev_n = 0; + double dist_prev_p = 0; + + for (int r = 0; r < diagonal; r++) { + double r2 = r*r; + double r4 = r2*r2; + double r6 = r4*r2; + + double rdist = 1.0 + k[0]*r2 + k[1]*r4 + k[2]*r6; + double irdist2 = 1./(1.0 + k[3]*r2 + k[4]*r4 + k[5]*r6); + double dist = r2*rdist*irdist2; // + s[0]*r2 + s[1]*r4; + + if (is_n) { + if (r2 == 0) {} + else if (!(dist < dist_prev_n)) { is_n = false; } + dist_prev_n = dist; + } + + if (is_p) { + if (r2 == 0) {} + else if (!(dist > dist_prev_p)) { is_p = false; } + dist_prev_p = dist; + } + + if (!is_n && !is_p) { return false; } + } + + return true; +} + +Mat ftl::calibration::scaleCameraMatrix(const Mat &K, const Size &size_new, const Size &size_old) { + Mat S(cv::Size(3, 3), CV_64F, 0.0); + double scale_x = ((double) size_new.width) / ((double) size_old.width); + double scale_y = ((double) size_new.height) / ((double) size_old.height); + + S.at<double>(0, 0) = scale_x; + S.at<double>(1, 1) = scale_y; + S.at<double>(2, 2) = 1.0; + return (S*K); +} \ No newline at end of file diff --git a/components/common/cpp/test/CMakeLists.txt b/components/common/cpp/test/CMakeLists.txt index 3ef38991a6f9599783bb036f0a570f8bf0348b26..c5d394ac48e429e46b9a41204a25aa4448250702 100644 --- a/components/common/cpp/test/CMakeLists.txt +++ b/components/common/cpp/test/CMakeLists.txt @@ -40,3 +40,12 @@ add_test(ConfigurableUnitTest configurable_unit) add_test(URIUnitTest uri_unit) add_test(MsgpackUnitTest msgpack_unit) # add_test(TimerUnitTest timer_unit) CI server can't achieve this + +### Calibration ################################################################ +add_executable(calibration_common_unit + $<TARGET_OBJECTS:CatchTest> + ./calibration_common_unit.cpp +) +target_include_directories(calibration_common_unit PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/../include") +target_link_libraries(calibration_common_unit ftlcommon Threads::Threads ${OS_LIBS} ${OpenCV_LIBS}) +add_test(CalibrationCommonTest calibration_common_unit) \ No newline at end of file diff --git a/components/common/cpp/test/calibration_common_unit.cpp b/components/common/cpp/test/calibration_common_unit.cpp new file mode 100644 index 0000000000000000000000000000000000000000..5610c169d3b78c1755fd1f9279e7e9bf94bc46c4 --- /dev/null +++ b/components/common/cpp/test/calibration_common_unit.cpp @@ -0,0 +1,40 @@ +#include "catch.hpp" +#include "ftl/calibration.hpp" + +using cv::Size; +using cv::Mat; + +TEST_CASE("Calibration values", "") { + SECTION("Valid distortion parameters (k1, k2, k3, k4)") { + Mat D(1, 5, CV_64FC1); + D.at<double>(0) = 0.0; + D.at<double>(1) = 0.0; + D.at<double>(2) = 0.0; + D.at<double>(3) = 0.0; + + REQUIRE(ftl::calibration::validate::distortionCoefficients(D, Size(1920, 1080))); + + D.at<double>(0) = 1.0; + D.at<double>(1) = 1.0; + REQUIRE(ftl::calibration::validate::distortionCoefficients(D, Size(1920, 1080))); + + D.at<double>(0) = 0.01512461889185869; + D.at<double>(1) = -0.1207895096066378; + D.at<double>(4) = 0.1582571415357494; + REQUIRE(ftl::calibration::validate::distortionCoefficients(D, Size(1920, 1080))); + } + + SECTION("Invalid distortion parameters (k1, k2, k3, k4)") { + Mat D(1, 4, CV_64FC1); + D.at<double>(0) = NAN; + D.at<double>(1) = 0.0; + D.at<double>(2) = 0.0; + D.at<double>(3) = 0.0; + + REQUIRE(!ftl::calibration::validate::distortionCoefficients(D, Size(1920, 1080))); + + D.at<double>(0) = 1.0; + D.at<double>(1) = -1.0; + REQUIRE(!ftl::calibration::validate::distortionCoefficients(D, Size(1920, 1080))); + } +} diff --git a/components/rgbd-sources/CMakeLists.txt b/components/rgbd-sources/CMakeLists.txt index c45597f8b6777c972b8754fc5207daef0018d0eb..9e5647e88ec11abed63497d2d6366e0bddbd40fa 100644 --- a/components/rgbd-sources/CMakeLists.txt +++ b/components/rgbd-sources/CMakeLists.txt @@ -5,15 +5,10 @@ set(RGBDSRC src/frame.cpp src/frameset.cpp src/sources/stereovideo/stereovideo.cpp - #src/sources/net/net.cpp - #src/streamer.cpp #src/colour.cpp src/group.cpp src/cb_segmentation.cpp #src/abr.cpp - #src/sources/virtual/virtual.cpp - #src/sources/ftlfile/file_source.cpp - #src/sources/ftlfile/player.cpp src/sources/screencapture/screencapture.cpp src/camera.cpp ) diff --git a/components/rgbd-sources/src/sources/ftlfile/file_source.cpp b/components/rgbd-sources/src/sources/ftlfile/file_source.cpp deleted file mode 100644 index f0ba1e010ef00e880a4ff4a532dfd310673c275c..0000000000000000000000000000000000000000 --- a/components/rgbd-sources/src/sources/ftlfile/file_source.cpp +++ /dev/null @@ -1,263 +0,0 @@ -#include "file_source.hpp" - -#include <ftl/codecs/hevc.hpp> -#include <ftl/timer.hpp> - -using ftl::rgbd::detail::FileSource; -using ftl::codecs::codec_t; -using ftl::codecs::Channel; -using cv::cuda::GpuMat; - -void FileSource::_createDecoder(int ix, const ftl::codecs::Packet &pkt) { - if (decoders_[ix]) { - if (!decoders_[ix]->accepts(pkt)) { - ftl::codecs::free(decoders_[ix]); - } else { - return; - } - } - - DLOG(INFO) << "Create a decoder: " << ix; - decoders_[ix] = ftl::codecs::allocateDecoder(pkt); -} - -FileSource::FileSource(ftl::rgbd::Source *s, ftl::rgbd::Player *r, int sid) : ftl::rgbd::detail::Source(s) { - reader_ = r; - has_calibration_ = false; - - for (int i=0; i<32; ++i) decoders_[i] = nullptr; - - cache_read_ = -1; - cache_write_ = 0; - realtime_ = host_->value("realtime", false); - timestamp_ = r->getStartTime(); - sourceid_ = sid; - freeze_ = host_->value("freeze", false); - have_frozen_ = false; - - host_->on("freeze", [this](const ftl::config::Event &e) { - have_frozen_ = false; - freeze_ = host_->value("freeze", false); - }); - - r->onPacket(sid, [this](const ftl::codecs::StreamPacket &spkt, ftl::codecs::Packet &pkt) { - //host_->notifyRaw(spkt, pkt); - - // Some channels are to be directly handled by the source object and - // do not proceed to any subsequent step. - // FIXME: Potential problem, these get processed at wrong time - if (spkt.channel == Channel::Configuration) { - std::tuple<std::string, std::string> cfg; - auto unpacked = msgpack::unpack((const char*)pkt.data.data(), pkt.data.size()); - unpacked.get().convert(cfg); - - LOG(INFO) << "Config Received: " << std::get<1>(cfg); - return; - } - else if (spkt.channel == Channel::Calibration) { - _processCalibration(pkt); - return; - } else if (spkt.channel == Channel::Pose) { - _processPose(pkt); - return; - } - - available_channels_ |= spkt.channel; - - // FIXME: For bad and old FTL files where wrong channel is used - if (pkt.codec == codec_t::POSE) { - _processPose(pkt); - return; - } else if (pkt.codec == codec_t::CALIBRATION) { - _processCalibration(pkt); - return; - } - - - // TODO: Check I-Frames for H264 - if (pkt.codec == codec_t::HEVC) { - if (ftl::codecs::hevc::isIFrame(pkt.data.data(), pkt.data.size())) _removeChannel(spkt.channel); - } - cache_[cache_write_].emplace_back(); - auto &c = cache_[cache_write_].back(); - - c.spkt = spkt; - c.pkt = std::move(pkt); - }); -} - -FileSource::~FileSource() { - -} - -void FileSource::_processPose(ftl::codecs::Packet &pkt) { - LOG(INFO) << "Got POSE channel"; - if (pkt.codec == codec_t::POSE) { - Eigen::Matrix4d p = Eigen::Map<Eigen::Matrix4d>((double*)pkt.data.data()); - host_->setPose(p); - } else if (pkt.codec == codec_t::MSGPACK) { - auto unpacked = msgpack::unpack((const char*)pkt.data.data(), pkt.data.size()); - std::vector<double> posevec; - unpacked.get().convert(posevec); - - Eigen::Matrix4d p(posevec.data()); - host_->setPose(p); - } -} - -void FileSource::_processCalibration(ftl::codecs::Packet &pkt) { - if (pkt.codec == codec_t::CALIBRATION) { - ftl::rgbd::Camera *camera = (ftl::rgbd::Camera*)pkt.data.data(); - params_ = *camera; - has_calibration_ = true; - } else if (pkt.codec == codec_t::MSGPACK) { - std::tuple<ftl::rgbd::Camera, ftl::codecs::Channel, ftl::rgbd::capability_t> params; - auto unpacked = msgpack::unpack((const char*)pkt.data.data(), pkt.data.size()); - unpacked.get().convert(params); - - if (std::get<1>(params) == Channel::Left) { - params_ = std::get<0>(params); - capabilities_ = std::get<2>(params); - has_calibration_ = true; - - LOG(INFO) << "Got Calibration channel: " << params_.width << "x" << params_.height; - } else { - //params_right_ = std::get<0>(params); - } - } -} - -void FileSource::_removeChannel(ftl::codecs::Channel channel) { - int c = 0; - for (auto i=cache_[cache_write_].begin(); i != cache_[cache_write_].end(); ++i) { - if ((*i).spkt.channel == channel) { - ++c; - i = cache_[cache_write_].erase(i); - } - } - DLOG(INFO) << "Skipped " << c << " packets"; -} - -bool FileSource::capture(int64_t ts) { - if (realtime_) { - timestamp_ = ts; - } else { - timestamp_ += ftl::timer::getInterval(); - } - return true; -} - -bool FileSource::retrieve() { - if (!have_frozen_ && !reader_->read(timestamp_)) { - cache_write_ = -1; - } - return true; -} - -void FileSource::swap() { - if (have_frozen_) return; - cache_read_ = cache_write_; - cache_write_ = (cache_write_ == 0) ? 1 : 0; -} - -bool FileSource::compute(int n, int b) { - // Freeze frame requires a copy to be made each time... - if (have_frozen_) { - cv::cuda::GpuMat t1, t2; - // FIXME: Implement this? - //if (!rgb_.empty()) rgb_.copyTo(t1); - //if (!depth_.empty()) depth_.copyTo(t2); - //host_->notify(timestamp_, t1, t2); - return true; - } - - if (cache_read_ < 0) return false; - if (cache_[cache_read_].size() == 0) return false; - - int64_t lastts = 0; - int lastc = 0; - - frame_.reset(); - frame_.setOrigin(&state_); - - // Decide which channels to decode - decode_channels_ = Channel::Colour; - - if (available_channels_.has(host_->getChannel())) { - decode_channels_ |= host_->getChannel(); - } else if (host_->getChannel() == Channel::Depth && available_channels_.has(Channel::Right)) { - decode_channels_ |= Channel::Right; - } - - // Go through previously read and cached frames in sequence - // needs to be done due to P-Frames - for (auto i=cache_[cache_read_].begin(); i!=cache_[cache_read_].end(); ++i) { - auto &c = *i; - - // Check for verifying that both channels are received, ie. two frames - // with the same timestamp. - if (c.spkt.timestamp > lastts) { - lastts = c.spkt.timestamp; - lastc = 1; - } else if (c.spkt.timestamp == lastts) { - lastc++; - } - - // Has this channel been requested? - if (decode_channels_.has(c.spkt.channel)) { //c.spkt.channel == Channel::Colour || c.spkt.channel == host_->getChannel()) { - - // Create channel only if not existing - if (!frame_.hasChannel(c.spkt.channel)) { - frame_.create<GpuMat>(c.spkt.channel); - } - - int channum = int(c.spkt.channel); - if (!ftl::codecs::isFloatChannel(c.spkt.channel)) { - frame_.get<GpuMat>(c.spkt.channel).create(cv::Size(ftl::codecs::getWidth(c.pkt.definition),ftl::codecs::getHeight(c.pkt.definition)), CV_8UC4); - _createDecoder(channum, c.pkt); - - try { - decoders_[channum]->decode(c.pkt, frame_.get<GpuMat>(c.spkt.channel)); - } catch (std::exception &e) { - LOG(INFO) << "Decoder exception: " << e.what(); - } - } else { - frame_.get<GpuMat>(c.spkt.channel).create(cv::Size(ftl::codecs::getWidth(c.pkt.definition),ftl::codecs::getHeight(c.pkt.definition)), CV_32F); - _createDecoder(channum, c.pkt); - try { - decoders_[channum]->decode(c.pkt, frame_.get<GpuMat>(c.spkt.channel)); - } catch (std::exception &e) { - LOG(INFO) << "Decoder exception: " << e.what(); - } - } - - frame_.pushPacket(c.spkt.channel, c.pkt); - } - - //host_->notifyRaw(c.spkt, c.pkt); - } - - // FIXME: Consider case of Channel::None - if (lastc < 2) { - LOG(ERROR) << "Channels not in sync (" << sourceid_ << "): " << lastts; - return false; - } - - //LOG(INFO) << "MERGE " << cache_[cache_read_].size(); - - cache_[cache_read_].clear(); - - //if (rgb_.empty() || depth_.empty()) return false; - - // Inform about a decoded frame pair - if (freeze_ && !have_frozen_) { - have_frozen_ = true; - } else { - host_->notify(timestamp_, frame_); - } - return true; -} - -bool FileSource::isReady() { - return true; -} diff --git a/components/rgbd-sources/src/sources/ftlfile/file_source.hpp b/components/rgbd-sources/src/sources/ftlfile/file_source.hpp deleted file mode 100644 index 9aa11b929f1d87b486064ec4337de3b48f0d1d70..0000000000000000000000000000000000000000 --- a/components/rgbd-sources/src/sources/ftlfile/file_source.hpp +++ /dev/null @@ -1,62 +0,0 @@ -#pragma once -#ifndef _FTL_RGBD_FILE_SOURCE_HPP_ -#define _FTL_RGBD_FILE_SOURCE_HPP_ - -#include <loguru.hpp> - -#include <ftl/rgbd/source.hpp> -#include "player.hpp" -#include <ftl/codecs/decoder.hpp> - -#include <list> - -namespace ftl { -namespace rgbd { -namespace detail { - -class FileSource : public detail::Source { - public: - FileSource(ftl::rgbd::Source *, ftl::rgbd::Player *, int sid); - ~FileSource(); - - bool capture(int64_t ts); - bool retrieve(); - bool compute(int n, int b); - bool isReady(); - void swap(); - - //void reset(); - private: - ftl::rgbd::Player *reader_; - bool has_calibration_; - - struct PacketPair { - ftl::codecs::StreamPacket spkt; - ftl::codecs::Packet pkt; - }; - - std::list<PacketPair> cache_[2]; - int cache_read_; - int cache_write_; - int sourceid_; - - ftl::codecs::Decoder *decoders_[32]; // 32 is max video channels - - bool realtime_; - bool freeze_; - bool have_frozen_; - - ftl::codecs::Channels<0> decode_channels_; - ftl::codecs::Channels<0> available_channels_; - - void _processCalibration(ftl::codecs::Packet &pkt); - void _processPose(ftl::codecs::Packet &pkt); - void _removeChannel(ftl::codecs::Channel channel); - void _createDecoder(int ix, const ftl::codecs::Packet &pkt); -}; - -} -} -} - -#endif // _FTL_RGBD_FILE_SOURCE_HPP_ diff --git a/components/rgbd-sources/src/sources/ftlfile/player.cpp b/components/rgbd-sources/src/sources/ftlfile/player.cpp deleted file mode 100644 index 9558c316c438bf8e4f4fe67e216adef33c95f96b..0000000000000000000000000000000000000000 --- a/components/rgbd-sources/src/sources/ftlfile/player.cpp +++ /dev/null @@ -1,84 +0,0 @@ -#include "player.hpp" -#include <ftl/configuration.hpp> - -using ftl::rgbd::Player; - -Player::Player(std::istream &s) : stream_(&s), reader_(s) { - auto *c = ftl::config::find("/controls"); - - offset_ = 0; - - if (c) { - paused_ = c->value("paused", false); - c->on("paused", [this,c](const ftl::config::Event &e) { - UNIQUE_LOCK(mtx_, lk); - paused_ = c->value("paused", false); - if (paused_) { - pause_time_ = last_ts_; - } else { - offset_ += last_ts_ - pause_time_; - } - }); - - looping_ = c->value("looping", true); - c->on("looping", [this,c](const ftl::config::Event &e) { - looping_ = c->value("looping", false); - }); - - speed_ = c->value("speed", 1.0f); - c->on("speed", [this,c](const ftl::config::Event &e) { - speed_ = c->value("speed", 1.0f); - }); - - reversed_ = c->value("reverse", false); - c->on("reverse", [this,c](const ftl::config::Event &e) { - reversed_ = c->value("reverse", false); - }); - } else { - looping_ = true; - paused_ = false; - speed_ = 1.0f; - reversed_ = false; - } -} - -Player::~Player() { - // TODO: Remove callbacks -} - -bool Player::read(int64_t ts) { - std::unique_lock<std::mutex> lk(mtx_, std::defer_lock); - if (!lk.try_lock()) return true; - - last_ts_ = ts; - if (paused_) return true; - - int64_t adjusted_ts = int64_t(float(ts - reader_.getStartTime()) * speed_) + reader_.getStartTime() + offset_; - bool res = reader_.read(adjusted_ts); - - if (looping_ && !res) { - reader_.end(); - offset_ = 0; - stream_->clear(); - stream_->seekg(0); - if (!reader_.begin()) { - LOG(ERROR) << "Could not loop"; - return false; - } - return true; - } - - return res; -} - -void Player::onPacket(int streamID, const std::function<void(const ftl::codecs::StreamPacket &, ftl::codecs::Packet &)> &f) { - reader_.onPacket(streamID, f); -} - -bool Player::begin() { - return reader_.begin(); -} - -bool Player::end() { - return reader_.end(); -} diff --git a/components/rgbd-sources/src/sources/ftlfile/player.hpp b/components/rgbd-sources/src/sources/ftlfile/player.hpp deleted file mode 100644 index f826caabaf6b461cc77b719427381e3b1c5828c4..0000000000000000000000000000000000000000 --- a/components/rgbd-sources/src/sources/ftlfile/player.hpp +++ /dev/null @@ -1,47 +0,0 @@ -#ifndef _FTL_RGBD_PLAYER_HPP_ -#define _FTL_RGBD_PLAYER_HPP_ - -#include <iostream> -#include <ftl/codecs/reader.hpp> -#include <ftl/threads.hpp> - -namespace ftl { -namespace rgbd { - -/** - * Simple wrapper around stream reader to control file playback. - */ -class Player { - public: - explicit Player(std::istream &s); - ~Player(); - - bool read(int64_t ts); - - void onPacket(int streamID, const std::function<void(const ftl::codecs::StreamPacket &, ftl::codecs::Packet &)> &); - - bool begin(); - bool end(); - - inline int64_t getStartTime() { return reader_.getStartTime(); } - - private: - std::istream *stream_; - ftl::codecs::Reader reader_; - - bool paused_; - bool reversed_; - bool looping_; - float speed_; - - int64_t pause_time_; - int64_t offset_; - int64_t last_ts_; - - MUTEX mtx_; -}; - -} -} - -#endif // _FTL_RGBD_PLAYER_HPP_ diff --git a/components/rgbd-sources/src/sources/net/net.cpp b/components/rgbd-sources/src/sources/net/net.cpp deleted file mode 100644 index 3d262aa958d983d188ad7071f03613d2d7343d1a..0000000000000000000000000000000000000000 --- a/components/rgbd-sources/src/sources/net/net.cpp +++ /dev/null @@ -1,505 +0,0 @@ -#include "net.hpp" -#include <vector> -#include <thread> -#include <chrono> -#include <tuple> -#include <bitset> - -#include "colour.hpp" - -#include <ftl/rgbd/streamer.hpp> -#include <ftl/codecs/codecs.hpp> - -using ftl::rgbd::detail::NetFrame; -using ftl::rgbd::detail::NetFrameQueue; -using ftl::rgbd::detail::NetSource; -using ftl::net::Universe; -using ftl::UUID; -using std::string; -using ftl::rgbd::Camera; -using std::vector; -using std::this_thread::sleep_for; -using std::chrono::milliseconds; -using std::tuple; -using ftl::codecs::Channel; -using cv::cuda::GpuMat; -using ftl::codecs::codec_t; - -// ===== NetFrameQueue ========================================================= - -NetFrameQueue::NetFrameQueue(int size) : frames_(size) { - for (auto &f : frames_) f.timestamp = -1; -} - -NetFrameQueue::~NetFrameQueue() { - -} - -NetFrame &NetFrameQueue::getFrame(int64_t ts, const cv::Size &s, int c1type, int c2type) { - UNIQUE_LOCK(mtx_, lk); - - // Find matching timestamp - for (auto &f : frames_) { - if (f.timestamp == ts) return f; - } - - int64_t oldest = ts; - - // No match so find an empty slot - for (auto &f : frames_) { - if (f.timestamp == -1) { - f.timestamp = ts; - f.chunk_count[0] = 0; - f.chunk_count[1] = 0; - f.chunk_total[0] = 0; - f.chunk_total[1] = 0; - f.channel_count = 0; - f.tx_size = 0; - //f.channel[0].create(s, c1type); - //f.channel[1].create(s, c2type); - return f; - } - oldest = (f.timestamp < oldest) ? f.timestamp : oldest; - } - - // No empty slot, so give a fatal error - for (auto &f : frames_) { - LOG(ERROR) << "Stale frame: " << f.timestamp << " - " << f.chunk_count; - - // Force release of frame! - if (f.timestamp == oldest) { - f.timestamp = ts; - f.chunk_count[0] = 0; - f.chunk_count[1] = 0; - f.chunk_total[0] = 0; - f.chunk_total[1] = 0; - f.channel_count = 0; - f.tx_size = 0; - //f.channel[0].create(s, c1type); - //f.channel[1].create(s, c2type); - return f; - } - } - LOG(FATAL) << "Net Frame Queue not large enough: " << ts; - // FIXME: (Nick) Could auto resize the queue. - return frames_[0]; // To avoid missing return error... -} - -void NetFrameQueue::freeFrame(NetFrame &f) { - UNIQUE_LOCK(mtx_, lk); - f.timestamp = -1; -} - - -// ===== NetSource ============================================================= - -int64_t NetSource::last_msg_ = 0; -float NetSource::req_bitrate_ = 0.0f; -float NetSource::sample_count_ = 0.0f; -MUTEX NetSource::msg_mtx_; - -NetSource::NetSource(ftl::rgbd::Source *host) - : ftl::rgbd::detail::Source(host), active_(false), minB_(9), maxN_(1), adaptive_(0), queue_(3) { - - gamma_ = host->value("gamma", 1.0f); - temperature_ = host->value("temperature", 6500); - default_quality_ = host->value("quality", 0); - last_bitrate_ = 0; - params_right_.width = 0; - has_calibration_ = false; - - decoder_[0] = nullptr; - decoder_[1] = nullptr; - - host->on("gamma", [this,host](const ftl::config::Event&) { - gamma_ = host->value("gamma", 1.0f); - }); - - host->on("temperature", [this,host](const ftl::config::Event&) { - temperature_ = host->value("temperature", 6500); - }); - - host->on("focal", [this,host](const ftl::config::Event&) { - params_.fx = host_->value("focal", 400.0); - params_.fy = params_.fx; - host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/focal", host_->getConfig()["focal"].dump()); - }); - - host->on("centre_x", [this,host](const ftl::config::Event&) { - params_.cx = host_->value("centre_x", 0.0); - host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/centre_x", host_->getConfig()["centre_x"].dump()); - }); - - host->on("centre_y", [this,host](const ftl::config::Event&) { - params_.cy = host_->value("centre_y", 0.0); - host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/centre_y", host_->getConfig()["centre_y"].dump()); - }); - - host->on("doffs", [this,host](const ftl::config::Event&) { - params_.doffs = host_->value("doffs", params_.doffs); - host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/doffs", host_->getConfig()["doffs"].dump()); - }); - - host->on("baseline", [this,host](const ftl::config::Event&) { - params_.baseline = host_->value("baseline", 400.0); - host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/baseline", host_->getConfig()["baseline"].dump()); - }); - - // Right parameters - - host->on("focal_right", [this,host](const ftl::config::Event&) { - params_right_.fx = host_->value("focal_right", 0.0); - params_right_.fy = params_right_.fx; - host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/focal_right", host_->getConfig()["focal_right"].dump()); - }); - - host->on("centre_x_right", [this,host](const ftl::config::Event&) { - params_right_.cx = host_->value("centre_x_right", 0.0); - host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/centre_x_right", host_->getConfig()["centre_x_right"].dump()); - }); - - host->on("centre_y_right", [this,host](const ftl::config::Event&) { - params_right_.cy = host_->value("centre_y_right", 0.0); - host_->getNet()->send(peer_, "update_cfg", host_->getURI() + "/centre_y_right", host_->getConfig()["centre_y_right"].dump()); - }); - - - host->on("quality", [this,host](const ftl::config::Event&) { - default_quality_ = host->value("quality", 0); - }); - - //abr_.setMaximumBitrate(host->value("max_bitrate", -1)); - //abr_.setMinimumBitrate(host->value("min_bitrate", -1)); - - _updateURI(); - - h_ = host_->getNet()->onConnect([this](ftl::net::Peer *p) { - if (active_) return; - LOG(INFO) << "NetSource restart..."; - _updateURI(); - }); -} - -NetSource::~NetSource() { - if (decoder_[0]) ftl::codecs::free(decoder_[0]); - if (decoder_[1]) ftl::codecs::free(decoder_[1]); - - if (uri_.size() > 0) { - host_->getNet()->unbind(uri_); - } - - host_->getNet()->removeCallback(h_); -} - -/*void NetSource::_checkAdaptive(int64_t ts) { - const int64_t current = ftl::timer::get_time(); - int64_t net_latency = current - ts; - - // Only change bit rate gradually - if (current - last_br_change_ > ftl::rgbd::detail::kAdaptationRate) { - // Was this frame late? - if (adaptive_ < ftl::rgbd::detail::kMaxBitrateLevels && net_latency > ftl::rgbd::detail::kLatencyThreshold) { - slow_log_ = (slow_log_ << 1) + 1; - std::bitset<32> bs(slow_log_); - - // Enough late frames to reduce bit rate - if (bs.count() > ftl::rgbd::detail::kSlowFramesThreshold) { - adaptive_++; - slow_log_ = 0; - last_br_change_ = current; - LOG(WARNING) << "Adjust bitrate to " << adaptive_; - } - // No late frames in recent history... - } else if (adaptive_ > 0 && slow_log_ == 0) { - // TODO: (Nick) Don't change bitrate up so quickly as down? - // Try a higher bitrate again? - adaptive_--; - } - } -}*/ - -void NetSource::_createDecoder(int chan, const ftl::codecs::Packet &pkt) { - UNIQUE_LOCK(mutex_,lk); - auto *decoder = decoder_[chan]; - if (decoder) { - if (!decoder->accepts(pkt)) { - ftl::codecs::free(decoder_[chan]); - } else { - return; - } - } - - decoder_[chan] = ftl::codecs::allocateDecoder(pkt); -} - -void NetSource::_processConfig(const ftl::codecs::Packet &pkt) { - std::tuple<std::string, std::string> cfg; - auto unpacked = msgpack::unpack((const char*)pkt.data.data(), pkt.data.size()); - unpacked.get().convert(cfg); - - //LOG(INFO) << "Config Received: " << std::get<1>(cfg); - // TODO: This needs to be put in safer / better location - host_->set(std::get<0>(cfg), nlohmann::json::parse(std::get<1>(cfg))); -} - -void NetSource::_processCalibration(const ftl::codecs::Packet &pkt) { - std::tuple<ftl::rgbd::Camera, ftl::codecs::Channel, ftl::rgbd::capability_t> params; - auto unpacked = msgpack::unpack((const char*)pkt.data.data(), pkt.data.size()); - unpacked.get().convert(params); - - if (std::get<1>(params) == Channel::Left) { - params_ = std::get<0>(params); - capabilities_ = std::get<2>(params); - has_calibration_ = true; - LOG(INFO) << "Got Calibration channel: " << params_.width << "x" << params_.height; - } else { - params_right_ = std::get<0>(params); - } -} - -void NetSource::_processPose(const ftl::codecs::Packet &pkt) { - if (pkt.codec == ftl::codecs::codec_t::POSE) { - Eigen::Matrix4d p = Eigen::Map<Eigen::Matrix4d>((double*)pkt.data.data()); - //host_->setPose(p); - } else if (pkt.codec == ftl::codecs::codec_t::MSGPACK) { - auto unpacked = msgpack::unpack((const char*)pkt.data.data(), pkt.data.size()); - std::vector<double> posevec; - unpacked.get().convert(posevec); - - Eigen::Matrix4d p(posevec.data()); - //host_->setPose(p); - // TODO: What to do with pose? - } -} - -void NetSource::_checkDataRate(size_t tx_size, int64_t tx_latency, int64_t ts) { - float actual_mbps = (float(tx_size) * 8.0f * (1000.0f / float(tx_latency))) / 1048576.0f; - float min_mbps = (float(tx_size) * 8.0f * (1000.0f / float(ftl::timer::getInterval()))) / 1048576.0f; - if (actual_mbps > 0.0f && actual_mbps < min_mbps) LOG(WARNING) << "Bitrate = " << actual_mbps << "Mbps, min required = " << min_mbps << "Mbps"; - - UNIQUE_LOCK(msg_mtx_,lk); - req_bitrate_ += float(tx_size) * 8.0f; - sample_count_ += 1.0f; - - if (ts - last_msg_ >= 1000) { - LOG(INFO) << "Required Bitrate = " << (req_bitrate_ / float(ts - last_msg_) * 1000.0f / 1048576.0f) << "Mbps"; - last_msg_ = ts; - req_bitrate_ = 0.0f; - sample_count_ = 0.0f; - } -} - -void NetSource::_recvPacket(short ttimeoff, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt) { - // Capture time here for better net latency estimate - int64_t now = std::chrono::time_point_cast<std::chrono::milliseconds>(std::chrono::high_resolution_clock::now()).time_since_epoch().count(); - if (!active_) return; - - // Allow acccess to the raw data elsewhere... - host_->notifyRaw(spkt, pkt); - - const ftl::codecs::Channel chan = host_->getChannel(); - const ftl::codecs::Channel rchan = spkt.channel; - const int channum = (rchan == Channel::Colour) ? 0 : 1; - - // Deal with the special channels... - switch (rchan) { - case Channel::Configuration : _processConfig(pkt); return; - case Channel::Calibration : _processCalibration(pkt); return; - case Channel::Pose : _processPose(pkt); return; - } - - if (!has_calibration_) { - LOG(WARNING) << "Missing calibration, skipping frame"; - return; - } - - //LOG(INFO) << "PACKET: " << spkt.timestamp << ", " << (int)spkt.channel << ", " << (int)pkt.codec; - - const cv::Size size = cv::Size(ftl::codecs::getWidth(pkt.definition), ftl::codecs::getHeight(pkt.definition)); - NetFrame &frame = queue_.getFrame(spkt.timestamp, size, CV_8UC4, (isFloatChannel(chan) ? CV_32FC1 : CV_8UC4)); - - if (timestamp_ > 0 && frame.timestamp <= timestamp_) { - LOG(ERROR) << "Duplicate frame - " << frame.timestamp << " received=" << int(rchan) << " uri=" << uri_; - return; - } - - // Calculate how many packets to expect for this channel - if (frame.chunk_total[channum] == 0) { - frame.chunk_total[channum] = pkt.block_total; - } - - // Capture tx time of first received chunk - if (frame.chunk_count[0] == 0 && frame.chunk_count[1] == 0) { - UNIQUE_LOCK(frame.mtx, flk); - if (frame.chunk_count[0] == 0 && frame.chunk_count[1] == 0) { - frame.tx_latency = int64_t(ttimeoff); - } - } - - ++frame.chunk_count[channum]; - if (frame.chunk_count[channum] > frame.chunk_total[channum]) { - LOG(WARNING) << "Too many channel packets received, discarding"; - return; - } - - // Update frame statistics - frame.tx_size += pkt.data.size(); - - frame.channel[channum].create(size, (isFloatChannel(rchan) ? CV_32FC1 : CV_8UC4)); - - // Only decode if this channel is wanted. - if (rchan == Channel::Colour || rchan == chan) { - _createDecoder(channum, pkt); - auto *decoder = decoder_[channum]; - if (!decoder) { - LOG(ERROR) << "No frame decoder available"; - return; - } - - decoder->decode(pkt, frame.channel[channum]); - } else if (chan != Channel::None && rchan != Channel::Colour) { - // Didn't receive correct second channel so just clear the images - if (isFloatChannel(chan)) { - frame.channel[1].setTo(cv::Scalar(0.0f)); - } else { - frame.channel[1].setTo(cv::Scalar(0,0,0)); - } - } - - // Apply colour correction to chunk - //ftl::rgbd::colourCorrection(tmp_rgb, gamma_, temperature_); - - // TODO:(Nick) Decode directly into double buffer if no scaling - - _checkDataRate(pkt.data.size(), now-(spkt.timestamp+ttimeoff), spkt.timestamp); - - if (frame.chunk_count[channum] == frame.chunk_total[channum]) ++frame.channel_count; - - // Last chunk of both channels now received, so we are done. - if (frame.channel_count == spkt.channel_count) { - _completeFrame(frame, now-(spkt.timestamp+frame.tx_latency)); - } -} - -void NetSource::_completeFrame(NetFrame &frame, int64_t latency) { - UNIQUE_LOCK(frame.mtx, flk); - - // Frame must not have already been freed. - if (frame.timestamp >= 0) { - timestamp_ = frame.timestamp; - frame.tx_latency = latency; - - // Note: Not used currently - //adaptive_ = abr_.selectBitrate(frame); - - frame_.reset(); - frame_.setOrigin(&state_); - cv::cuda::swap(frame_.create<GpuMat>(Channel::Colour), frame.channel[0]); - - if (host_->getChannel() != Channel::None) - cv::cuda::swap(frame_.create<GpuMat>(host_->getChannel()), frame.channel[1]); - - host_->notify(frame.timestamp, frame_); - - queue_.freeFrame(frame); - N_--; - } -} - -void NetSource::setPose(const Eigen::Matrix4d &pose) { - ftl::rgbd::detail::Source::setPose(pose); - if (!active_) return; - - vector<unsigned char> vec((unsigned char*)pose.data(), (unsigned char*)(pose.data()+(pose.size()))); - try { - if (!host_->getNet()->send(peer_, "set_pose", *host_->get<string>("uri"), vec)) { - active_ = false; - } - } catch (...) { - LOG(ERROR) << "Exception when setting pose"; - } - //Source::setPose(pose); -} - -ftl::rgbd::Camera NetSource::parameters(ftl::codecs::Channel chan) { - if (chan == ftl::codecs::Channel::Right) { - return params_right_; - } else { - return params_; - } -} - -void NetSource::_updateURI() { - UNIQUE_LOCK(mutex_,lk); - active_ = false; - prev_chan_ = ftl::codecs::Channel::None; - auto uri = host_->get<string>("uri"); - - if (uri_.size() > 0) { - host_->getNet()->unbind(uri_); - } - - if (uri) { - auto p = host_->getNet()->findOne<ftl::UUID>("find_stream", *uri); - if (!p) { - LOG(ERROR) << "Could not find stream: " << *uri; - return; - } - peer_ = *p; - - host_->getNet()->bind(*uri, [this](short ttimeoff, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt) { - _recvPacket(ttimeoff, spkt, pkt); - }); - - N_ = 0; - uri_ = *uri; - active_ = true; - } else { - uri_ = ""; - LOG(WARNING) << "NetSource URI is missing"; - } -} - -bool NetSource::compute(int n, int b) { - // Choose highest requested number of frames - maxN_ = std::max(maxN_,(n == -1) ? ftl::rgbd::detail::kDefaultFrameCount : n); - - // Choose best requested quality - minB_ = std::min(minB_,(b == -1) ? int(adaptive_) : b); - - // Send k frames before end to prevent unwanted pause - // Unless only a single frame is requested - if ((N_ <= maxN_/2 && maxN_ > 1) || N_ == 0) { - const ftl::codecs::Channel chan = host_->getChannel(); - - N_ = maxN_; - - // Verify depth destination is of required type - /*if (isFloatChannel(chan)) { - depth_.create(cv::Size(params_.width, params_.height), CV_32FC1); // 0.0f - } else if (!isFloatChannel(chan)) { - depth_.create(cv::Size(params_.width, params_.height), CV_8UC3); // FIXME: Use 8UC4 - }*/ - - if (prev_chan_ != chan) { - host_->getNet()->send(peer_, "set_channel", *host_->get<string>("uri"), chan); - prev_chan_ = chan; - } - - if (!host_->getNet()->send(peer_, "get_stream", - *host_->get<string>("uri"), maxN_, minB_, - host_->getNet()->id(), *host_->get<string>("uri"))) { - active_ = false; - } - - //abr_.notifyChanged(); - - maxN_ = 1; // Reset to single frame - minB_ = 9; // Reset to worst quality - } - return true; -} - -bool NetSource::isReady() { - return has_calibration_; -} diff --git a/components/rgbd-sources/src/sources/net/net.hpp b/components/rgbd-sources/src/sources/net/net.hpp deleted file mode 100644 index fca089290669e27f26584d88ef38d349ccfffa2e..0000000000000000000000000000000000000000 --- a/components/rgbd-sources/src/sources/net/net.hpp +++ /dev/null @@ -1,104 +0,0 @@ -#pragma once -#ifndef _FTL_RGBD_NET_HPP_ -#define _FTL_RGBD_NET_HPP_ - -#include <ftl/config.h> - -#include <ftl/net/universe.hpp> -#include <ftl/rgbd/source.hpp> -#include <ftl/rgbd/detail/abr.hpp> -#include <ftl/threads.hpp> -#include <ftl/rgbd/detail/netframe.hpp> -#include <ftl/codecs/decoder.hpp> -#include <string> - -#ifdef HAVE_NVPIPE -#include <NvPipe.h> -#endif - -namespace ftl { -namespace rgbd { -namespace detail { - -static const int kDefaultFrameCount = 30; -static const int kLatencyThreshold = 5; // Milliseconds delay considered as late -static const int kSlowFramesThreshold = 5; // Number of late frames before change -static const int kAdaptationRate = 5000; // Milliseconds between bitrate changes - -/** - * A two channel network streamed source for RGB-Depth. - */ -class NetSource : public detail::Source { - public: - explicit NetSource(ftl::rgbd::Source *); - ~NetSource(); - - bool capture(int64_t ts) { return true; } - bool retrieve() { return true; } - bool compute(int n, int b); - bool isReady(); - - void setPose(const Eigen::Matrix4d &pose); - Camera parameters(ftl::codecs::Channel chan); - - void reset(); - - private: - bool has_calibration_; - ftl::UUID peer_; - std::atomic<int> N_; - bool active_; - std::string uri_; - ftl::net::callback_t h_; - SHARED_MUTEX mutex_; - cv::Mat idepth_; - float gamma_; - int temperature_; - int minB_; - int maxN_; - int default_quality_; - ftl::codecs::Channel prev_chan_; - ftl::rgbd::Camera params_right_; - - //ftl::rgbd::detail::ABRController abr_; - int last_bitrate_; - - static int64_t last_msg_; - static float req_bitrate_; - static float sample_count_; - static MUTEX msg_mtx_; - - //#ifdef HAVE_NVPIPE - //NvPipe *nv_channel1_decoder_; - //NvPipe *nv_channel2_decoder_; - //#endif - - ftl::codecs::Decoder *decoder_[2]; - - // Adaptive bitrate functionality - ftl::rgbd::detail::bitrate_t adaptive_; // Current adapted bitrate - //unsigned int slow_log_; // Bit count of delayed frames - //int64_t last_br_change_; // Time of last adaptive change - - NetFrameQueue queue_; - - bool _getCalibration(ftl::net::Universe &net, const ftl::UUID &peer, const std::string &src, ftl::rgbd::Camera &p, ftl::codecs::Channel chan); - void _recv(const std::vector<unsigned char> &jpg, const std::vector<unsigned char> &d); - void _recvPacket(short ttimeoff, const ftl::codecs::StreamPacket &, const ftl::codecs::Packet &); - //void _recvChunk(int64_t frame, short ttimeoff, uint8_t bitrate, int chunk, const std::vector<unsigned char> &jpg, const std::vector<unsigned char> &d); - //void _recvVideo(int64_t ts, short ttimeoff, uint8_t bitrate, const std::vector<unsigned char> &chan1, const std::vector<unsigned char> &chan2); - void _updateURI(); - //void _checkAdaptive(int64_t); - void _createDecoder(int chan, const ftl::codecs::Packet &); - void _completeFrame(NetFrame &frame, int64_t now); - void _processCalibration(const ftl::codecs::Packet &pkt); - void _processConfig(const ftl::codecs::Packet &pkt); - void _processPose(const ftl::codecs::Packet &pkt); - void _checkDataRate(size_t tx_size, int64_t tx_latency, int64_t ts); -}; - -} -} -} - -#endif // _FTL_RGBD_NET_HPP_ diff --git a/components/rgbd-sources/src/sources/stereovideo/calibrate.cpp b/components/rgbd-sources/src/sources/stereovideo/calibrate.cpp index 5b7875097fd4f7f25757c7c4d17f76d6e8748a5d..f67262c9e71c743bcd6d6cc9e740f60f29219a49 100644 --- a/components/rgbd-sources/src/sources/stereovideo/calibrate.cpp +++ b/components/rgbd-sources/src/sources/stereovideo/calibrate.cpp @@ -6,10 +6,12 @@ #include <ftl/config.h> #include <ftl/configuration.hpp> #include <ftl/threads.hpp> +#include <ftl/calibration.hpp> #include "calibrate.hpp" #include "ftl/exception.hpp" + #include <opencv2/core.hpp> #include <opencv2/core/utility.hpp> #include <opencv2/imgproc.hpp> @@ -39,69 +41,6 @@ using cv::Scalar; using std::string; using std::vector; -//////////////////////////////////////////////////////////////////////////////// - -static bool isValidTranslationForRectification(const Mat &t) { - if (t.type() != CV_64F) { return false; } - if (t.channels() != 1) { return false; } - if (t.size() != Size(1, 3)) { return false; } - if (cv::norm(t, cv::NORM_L2) == 0) { return false; } - return true; -} - -static bool isValidRotationMatrix(const Mat &M) { - if (M.type() != CV_64F) { return false; } - if (M.channels() != 1) { return false; } - if (M.size() != Size(3, 3)) { return false; } - - double det = cv::determinant(M); - if (abs(abs(det)-1.0) > 0.00001) { return false; } - - // TODO: floating point errors (result not exactly identity matrix) - // rotation matrix is orthogonal: M.T * M == M * M.T == I - //if (cv::countNonZero((M.t() * M) != Mat::eye(Size(3, 3), CV_64FC1)) != 0) - // { return false; } - - return true; -} - -static bool isValidPose(const Mat &M) { - if (M.size() != Size(4, 4)) { return false; } - if (!isValidRotationMatrix(M(cv::Rect(0 , 0, 3, 3)))) - { return false; } - if (!( (M.at<double>(3, 0) == 0.0) && - (M.at<double>(3, 1) == 0.0) && - (M.at<double>(3, 2) == 0.0) && - (M.at<double>(3, 3) == 1.0))) { return false; } - - return true; -} - -static bool isValidCamera(const Mat &M) { - if (M.type() != CV_64F) { return false; } - if (M.channels() != 1) { return false; } - if (M.size() != Size(3, 3)) { return false; } - - if (!( (M.at<double>(2, 0) == 0.0) && - (M.at<double>(2, 1) == 0.0) && - (M.at<double>(2, 2) == 1.0))) { return false; } - - return true; -} - -static Mat scaleCameraIntrinsics(const Mat &K, const Size &size_new, const Size &size_old) { - Mat S(cv::Size(3, 3), CV_64F, 0.0); - double scale_x = ((double) size_new.width) / ((double) size_old.width); - double scale_y = ((double) size_new.height) / ((double) size_old.height); - - S.at<double>(0, 0) = scale_x; - S.at<double>(1, 1) = scale_y; - S.at<double>(2, 2) = 1.0; - return (S*K); -} - -//////////////////////////////////////////////////////////////////////////////// - Calibrate::Calibrate(nlohmann::json &config, Size image_size, cv::cuda::Stream &stream) : ftl::Configurable(config) { @@ -125,7 +64,7 @@ Calibrate::Calibrate(nlohmann::json &config, Size image_size, cv::cuda::Stream & Mat Calibrate::_getK(size_t idx, Size size) { CHECK(idx < K_.size()); CHECK(!size.empty()); - return scaleCameraIntrinsics(K_[idx], size, calib_size_); + return ftl::calibration::scaleCameraMatrix(K_[idx], size, calib_size_); } Mat Calibrate::_getK(size_t idx) { @@ -139,17 +78,17 @@ double Calibrate::getBaseline() const { Mat Calibrate::getCameraMatrixLeft(const cv::Size res) { if (rectify_) { - return scaleCameraIntrinsics(Mat(P1_, cv::Rect(0, 0, 3, 3)), res, img_size_); + return ftl::calibration::scaleCameraMatrix(Mat(P1_, cv::Rect(0, 0, 3, 3)), res, img_size_); } else { - return scaleCameraIntrinsics(K_[0], res, calib_size_); + return ftl::calibration::scaleCameraMatrix(K_[0], res, calib_size_); } } Mat Calibrate::getCameraMatrixRight(const cv::Size res) { if (rectify_) { - return scaleCameraIntrinsics(Mat(P2_, cv::Rect(0, 0, 3, 3)), res, img_size_); + return ftl::calibration::scaleCameraMatrix(Mat(P2_, cv::Rect(0, 0, 3, 3)), res, img_size_); } else { - return scaleCameraIntrinsics(K_[1], res, calib_size_); + return ftl::calibration::scaleCameraMatrix(K_[1], res, calib_size_); } } @@ -163,6 +102,19 @@ Mat Calibrate::getCameraDistortionRight() { else { return D_[1]; } } +Mat Calibrate::getPose() const { + Mat T; + if (rectify_) { + Mat R1 = Mat::eye(4, 4, CV_64FC1); + R1_.copyTo(R1(cv::Rect(0, 0, 3, 3))); + T = pose_ * R1.inv(); + } + else { + pose_.copyTo(T); + } + return T; +} + bool Calibrate::setRectify(bool enabled) { if (t_.empty() || R_.empty()) { enabled = false; } if (enabled) { @@ -185,7 +137,11 @@ bool Calibrate::setDistortion(const vector<Mat> &D) { bool Calibrate::setIntrinsics(const Size &size, const vector<Mat> &K) { if (K.size() != 2) { return false; } if (size.empty() || size.width <= 0 || size.height <= 0) { return false; } - for (const auto k : K) { if (!isValidCamera(k)) { return false; }} + for (const auto k : K) { + if (!ftl::calibration::validate::cameraMatrix(k)) { + return false; + } + } calib_size_ = Size(size); K[0].copyTo(K_[0]); @@ -194,8 +150,8 @@ bool Calibrate::setIntrinsics(const Size &size, const vector<Mat> &K) { } bool Calibrate::setExtrinsics(const Mat &R, const Mat &t) { - if (!isValidRotationMatrix(R) || - !isValidTranslationForRectification(t)) { return false; } + if (!ftl::calibration::validate::rotationMatrix(R) || + !ftl::calibration::validate::translationStereo(t)) { return false; } R.copyTo(R_); t.copyTo(t_); @@ -203,7 +159,7 @@ bool Calibrate::setExtrinsics(const Mat &R, const Mat &t) { } bool Calibrate::setPose(const Mat &P) { - if (!isValidPose(P)) { return false; } + if (!ftl::calibration::validate::pose(P)) { return false; } P.copyTo(pose_); return true; } @@ -301,7 +257,6 @@ bool Calibrate::calculateRectificationParameters() { img_size_, R_, t_, R1_, R2_, P1_, P2_, Q_, 0, alpha); - // TODO use fixed point maps for CPU (gpu remap() requires floating point) initUndistortRectifyMap(K1, D1, R1_, P1_, img_size_, CV_32FC1, map1_.first, map2_.first); initUndistortRectifyMap(K2, D2, R2_, P2_, img_size_, CV_32FC1, map1_.second, map2_.second); diff --git a/components/rgbd-sources/src/sources/stereovideo/calibrate.hpp b/components/rgbd-sources/src/sources/stereovideo/calibrate.hpp index bec1c93388cfd20f8b78d60f7cf332f78e9244a5..06a129b7f94665556a079e49b1f1b4b70946543c 100644 --- a/components/rgbd-sources/src/sources/stereovideo/calibrate.hpp +++ b/components/rgbd-sources/src/sources/stereovideo/calibrate.hpp @@ -85,9 +85,10 @@ class Calibrate : public ftl::Configurable { cv::Mat getCameraDistortionRight(); /** - * @brief Get camera pose from calibration + * @brief Get camera pose from calibration. Returns pose to rectified + * camera if rectification is enabled. */ - const cv::Mat &getPose() const { return pose_; }; + cv::Mat getPose() const; /** * @brief Enable/disable recitification. If disabled, instance returns diff --git a/components/rgbd-sources/src/sources/stereovideo/local.cpp b/components/rgbd-sources/src/sources/stereovideo/local.cpp index eed169bd2b3d073e544f09e101053e50103fc018..c46369c5356eddf1c6f1c61cdadf989ab2af2882 100644 --- a/components/rgbd-sources/src/sources/stereovideo/local.cpp +++ b/components/rgbd-sources/src/sources/stereovideo/local.cpp @@ -116,7 +116,9 @@ bool LocalSource::grab() { return true; } -bool LocalSource::get(cv::cuda::GpuMat &l_out, cv::cuda::GpuMat &r_out, cv::cuda::GpuMat &hres_out, Calibrate *c, cv::cuda::Stream &stream) { +bool LocalSource::get(cv::cuda::GpuMat &l_out, cv::cuda::GpuMat &r_out, + cv::cuda::GpuMat &l_hres_out, cv::Mat &r_hres_out, Calibrate *c, cv::cuda::Stream &stream) { + Mat l, r ,hres; // Use page locked memory @@ -131,7 +133,7 @@ bool LocalSource::get(cv::cuda::GpuMat &l_out, cv::cuda::GpuMat &r_out, cv::cuda std::future<bool> future_b; if (camera_b_) { - future_b = std::move(ftl::pool.push([this,&rfull,&r,c,&r_out,&stream](int id) { + future_b = std::move(ftl::pool.push([this,&rfull,&r,c,&r_out,&r_hres_out,&stream](int id) { if (!camera_b_->retrieve(frame_r_)) { LOG(ERROR) << "Unable to read frame from camera B"; return false; @@ -145,6 +147,10 @@ bool LocalSource::get(cv::cuda::GpuMat &l_out, cv::cuda::GpuMat &r_out, cv::cuda if (hasHigherRes()) { // TODO: Use threads? cv::resize(rfull, r, r.size(), 0.0, 0.0, cv::INTER_CUBIC); + r_hres_out = rfull; + } + else { + r_hres_out = Mat(); } } @@ -189,9 +195,9 @@ bool LocalSource::get(cv::cuda::GpuMat &l_out, cv::cuda::GpuMat &r_out, cv::cuda if (hasHigherRes()) { //FTL_Profile("Frame Resize", 0.01); cv::resize(lfull, l, l.size(), 0.0, 0.0, cv::INTER_CUBIC); - hres_out.upload(hres, stream); + l_hres_out.upload(hres, stream); } else { - hres_out = cv::cuda::GpuMat(); + l_hres_out = cv::cuda::GpuMat(); } { diff --git a/components/rgbd-sources/src/sources/stereovideo/local.hpp b/components/rgbd-sources/src/sources/stereovideo/local.hpp index 5615e550d01eedb580923810aac8a6d01959169b..90654916489ed27d111ab616a220c2bd5323a38a 100644 --- a/components/rgbd-sources/src/sources/stereovideo/local.hpp +++ b/components/rgbd-sources/src/sources/stereovideo/local.hpp @@ -24,7 +24,7 @@ class LocalSource : public Configurable { //bool left(cv::Mat &m); //bool right(cv::Mat &m); bool grab(); - bool get(cv::cuda::GpuMat &l, cv::cuda::GpuMat &r, cv::cuda::GpuMat &h, Calibrate *c, cv::cuda::Stream &stream); + bool get(cv::cuda::GpuMat &l, cv::cuda::GpuMat &r, cv::cuda::GpuMat &h_l, cv::Mat &h_r, Calibrate *c, cv::cuda::Stream &stream); unsigned int width() const { return dwidth_; } unsigned int height() const { return dheight_; } diff --git a/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp b/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp index bf0b01c8229931f7f80f7da8fa739e3bf121d1e1..94854624e01b9256f8a7a793ef740ca472c28000 100644 --- a/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp +++ b/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp @@ -268,18 +268,20 @@ bool StereoVideoSource::retrieve() { frame.reset(); frame.setOrigin(&state_); - cv::cuda::GpuMat dummy; - auto &hres = (lsrc_->hasHigherRes()) ? frame.create<cv::cuda::GpuMat>(Channel::ColourHighRes) : dummy; + cv::cuda::GpuMat gpu_dummy; + cv::Mat dummy; + auto &hres = (lsrc_->hasHigherRes()) ? frame.create<cv::cuda::GpuMat>(Channel::ColourHighRes) : gpu_dummy; + auto &hres_r = (lsrc_->hasHigherRes()) ? frame.create<cv::Mat>(Channel::RightHighRes) : dummy; if (lsrc_->isStereo()) { cv::cuda::GpuMat &left = frame.create<cv::cuda::GpuMat>(Channel::Left); cv::cuda::GpuMat &right = frame.create<cv::cuda::GpuMat>(Channel::Right); - lsrc_->get(left, right, hres, calib_, stream2_); + lsrc_->get(left, right, hres, hres_r, calib_, stream2_); } else { cv::cuda::GpuMat &left = frame.create<cv::cuda::GpuMat>(Channel::Left); cv::cuda::GpuMat right; - lsrc_->get(left, right, hres, calib_, stream2_); + lsrc_->get(left, right, hres, hres_r, calib_, stream2_); } //LOG(INFO) << "Channel size: " << hres.size(); diff --git a/components/rgbd-sources/src/sources/virtual/virtual.cpp b/components/rgbd-sources/src/sources/virtual/virtual.cpp deleted file mode 100644 index 1580750afb047150e7f2fe2970aef80661d6fff9..0000000000000000000000000000000000000000 --- a/components/rgbd-sources/src/sources/virtual/virtual.cpp +++ /dev/null @@ -1,202 +0,0 @@ -#include <ftl/rgbd/virtual.hpp> - -using ftl::rgbd::VirtualSource; -using ftl::rgbd::Source; -using ftl::codecs::Channel; -using ftl::rgbd::Camera; - -class VirtualImpl : public ftl::rgbd::detail::Source { - public: - explicit VirtualImpl(ftl::rgbd::Source *host) : ftl::rgbd::detail::Source(host) { - params_.width = host->value("width", 1280); - params_.height = host->value("height", 720); - params_.fx = host->value("focal", 700.0f); - params_.fy = params_.fx; - params_.cx = -(double)params_.width / 2.0; - params_.cy = -(double)params_.height / 2.0; - params_.minDepth = host->value("minDepth", 0.1f); - params_.maxDepth = host->value("maxDepth", 20.0f); - params_.doffs = 0; - params_.baseline = host->value("baseline", 0.0f); - - params_right_.width = host->value("width", 1280); - params_right_.height = host->value("height", 720); - params_right_.fx = host->value("focal_right", 700.0f); - params_right_.fy = params_right_.fx; - params_right_.cx = host->value("centre_x_right", -(double)params_.width / 2.0); - params_right_.cy = host->value("centre_y_right", -(double)params_.height / 2.0); - params_right_.minDepth = host->value("minDepth", 0.1f); - params_right_.maxDepth = host->value("maxDepth", 20.0f); - params_right_.doffs = 0; - params_right_.baseline = host->value("baseline", 0.0f); - - capabilities_ = ftl::rgbd::kCapVideo | ftl::rgbd::kCapStereo; - - if (!host->value("locked", false)) capabilities_ |= ftl::rgbd::kCapMovable; - host->on("baseline", [this](const ftl::config::Event&) { - params_.baseline = host_->value("baseline", 0.0f); - }); - - host->on("focal", [this](const ftl::config::Event&) { - params_.fx = host_->value("focal", 700.0f); - params_.fy = params_.fx; - }); - - host->on("centre_x", [this](const ftl::config::Event&) { - params_.cx = host_->value("centre_x", 0.0f); - }); - - host->on("centre_y", [this](const ftl::config::Event&) { - params_.cy = host_->value("centre_y", 0.0f); - }); - - host->on("focal_right", [this](const ftl::config::Event&) { - params_right_.fx = host_->value("focal_right", 700.0f); - params_right_.fy = params_right_.fx; - }); - - host->on("centre_x_right", [this](const ftl::config::Event&) { - params_right_.cx = host_->value("centre_x_right", 0.0f); - }); - - host->on("centre_y_right", [this](const ftl::config::Event&) { - params_right_.cy = host_->value("centre_y_right", 0.0f); - }); - - } - - ~VirtualImpl() { - - } - - bool capture(int64_t ts) override { - timestamp_ = ts; - return true; - } - - bool retrieve() override { - return true; - } - - bool compute(int n, int b) override { - if (callback) { - frame_.reset(); - frame_.setOrigin(&state_); - bool goodFrame = false; - - try { - goodFrame = callback(frame_); - } catch (std::exception &e) { - LOG(ERROR) << "Exception in render callback: " << e.what(); - } catch (...) { - LOG(ERROR) << "Unknown exception in render callback"; - } - - /*if (frame.hasChannel(Channel::Colour)) { - //frame.download(Channel::Colour); - cv::cuda::swap(frame.get<cv::cuda::GpuMat>(Channel::Colour), rgb_); - } else { - LOG(ERROR) << "Channel 1 frame in rendering"; - } - - if ((host_->getChannel() != Channel::None) && - frame.hasChannel(host_->getChannel())) { - //frame.download(host_->getChannel()); - cv::cuda::swap(frame.get<cv::cuda::GpuMat>(host_->getChannel()), depth_); - }*/ - - if (goodFrame) host_->notify(timestamp_, frame_); - } - return true; - } - - Camera parameters(ftl::codecs::Channel c) { - return (c == Channel::Left) ? params_ : params_right_; - } - - bool isReady() override { return true; } - - std::function<bool(ftl::rgbd::Frame &)> callback; - //ftl::rgbd::Frame frame; - - ftl::rgbd::Camera params_right_; -}; - -VirtualSource::VirtualSource(ftl::config::json_t &cfg) : Source(cfg) { - impl_ = new VirtualImpl(this); -} - -VirtualSource::~VirtualSource() { - -} - -void VirtualSource::onRender(const std::function<bool(ftl::rgbd::Frame &)> &f) { - dynamic_cast<VirtualImpl*>(impl_)->callback = f; -} - -/* -void Source::writeFrames(int64_t ts, const cv::Mat &rgb, const cv::Mat &depth) { - if (!impl_) { - UNIQUE_LOCK(mutex_,lk); - rgb.copyTo(rgb_); - depth.copyTo(depth_); - timestamp_ = ts; - } -} - -void Source::writeFrames(int64_t ts, const ftl::cuda::TextureObject<uchar4> &rgb, const ftl::cuda::TextureObject<uint> &depth, cudaStream_t stream) { - if (!impl_) { - UNIQUE_LOCK(mutex_,lk); - timestamp_ = ts; - rgb_.create(rgb.height(), rgb.width(), CV_8UC4); - cudaSafeCall(cudaMemcpy2DAsync(rgb_.data, rgb_.step, rgb.devicePtr(), rgb.pitch(), rgb_.cols * sizeof(uchar4), rgb_.rows, cudaMemcpyDeviceToHost, stream)); - depth_.create(depth.height(), depth.width(), CV_32SC1); - cudaSafeCall(cudaMemcpy2DAsync(depth_.data, depth_.step, depth.devicePtr(), depth.pitch(), depth_.cols * sizeof(uint), depth_.rows, cudaMemcpyDeviceToHost, stream)); - //cudaSafeCall(cudaStreamSynchronize(stream)); // TODO:(Nick) Don't wait here. - stream_ = stream; - //depth_.convertTo(depth_, CV_32F, 1.0f / 1000.0f); - } else { - LOG(ERROR) << "writeFrames cannot be done on this source: " << getURI(); - } -} - -void Source::writeFrames(int64_t ts, const ftl::cuda::TextureObject<uchar4> &rgb, const ftl::cuda::TextureObject<float> &depth, cudaStream_t stream) { - if (!impl_) { - UNIQUE_LOCK(mutex_,lk); - timestamp_ = ts; - rgb.download(rgb_, stream); - //rgb_.create(rgb.height(), rgb.width(), CV_8UC4); - //cudaSafeCall(cudaMemcpy2DAsync(rgb_.data, rgb_.step, rgb.devicePtr(), rgb.pitch(), rgb_.cols * sizeof(uchar4), rgb_.rows, cudaMemcpyDeviceToHost, stream)); - depth.download(depth_, stream); - //depth_.create(depth.height(), depth.width(), CV_32FC1); - //cudaSafeCall(cudaMemcpy2DAsync(depth_.data, depth_.step, depth.devicePtr(), depth.pitch(), depth_.cols * sizeof(float), depth_.rows, cudaMemcpyDeviceToHost, stream)); - - stream_ = stream; - cudaSafeCall(cudaStreamSynchronize(stream_)); - cv::cvtColor(rgb_,rgb_, cv::COLOR_BGRA2BGR); - cv::cvtColor(rgb_,rgb_, cv::COLOR_Lab2BGR); - - if (callback_) callback_(timestamp_, rgb_, depth_); - } -} - -void Source::writeFrames(int64_t ts, const ftl::cuda::TextureObject<uchar4> &rgb, const ftl::cuda::TextureObject<uchar4> &rgb2, cudaStream_t stream) { - if (!impl_) { - UNIQUE_LOCK(mutex_,lk); - timestamp_ = ts; - rgb.download(rgb_, stream); - //rgb_.create(rgb.height(), rgb.width(), CV_8UC4); - //cudaSafeCall(cudaMemcpy2DAsync(rgb_.data, rgb_.step, rgb.devicePtr(), rgb.pitch(), rgb_.cols * sizeof(uchar4), rgb_.rows, cudaMemcpyDeviceToHost, stream)); - rgb2.download(depth_, stream); - //depth_.create(depth.height(), depth.width(), CV_32FC1); - //cudaSafeCall(cudaMemcpy2DAsync(depth_.data, depth_.step, depth.devicePtr(), depth.pitch(), depth_.cols * sizeof(float), depth_.rows, cudaMemcpyDeviceToHost, stream)); - - stream_ = stream; - cudaSafeCall(cudaStreamSynchronize(stream_)); - cv::cvtColor(rgb_,rgb_, cv::COLOR_BGRA2BGR); - cv::cvtColor(rgb_,rgb_, cv::COLOR_Lab2BGR); - cv::cvtColor(depth_,depth_, cv::COLOR_BGRA2BGR); - cv::cvtColor(depth_,depth_, cv::COLOR_Lab2BGR); - } -} -*/ \ No newline at end of file diff --git a/components/rgbd-sources/src/streamer.cpp b/components/rgbd-sources/src/streamer.cpp deleted file mode 100644 index e6c08e5b53feaba743dcbb3816cb16fe7f9ad7ed..0000000000000000000000000000000000000000 --- a/components/rgbd-sources/src/streamer.cpp +++ /dev/null @@ -1,686 +0,0 @@ -#include <ftl/rgbd/streamer.hpp> -#include <ftl/timer.hpp> -#include <vector> -#include <optional> -#include <thread> -#include <chrono> -#include <tuple> -#include <algorithm> - -#include <ftl/rgbd/detail/abr.hpp> -#include <ftl/codecs/encoder.hpp> - -using ftl::rgbd::Streamer; -using ftl::rgbd::Source; -using ftl::rgbd::detail::StreamSource; -using ftl::rgbd::detail::StreamClient; -using ftl::rgbd::detail::ABRController; -using ftl::codecs::definition_t; -using ftl::codecs::device_t; -using ftl::codecs::Channel; -using ftl::net::Universe; -using std::string; -using std::list; -using std::map; -using std::optional; -using std::vector; -using std::this_thread::sleep_for; -using std::chrono::milliseconds; -using std::tuple; -using std::make_tuple; - -static const ftl::codecs::preset_t kQualityThreshold = ftl::codecs::kPresetLQThreshold; - - -Streamer::Streamer(nlohmann::json &config, Universe *net) - : ftl::Configurable(config), late_(false) { - - active_ = false; - net_ = net; - time_peer_ = ftl::UUID(0); - clock_adjust_ = 0; - mspf_ = ftl::timer::getInterval(); //1000 / value("fps", 20); - //last_dropped_ = 0; - //drop_count_ = 0; - - second_channel_ = Channel::None; - hq_devices_ = (value("disable_hardware_encode", false)) ? device_t::Software : device_t::Any; - hq_codec_ = value("video_codec", ftl::codecs::codec_t::Any); - - //group_.setFPS(value("fps", 20)); - group_.setName("NetStreamer"); - - compress_level_ = value("compression", 1); - - net->bind("find_stream", [this](const std::string &uri) -> optional<ftl::UUID> { - SHARED_LOCK(mutex_,slk); - - if (sources_.find(uri) != sources_.end()) { - LOG(INFO) << "Valid source request received: " << uri; - return net_->id(); - } else return {}; - }); - - net->bind("list_streams", [this]() -> vector<string> { - vector<string> streams; - for (auto &i : sources_) { - streams.push_back(i.first); - } - return streams; - }); - - net->bind("set_pose", [this](const std::string &uri, const std::vector<unsigned char> &buf) { - SHARED_LOCK(mutex_,slk); - - if (sources_.find(uri) != sources_.end()) { - Eigen::Matrix4d pose; - memcpy(pose.data(), buf.data(), buf.size()); - sources_[uri]->src->setPose(pose); - } - }); - - net->bind("get_pose", [this](const std::string &uri) -> std::vector<unsigned char> { - SHARED_LOCK(mutex_,slk); - - if (sources_.find(uri) != sources_.end()) { - Eigen::Matrix4d pose = sources_[uri]->src->getPose(); - vector<unsigned char> vec((unsigned char*)pose.data(), (unsigned char*)(pose.data()+(pose.size()))); - return vec; - } else { - LOG(WARNING) << "Requested pose not found: " << uri; - return {}; - } - }); - - // Allow remote users to access camera calibration matrix - net->bind("source_details", [this](const std::string &uri, ftl::codecs::Channel chan) -> tuple<unsigned int,vector<unsigned char>> { - vector<unsigned char> buf; - SHARED_LOCK(mutex_,slk); - - if (sources_.find(uri) != sources_.end()) { - buf.resize(sizeof(Camera)); - LOG(INFO) << "Calib buf size = " << buf.size(); - auto params = sources_[uri]->src->parameters(chan); - memcpy(buf.data(), ¶ms, buf.size()); - return make_tuple(sources_[uri]->src->getCapabilities(), buf); - } else { - return make_tuple(0u,buf); - } - }); - - net->bind("get_stream", [this](const string &source, int N, int rate, const UUID &peer, const string &dest) { - _addClient(source, N, rate, peer, dest); - }); - - net->bind("set_channel", [this](const string &uri, Channel chan) { - SHARED_LOCK(mutex_,slk); - - //if (sources_.find(uri) != sources_.end()) { - // sources_[uri]->src->setChannel(chan); - //} - second_channel_ = chan; - }); - - //net->bind("sync_streams", [this](unsigned long long time) { - // Calc timestamp delta - //}); - - //net->bind("ping_streamer", [this](unsigned long long time) -> unsigned long long { - // return time; - //}); - - on("hq_bitrate", [this](const ftl::config::Event &e) { - UNIQUE_LOCK(mutex_,ulk); - for (auto &s : sources_) { - s.second->hq_bitrate = value("hq_bitrate", ftl::codecs::kPresetBest); - } - }); - - on("video_codec", [this](const ftl::config::Event &e) { - UNIQUE_LOCK(mutex_,ulk); - hq_codec_ = value("video_codec", ftl::codecs::codec_t::Any); - for (auto &s : sources_) { - if (s.second->hq_encoder_c1) ftl::codecs::free(s.second->hq_encoder_c1); - if (s.second->hq_encoder_c2) ftl::codecs::free(s.second->hq_encoder_c2); - s.second->hq_encoder_c1 = nullptr; - s.second->hq_encoder_c2 = nullptr; - } - }); - - on("lq_bitrate", [this](const ftl::config::Event &e) { - UNIQUE_LOCK(mutex_,ulk); - for (auto &s : sources_) { - s.second->lq_bitrate = value("lq_bitrate", ftl::codecs::kPresetWorst); - } - }); - - insert_iframes_ = value("insert_iframes", false); - on("insert_iframes", [this](const ftl::config::Event &e) { - insert_iframes_ = value("insert_iframes", false); - }); -} - -Streamer::~Streamer() { - timer_job_.cancel(); - net_->unbind("find_stream"); - net_->unbind("list_streams"); - net_->unbind("source_calibration"); - net_->unbind("get_stream"); - net_->unbind("sync_streams"); - net_->unbind("ping_streamer"); - //pool_.stop(); - - { - UNIQUE_LOCK(mutex_,ulk); - for (auto &s : sources_) { - StreamSource *src = s.second; - src->clientCount = 0; - } - } - _cleanUp(); - { - UNIQUE_LOCK(mutex_,ulk); - sources_.clear(); - } -} - -void Streamer::add(Source *src) { - { - UNIQUE_LOCK(mutex_,ulk); - if (sources_.find(src->getID()) != sources_.end()) return; - - StreamSource *s = new StreamSource; - s->src = src; - //s->prev_depth = cv::Mat(cv::Size(src->parameters().width, src->parameters().height), CV_16SC1, 0); - s->jobs = 0; - s->frame = 0; - s->clientCount = 0; - s->hq_count = 0; - s->lq_count = 0; - - s->hq_bitrate = value("hq_bitrate", ftl::codecs::kPresetBest); - s->lq_bitrate = value("lq_bitrate", ftl::codecs::kPresetWorst); - - sources_[src->getID()] = s; - sourcesByNum_.push_back(s); - - group_.addSource(src); - - src->addRawCallback([this,s](Source *src, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt) { - if (spkt.channel == Channel::Calibration) { - // Calibration changed, so lets re-check the bitrate presets - const auto ¶ms = src->parameters(); - s->hq_bitrate = ftl::codecs::kPresetBest; - } - - LOG(INFO) << "RAW CALLBACK"; - _transmitPacket(s, spkt, pkt, Quality::Any); - }); - } - - LOG(INFO) << "Streaming: " << src->getID(); - net_->broadcast("add_stream", src->getID()); - - // FIXME: Temp hack for forward compatibility. - net_->bind(src->getID(), [this,src](ftl::net::Peer &p, short ttime, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt) { - LOG(INFO) << "RECEIVED PACKET: " << spkt.timestamp; - _addClient(src->getID(), pkt.frame_count, 0, p.id(), src->getID()); - if (spkt.channel != Channel::Colour && src->getChannel() != spkt.channel) { - LOG(INFO) << "SET CHANNEL: " << (int)spkt.channel; - src->setChannel(spkt.channel); - second_channel_ = spkt.channel; - } - }); -} - -void Streamer::add(ftl::rgbd::Group *grp) { - auto srcs = grp->sources(); - for (int i=0; i<srcs.size(); ++i) { - auto &src = srcs[i]; - { - UNIQUE_LOCK(mutex_,ulk); - if (sources_.find(src->getID()) != sources_.end()) return; - - StreamSource *s = new StreamSource; - s->src = src; - //s->prev_depth = cv::Mat(cv::Size(src->parameters().width, src->parameters().height), CV_16SC1, 0); - s->jobs = 0; - s->frame = 0; - s->clientCount = 0; - s->hq_count = 0; - s->lq_count = 0; - s->id = i; - sources_[src->getID()] = s; - - //group_.addSource(src); - - src->addRawCallback([this,s](Source *src, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt) { - LOG(INFO) << "RAW CALLBACK2"; - _transmitPacket(s, spkt, pkt, Quality::Any); - }); - } - - LOG(INFO) << "Proxy Streaming: " << src->getID(); - net_->broadcast("add_stream", src->getID()); - } - - LOG(INFO) << "All proxy streams added"; -} - -void Streamer::_addClient(const string &source, int N, int rate, const ftl::UUID &peer, const string &dest) { - StreamSource *s = nullptr; - - { - UNIQUE_LOCK(mutex_,slk); - if (sources_.find(source) == sources_.end()) return; - - if (rate < 0 || rate >= 10) return; - if (N < 0 || N > ftl::rgbd::kMaxFrames) return; - - //DLOG(INFO) << "Adding Stream Peer: " << peer.to_string() << " rate=" << rate << " N=" << N; - - s = sources_[source]; - - // Set a time peer for clock sync - if (time_peer_ == ftl::UUID(0)) { - time_peer_ = peer; - - // Do a time sync whenever the CPU is idle for 10ms or more. - // FIXME: Could be starved - timer_job_ = ftl::timer::add(ftl::timer::kTimerIdle10, [peer,this](int id) { - auto start = std::chrono::high_resolution_clock::now(); - int64_t mastertime; - - try { - mastertime = net_->call<int64_t>(peer, "__ping__"); - } catch (...) { - LOG(ERROR) << "Ping failed"; - // Reset time peer and remove timer - time_peer_ = ftl::UUID(0); - return false; - } - - auto elapsed = std::chrono::high_resolution_clock::now() - start; - int64_t latency = std::chrono::duration_cast<std::chrono::milliseconds>(elapsed).count(); - auto clock_adjust = mastertime - (ftl::timer::get_time() + (latency/2)); - - if (clock_adjust > 0) { - LOG(INFO) << "Clock adjustment: " << clock_adjust; - //LOG(INFO) << "Latency: " << (latency / 2); - //LOG(INFO) << "Local: " << std::chrono::time_point_cast<std::chrono::milliseconds>(start).time_since_epoch().count() << ", master: " << mastertime; - ftl::timer::setClockAdjustment(clock_adjust); - } - - return true; - }); - } - } - - if (!s) return; // No matching stream - - SHARED_LOCK(mutex_, slk); - UNIQUE_LOCK(s->mutex, lk2); - for (auto &client : s->clients) { - // If already listening, just update chunk counters - if (client.peerid == peer) { - // Allow for same client but different quality (beyond threshold) - if ((client.preset < kQualityThreshold && rate >= kQualityThreshold) || - (client.preset >= kQualityThreshold && rate < kQualityThreshold)) continue; - - client.txmax = N; - client.txcount = 0; - - // Possible switch from high quality to low quality encoding or vice versa - /*if (client.preset < kQualityThreshold && rate >= kQualityThreshold) { - s->hq_count--; - s->lq_count++; - if (s->lq_encoder_c1) s->lq_encoder_c1->reset(); - if (s->lq_encoder_c2) s->lq_encoder_c2->reset(); - } else if (client.preset >= kQualityThreshold && rate < kQualityThreshold) { - s->hq_count++; - s->lq_count--; - if (s->hq_encoder_c1) s->hq_encoder_c1->reset(); - if (s->hq_encoder_c2) s->hq_encoder_c2->reset(); - break; - }*/ - - client.preset = rate; - return; - } - } - - // Not an existing client so add one - StreamClient &c = s->clients.emplace_back(); - c.peerid = peer; - c.uri = dest; - c.txcount = 0; - c.txmax = N; - c.preset = rate; - - if (rate >= kQualityThreshold) { - if (s->lq_encoder_c1) s->lq_encoder_c1->reset(); - if (s->lq_encoder_c2) s->lq_encoder_c2->reset(); - s->lq_count++; - } else { - if (s->hq_encoder_c1) s->hq_encoder_c1->reset(); - if (s->hq_encoder_c2) s->hq_encoder_c2->reset(); - s->hq_count++; - } - - ++s->clientCount; - - // Finally, inject calibration and config data - s->src->inject(Channel::Calibration, s->src->parameters(Channel::Left), Channel::Left, s->src->getCapabilities()); - s->src->inject(Channel::Calibration, s->src->parameters(Channel::Right), Channel::Right, s->src->getCapabilities()); - s->src->inject(s->src->getPose()); - //if (!(*s->src->get<nlohmann::json>("meta")).is_null()) { - s->src->inject(Channel::Configuration, "/original", s->src->getConfig().dump()); - //} -} - -void Streamer::remove(Source *) { - -} - -void Streamer::remove(const std::string &) { - -} - -void Streamer::stop() { - group_.stop(); -} - -void Streamer::run(bool block) { - if (block) { - group_.onFrameSet([this](FrameSet &fs) -> bool { - _process(fs); - return true; - }); - } else { - // Create thread job for frame ticking - ftl::pool.push([this](int id) { - group_.onFrameSet([this](FrameSet &fs) -> bool { - _process(fs); - return true; - }); - }); - } -} - -void Streamer::_cleanUp() { - for (auto &s : sources_) { - StreamSource *src = s.second; - UNIQUE_LOCK(src->mutex,lk); - - auto i = src->clients.begin(); - while (i != src->clients.end()) { - // Client request completed so remove from list - if ((*i).txcount >= (*i).txmax) { - // If peer was clock sync master, the remove that... - if ((*i).peerid == time_peer_) { - timer_job_.cancel(); - time_peer_ = ftl::UUID(0); - } - LOG(INFO) << "Remove client: " << (*i).uri; - - if ((*i).preset < kQualityThreshold) { - src->hq_count--; - } else { - src->lq_count--; - } - - i = src->clients.erase(i); - --src->clientCount; - } else { - i++; - } - } - - if (src->hq_count == 0) { - if (src->hq_encoder_c1) ftl::codecs::free(src->hq_encoder_c1); - if (src->hq_encoder_c2) ftl::codecs::free(src->hq_encoder_c2); - } - - if (src->lq_count == 0) { - if (src->lq_encoder_c1) ftl::codecs::free(src->lq_encoder_c1); - if (src->lq_encoder_c2) ftl::codecs::free(src->lq_encoder_c2); - } - - if (src->clientCount == 0) { - - } - } -} - -void Streamer::_process(ftl::rgbd::FrameSet &fs) { - // Prevent new clients during processing. - SHARED_LOCK(mutex_,slk); - - // This check is not valid, always assume fs.sources is correct - //if (fs.sources.size() != sources_.size()) { - // LOG(ERROR) << "Incorrect number of sources in frameset: " << fs.sources.size() << " vs " << sources_.size(); - //return; - //} - - int totalclients = 0; - - frame_no_ = fs.timestamp; - - for (int j=0; j<fs.frames.size(); ++j) { - StreamSource *src = sourcesByNum_[j]; - SHARED_LOCK(src->mutex,lk); - - // Don't do any work in the following cases - if (!src) continue; - //if (!fs.sources[j]->isReady()) continue; - if (src->clientCount == 0) continue; - //if (fs.channel1[j].empty() || (fs.sources[j]->getChannel() != ftl::rgbd::kChanNone && fs.channel2[j].empty())) continue; - if (!fs.frames[j].hasChannel(Channel::Colour) || !fs.frames[j].hasChannel(second_channel_)) { - LOG(WARNING) << "Missing required channel when streaming: " << (int)second_channel_; - continue; - } - - bool hasChan2 = second_channel_ != Channel::None && - fs.frames[j].hasChannel(second_channel_); - - totalclients += src->clientCount; - - // Do we need to do high quality encoding? - if (src->hq_count > 0) { - - auto chan = second_channel_; - - // Do we have the resources to do a HQ encoding? - ///if (src->hq_encoder_c1 && (!hasChan2 || src->hq_encoder_c2)) { - //auto *enc1 = src->hq_encoder_c1; - //auto *enc2 = src->hq_encoder_c2; - - MUTEX mtx; - std::condition_variable cv; - bool chan2done = false; - - if (hasChan2) { - if (fs.frames[j].getPackets(chan).size() == 0) { - - // Allocate an encoder - if (!src->hq_encoder_c2) src->hq_encoder_c2 = ftl::codecs::allocateEncoder( - definition_t::HD1080, hq_devices_, hq_codec_); - - auto *enc = src->hq_encoder_c2; - - // Do we have an encoder to continue with? - if (enc) { - ftl::pool.push([this,&fs,enc,src,hasChan2,&cv,j,&chan2done](int id) { - // TODO: Stagger the reset between nodes... random phasing - if (insert_iframes_ && fs.timestamp % (10*ftl::timer::getInterval()) == 0) enc->reset(); - - auto chan = second_channel_; - - try { - enc->encode(fs.frames[j].get<cv::cuda::GpuMat>(chan), src->hq_bitrate, [this,src,hasChan2,chan,&cv,&chan2done](const ftl::codecs::Packet &blk){ - _transmitPacket(src, blk, chan, hasChan2, Quality::High); - chan2done = true; - cv.notify_one(); - }); - } catch (std::exception &e) { - LOG(ERROR) << "Exception in encoder: " << e.what(); - chan2done = true; - cv.notify_one(); - } - }); - } else { - chan2done = true; - LOG(ERROR) << "Insufficient encoder resources"; - } - } else { - // Already have an encoding so send this - const auto &packets = fs.frames[j].getPackets(chan); - //LOG(INFO) << "Send existing chan2 encoding: " << packets.size(); - for (const auto &i : packets) { - _transmitPacket(src, i, chan, hasChan2, Quality::High); - } - } - } else { - // No second channel requested... - if (src->hq_encoder_c2) src->hq_encoder_c2->reset(); - chan2done = true; - } - - - auto colChan = (fs.frames[j].hasChannel(Channel::ColourHighRes)) ? Channel::ColourHighRes : Channel::Colour; - if (fs.frames[j].getPackets(colChan).size() == 0) { - if (!src->hq_encoder_c1) src->hq_encoder_c1 = ftl::codecs::allocateEncoder( - definition_t::HD1080, hq_devices_, hq_codec_); - auto *enc = src->hq_encoder_c1; - - if (enc) { - // TODO: Stagger the reset between nodes... random phasing - if (insert_iframes_ && fs.timestamp % (10*ftl::timer::getInterval()) == 0) enc->reset(); - enc->encode(fs.frames[j].get<cv::cuda::GpuMat>(colChan), src->hq_bitrate, [this,src,hasChan2](const ftl::codecs::Packet &blk){ - _transmitPacket(src, blk, Channel::Colour, hasChan2, Quality::High); - }); - } else { - LOG(ERROR) << "Insufficient encoder resources"; - } - } else { - const auto &packets = fs.frames[j].getPackets(colChan); - // FIXME: Adjust block number and total to match number of packets - // Also requires the receiver to decode in block number order. - //LOG(INFO) << "Send existing encoding: " << packets.size(); - for (const auto &i : packets) { - _transmitPacket(src, i, Channel::Colour, hasChan2, Quality::High); - } - } - - // Ensure both channels have been completed. - std::unique_lock<std::mutex> lk(mtx); - cv.wait(lk, [&chan2done]{ return chan2done; }); - //} - } - - // Do we need to do low quality encoding? - if (src->lq_count > 0) { - if (!src->lq_encoder_c1) src->lq_encoder_c1 = ftl::codecs::allocateEncoder( - definition_t::SD480, device_t::Software); - if (!src->lq_encoder_c2 && hasChan2) src->lq_encoder_c2 = ftl::codecs::allocateEncoder( - definition_t::SD480, device_t::Software); - - // Do we have the resources to do a LQ encoding? - if (src->lq_encoder_c1 && (!hasChan2 || src->lq_encoder_c2)) { - auto *enc1 = src->lq_encoder_c1; - auto *enc2 = src->lq_encoder_c2; - - // Important to send channel 2 first if needed... - // Receiver only waits for channel 1 by default - if (hasChan2) { - auto chan = second_channel_; - - enc2->encode(fs.frames[j].get<cv::cuda::GpuMat>(chan), src->lq_bitrate, [this,src,hasChan2,chan](const ftl::codecs::Packet &blk){ - _transmitPacket(src, blk, chan, hasChan2, Quality::Low); - }); - } else { - if (enc2) enc2->reset(); - } - - enc1->encode(fs.frames[j].get<cv::cuda::GpuMat>(Channel::Colour), src->lq_bitrate, [this,src,hasChan2](const ftl::codecs::Packet &blk){ - _transmitPacket(src, blk, Channel::Colour, hasChan2, Quality::Low); - }); - } - } - } - - /*std::unique_lock<std::mutex> lk(job_mtx_); - job_cv_.wait_for(lk, std::chrono::seconds(20), [this]{ return jobs_ == 0; }); - if (jobs_ != 0) { - LOG(FATAL) << "Deadlock detected"; - }*/ - - // Go to sleep if no clients instead of spinning the cpu - if (totalclients == 0 || sources_.size() == 0) { - // Make sure to unlock so clients can connect! - //lk.unlock(); - slk.unlock(); - //sleep_for(milliseconds(50)); - } else _cleanUp(); -} - -void Streamer::_transmitPacket(StreamSource *src, const ftl::codecs::Packet &pkt, Channel chan, bool hasChan2, Quality q) { - const int version = 4; // FIXME: Needs to be selected based on client version? Or removed when refactor complete. - - if (version <= 3) { - ftl::codecs::StreamPacket spkt = { - 3, // Version - frame_no_, - src->id, - (hasChan2) ? 2 : 1, - chan - //static_cast<uint8_t>((chan & 0x1) | ((hasChan2) ? 0x2 : 0x0)) - }; - _transmitPacket(src, spkt, pkt, q); - } else { - ftl::codecs::StreamPacket spkt = { - 4, // Version - frame_no_, - 0, - src->id, - chan - //static_cast<uint8_t>((chan & 0x1) | ((hasChan2) ? 0x2 : 0x0)) - }; - _transmitPacket(src, spkt, pkt, q); - } -} - -void Streamer::_transmitPacket(StreamSource *src, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt, Quality q) { - //LOG(INFO) << "TRANSMIT: " << spkt.timestamp; - // Lock to prevent clients being added / removed - //SHARED_LOCK(src->mutex,lk); - auto c = src->clients.begin(); - while (c != src->clients.end()) { - const ftl::codecs::preset_t b = (*c).preset; - if ((q == Quality::High && b >= kQualityThreshold) || (q == Quality::Low && b < kQualityThreshold)) { - ++c; - LOG(INFO) << "INCORRECT QUALITY"; - continue; - } - - try { - // TODO:(Nick) Send pose - short pre_transmit_latency = short(ftl::timer::get_time() - spkt.timestamp); - if (!net_->send((*c).peerid, - (*c).uri, - pre_transmit_latency, // Time since timestamp for tx - spkt, - pkt)) { - - // Send failed so mark as client stream completed - (*c).txcount = (*c).txmax; - } else { - // Count frame as completed only if last block and channel is 0 - if (spkt.channel == Channel::Colour) ++(*c).txcount; // pkt.block_number == pkt.block_total - 1 && - } - } catch(...) { - (*c).txcount = (*c).txmax; - } - ++c; - } -} diff --git a/components/streams/src/netstream.cpp b/components/streams/src/netstream.cpp index bd16f8c0a6becce1bcc3e6a1ba4dcfb047199065..54fc032074f25be186a8a20055f330f6968c7eac 100644 --- a/components/streams/src/netstream.cpp +++ b/components/streams/src/netstream.cpp @@ -353,14 +353,14 @@ bool Net::_processRequest(ftl::net::Peer &p, const ftl::codecs::Packet &pkt) { void Net::_checkDataRate(size_t tx_size, int64_t tx_latency, int64_t ts) { float actual_mbps = (float(tx_size) * 8.0f * (1000.0f / float(tx_latency))) / 1048576.0f; float min_mbps = (float(tx_size) * 8.0f * (1000.0f / float(ftl::timer::getInterval()))) / 1048576.0f; - if (actual_mbps > 0.0f && actual_mbps < min_mbps) LOG(WARNING) << "Bitrate = " << actual_mbps << "Mbps, min required = " << min_mbps << "Mbps"; + //if (actual_mbps > 0.0f && actual_mbps < min_mbps) LOG(WARNING) << "Bitrate = " << actual_mbps << "Mbps, min required = " << min_mbps << "Mbps"; UNIQUE_LOCK(msg_mtx_,lk); req_bitrate_ += float(tx_size) * 8.0f; sample_count_ += 1.0f; if (ts - last_msg_ >= 1000) { - LOG(INFO) << "Required Bitrate = " << (req_bitrate_ / float(ts - last_msg_) * 1000.0f / 1048576.0f) << "Mbps"; + DLOG(INFO) << "Required Bitrate = " << (req_bitrate_ / float(ts - last_msg_) * 1000.0f / 1048576.0f) << "Mbps"; last_msg_ = ts; req_bitrate_ = 0.0f; sample_count_ = 0.0f; diff --git a/components/streams/src/sender.cpp b/components/streams/src/sender.cpp index 1b448648fe5ef51fd3f4ccf0440c79ebbe4fe8a9..d39d0a0ddd80dcbb19d678510bb6600ff4697615 100644 --- a/components/streams/src/sender.cpp +++ b/components/streams/src/sender.cpp @@ -233,7 +233,15 @@ void Sender::_encodeChannel(ftl::rgbd::FrameSet &fs, Channel c, bool reset) { uint32_t offset = 0; while (offset < fs.frames.size()) { - auto cc = (c == Channel::Colour && fs.frames[offset].hasChannel(Channel::ColourHighRes)) ? Channel::ColourHighRes : c; + Channel cc = c; + if ((cc == Channel::Colour) && fs.frames[offset].hasChannel(Channel::ColourHighRes)) { + cc = Channel::ColourHighRes; + } + + if ((cc == Channel::Right) && fs.frames[offset].hasChannel(Channel::RightHighRes)) { + cc = Channel::RightHighRes; + fs.frames[offset].upload(cc); + } StreamPacket spkt; spkt.version = 4;