Slow working on bringing the old code up to standard.

- Documentation updates - most of the old files use non-Doxygen or
  no/minimal header comments.
- Rework SimpleSuite to be more useful.
- Coverity-surfaced fixes.
This commit is contained in:
Kyle Isom 2023-10-19 20:32:46 -07:00
parent a9991f241a
commit b1bbaebdac
19 changed files with 825 additions and 441 deletions

View File

@ -1,6 +1,7 @@
<component name="InspectionProjectProfileManager">
<profile version="1.0">
<option name="myName" value="Project Default" />
<inspection_tool class="ClangTidy" enabled="false" level="WARNING" enabled_by_default="false" />
<inspection_tool class="Eslint" enabled="true" level="WARNING" enabled_by_default="true" />
<inspection_tool class="SpellCheckingInspection" enabled="false" level="TYPO" enabled_by_default="false">
<option name="processCode" value="true" />

View File

@ -44,16 +44,17 @@ set(HEADER_FILES
include/scsl/StringUtil.h
include/scsl/TLV.h
include/scmp/scmp.h
include/scmp/Math.h
include/scmp/Motion2D.h
include/scmp/geom/Coord2D.h
include/scmp/geom/Orientation.h
include/scmp/geom/Quaternion.h
include/scmp/geom/Vector.h
include/scmp/filter/Madgwick.h
include/sctest/Assert.h
include/sctest/Report.h
include/scmp/filter/Madgwick.h
)
include_directories(include)

View File

@ -1,4 +1,26 @@
/// math.h provides certain useful mathematical functions.
///
/// \file include/scmp/Math.h
/// \author K. Isom <kyle@imap.cc>
/// \date 2017-06-05
/// \brief Common math functions.
///
/// Arena defines a memory management backend for pre-allocating memory.
///
/// Copyright 2023 K. Isom <kyle@imap.cc>
///
/// Permission to use, copy, modify, and/or distribute this software for
/// any purpose with or without fee is hereby granted, provided that
/// the above copyright notice and this permission notice appear in all /// copies.
///
/// THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL
/// WARRANTIES WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED
/// WARRANTIES OF MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE
/// AUTHOR BE LIABLE FOR ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL
/// DAMAGES OR ANY DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA
/// OR PROFITS, WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER
/// TORTIOUS ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR
/// PERFORMANCE OF THIS SOFTWARE.
///
#ifndef SCCCL_MATH_H
#define SCCCL_MATH_H
@ -9,8 +31,8 @@
namespace scmp {
// MAX_RADIAN is a precomputed 2 * M_PI, and MIN_RADIAN is -2 * M_PI.
constexpr double MAX_RADIAN = 2 * M_PI;
/// MAX_RADIAN is a precomputed 2 * M_PI. and MIN_RADIAN is -2 * M_PI.
constexpr double MAX_RADIAN = 2 * M_PI;
constexpr double MIN_RADIAN = -2 * M_PI;
constexpr double POS_HALF_RADIAN = M_PI / 2;
constexpr double NEG_HALF_RADIAN = -(M_PI / 2);
@ -18,8 +40,10 @@ constexpr double NEG_HALF_RADIAN = -(M_PI / 2);
/// Roll m die of n sides, returning a vector of the dice.
std::vector<int> Die(int m, int n);
/// Roll m die of n sides, returning the total of the die.
int DieTotal(int m, int n);
/// Roll m die of n sides, and take the total of the top k die.
int BestDie(int k, int m, int n);

View File

@ -34,8 +34,9 @@
#include <scmp/geom/Quaternion.h>
/// scmp contains the wntrmute robotics code.
/// scmp contains the chimmering clarity math and physics code.
namespace scmp {
/// filter contains filtering algorithms.
namespace filter {
@ -54,30 +55,30 @@ namespace filter {
template <typename T>
class Madgwick {
public:
/// The Madgwick filter is initialised with an identity quaternion.
/// \brief The Madgwick filter is initialised with an identity quaternion.
Madgwick() : deltaT(0.0), previousSensorFrame(), sensorFrame() {};
/// The Madgwick filter is initialised with a sensor frame.
/// \brief The Madgwick filter is initialised with a sensor frame.
///
/// \param sf A sensor frame; if zero, the sensor frame will be
/// initialised as an identity quaternion.
Madgwick(scmp::geom::Vector<T, 3> sf) : deltaT(0.0), previousSensorFrame()
{
if (!sf.isZero()) {
sensorFrame = scmp::geom::quaternion(sf, 0.0);
sensorFrame = scmp::geom::quaternion<T>(sf, 0.0);
}
}
/// Initialise the filter with a sensor frame quaternion.
/// \brief Initialise the filter with a sensor frame quaternion.
///
/// \param sf A quaternion representing the current Orientation.
Madgwick(scmp::geom::Quaternion<T> sf) :
deltaT(0.0), previousSensorFrame(), sensorFrame(sf) {};
/// Return the current Orientation as measured by the filter.
/// \brief Return the current Orientation as measured by the filter.
///
/// \return The current sensor frame.
scmp::geom::Quaternion<T>
@ -87,6 +88,9 @@ public:
}
/// \brief Return the filter's rate of angular change from a
/// sensor frame.
///
/// Return the rate of change of the Orientation of the earth frame
/// with respect to the sensor frame.
///
@ -99,7 +103,7 @@ public:
return (this->sensorFrame * 0.5) * scmp::geom::Quaternion<T>(gyro, 0.0);
}
/// Update the sensor frame to a new frame.
/// \brief Update the sensor frame to a new frame.
///
/// \param sf The new sensor frame replacing the previous one.
/// \param delta The time delta since the last update.
@ -112,7 +116,7 @@ public:
}
/// Update the sensor frame with a gyroscope reading.
/// \brief Update the sensor frame with a gyroscope reading.
///
/// \param gyro A three-dimensional vector containing gyro readings
/// as w_x, w_y, w_z.
@ -121,14 +125,14 @@ public:
UpdateAngularOrientation(const scmp::geom::Vector<T, 3> &gyro, T delta)
{
// Ensure the delta isn't zero within a 100 μs tolerance.
assert(!scmp::WithinTolerance(delta, 0.0, 0.0001));
assert(!scmp::WithinTolerance<T>(delta, 0.0, 0.0001));
scmp::geom::Quaternion<T> q = this->AngularRate(gyro) * delta;
this->UpdateFrame(this->sensorFrame + q, delta);
}
/// Retrieve a vector of the Euler angles in ZYX Orientation.
/// \brief Retrieve a vector of the Euler angles in ZYX Orientation.
///
/// \return A vector of Euler angles as <ψ, θ, ϕ>.
scmp::geom::Vector<T, 3>
@ -144,11 +148,11 @@ private:
};
/// Madgwickd is a shorthand alias for a Madgwick<double>.
typedef Madgwick<double> Madgwickd;
/// \brief Madgwickd is a shorthand alias for a Madgwick<double>.
using Madgwickd = Madgwick<double>;
/// Madgwickf is a shorthand alias for a Madgwick<float>.
typedef Madgwick<float> Madgwickf;
/// \brief Madgwickf is a shorthand alias for a Madgwick<float>.
using Madgwickf = Madgwick<float>;
} // namespace filter

33
include/scmp/scmp.h Normal file
View File

@ -0,0 +1,33 @@
///
/// \file include/scmp/scmp.h
/// \author K. Isom <kyle@imap.cc>
/// \date 2023-10-19
/// \brief Aggregated scmp include header.
///
/// Copyright 2023 K. Isom <kyle@imap.cc>
///
/// Permission to use, copy, modify, and/or distribute this software for
/// any purpose with or without fee is hereby granted, provided that
/// the above copyright notice and this permission notice appear in all /// copies.
///
/// THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL
/// WARRANTIES WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED
/// WARRANTIES OF MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE
/// AUTHOR BE LIABLE FOR ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL
/// DAMAGES OR ANY DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA
/// OR PROFITS, WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER
/// TORTIOUS ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR
/// PERFORMANCE OF THIS SOFTWARE.
///
#ifndef SCSL_SCMP_H
#define SCSL_SCMP_H
/// \brief Shimmering Clarity Math & Physics toolkit.
namespace scmp {
} // namespace scmp
#endif //SCSL_SCMP_H

View File

@ -21,12 +21,6 @@
/// TORTIOUS ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR
/// PERFORMANCE OF THIS SOFTWARE.
///
/// \section PLATFORM SUPPORT
///
/// Arena will build on the major platforms, but memory-mapped files are only
/// supported on Unix-like systems. File I/O on Windows, for example, reads the
/// file into an allocated arena. See Arena::Open for more details.
#ifndef KIMODEM_ARENA_H
#define KIMODEM_ARENA_H

View File

@ -35,16 +35,11 @@ namespace sctest {
#define SCTEST_CHECK_FALSE(x) if ((x)) { return false; }
#define SCTEST_CHECK_EQ(x, y) if ((x) != (y)) { return false; }
#define SCTEST_CHECK_NE(x, y) if ((x) == (y)) { return false; }
#define SCTEST_CHECK_ZERO(x) if ((x) != 0) { return false; }
#define SCTEST_CHECK_GTZ(x) if ((x) > 0) { return false; }
#define SCTEST_CHECK_GEZ(x) if ((x) >= 0) { return false; }
#define SCTEST_CHECK_LEZ(x) if ((x) <= 0) { return false; }
#define SCTEST_CHECK_LTZ(x) if ((x) < 0) { return false; }
#define SCTEST_CHECK_FEQ(x, y) { float eps; scmp::DefaultEpsilon(eps); if (!scmp::WithinTolerance((x), (y), eps)) { return false; }}
#define SCTEST_CHECK_DEQ(x, y) { double eps; scmp::DefaultEpsilon(eps); if (!scmp::WithinTolerance((x), (y), eps)) { return false; }}
#define SCTEST_CHECK_FEQ_EPS(x, y, eps) { if (!scmp::WithinTolerance((x), (y), eps)) { return false; }}
#define SCTEST_CHECK_DEQ_EPS(x, y, eps) { if (!scmp::WithinTolerance((x), (y), eps)) { return false; }}
#define SCTEST_CHECK_FEQ_EPS(x, y, eps) { if (!scmp::WithinTolerance<float>((x), (y), eps)) { return false; }}
#define SCTEST_CHECK_DEQ_EPS(x, y, eps) { if (!scmp::WithinTolerance<double>((x), (y), eps)) { return false; }}
} // namespace sctest

View File

@ -28,21 +28,42 @@
namespace sctest {
typedef struct _Report {
// Failing stores the number of failing tests; for tests added
// with AddTest, this is a test that returned false. For tests
// added with AddFailingTest, this is a test that returned true.
size_t Failing;
// Total is the number of tests registered during the last run.
size_t Total;
class Report {
public:
/// \brief Failing returns the count of failed tests.
///
/// \details If a test is run and expected to pass, but fails,
/// it is marked as failed. If a test is expected to
/// fail, but passes, it is marked as failed.
///
/// \return The number of tests that failed.
size_t Failing() const;
std::chrono::time_point<std::chrono::steady_clock> Start;
std::chrono::time_point<std::chrono::steady_clock> End;
std::chrono::duration<double> Duration;
/// \brief Total is the number of tests registered.
size_t Total() const;
void Failed();
void AddTest(size_t testCount = 0);
void Reset(size_t testCount = 0);
void Start();
void End();
std::chrono::duration<double, std::milli>
Elapsed() const;
Report();
private:
size_t failing{};
size_t total{};
std::chrono::time_point<std::chrono::steady_clock> start;
std::chrono::time_point<std::chrono::steady_clock> end;
};
std::ostream &operator<<(std::ostream &os, const Report &report);
} // end namespace sctest
_Report();
} Report;
} // end namespace test
#endif

View File

@ -1,30 +1,28 @@
//
// Project: scccl
// File: include/test/SimpleSuite.h
// Author: Kyle Isom
// Date: 2017-06-05
// Namespace: test
//
// SimpleSuite.h defines the SimpleSuite class for unit testing.
//
// Copyright 2017 Kyle Isom <kyle@imap.cc>
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
///
/// \file SimpleSuite.h
/// \author K. Isom <kyle@imap.cc>
/// \date 2017-06-05
/// \brief Defines a simple unit testing framework.
///
/// Copyright 2017 K. Isom <kyle@imap.cc>
///
/// Permission to use, copy, modify, and/or distribute this software for
/// any purpose with or without fee is hereby granted, provided that
/// the above copyright notice and this permission notice appear in all /// copies.
///
/// THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL
/// WARRANTIES WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED
/// WARRANTIES OF MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE
/// AUTHOR BE LIABLE FOR ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL
/// DAMAGES OR ANY DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA
/// OR PROFITS, WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER
/// TORTIOUS ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR
/// PERFORMANCE OF THIS SOFTWARE.
///
#ifndef SCTEST_SIMPLESUITE_H
#define SCTEST_SIMPLESUITE_H
// SimpleSuite.h
// This header file defines the interface for a simple suite of tests.
#include <functional>
#include <string>
@ -34,54 +32,91 @@
namespace sctest {
typedef struct {
std::string name;
std::function<bool(void)> test;
} TestCase;
/// \brief UnitTest describes a single unit test. It is a predicate:
/// did the test pass?
struct UnitTest {
/// What name should be shown when running tests?
std::string name;
/// This is the test function to be run.
std::function<bool()> test;
};
/// \brief SimpleSuite is a test-running harness for simple tests.
///
/// A simple test is defined as a test that takes no arguments and
/// returns a boolean status where true indicates the test has passed.
class SimpleSuite {
public:
public:
SimpleSuite();
// Silence suppresses output.
void Silence(void) { quiet = true; }
/// \brief Silence suppresses output.
void Silence();
// Setup defines a setup function; this should be a predicate. This function
// is called at the start of the Run method, before tests are run.
/// \brief Define a suite setup function.
///
/// If present, this setup function is called at the start of
/// the Run method, before tests are run. It should be a
/// predicate: if it returns false, tests automatically fail.
void Setup(std::function<bool(void)> setupFn) { fnSetup = setupFn; }
// Teardown defines a teardown function; this should be a predicate. This
// function is called at the end of the Run method, after all tests have run.
/// \brief Define a teardown function.
///
/// If present, this teardown function is called at the end of
/// the Run method, after all tests have run.
void Teardown(std::function<bool(void)> teardownFn) { fnTeardown = teardownFn; }
// AddTest is used to add a test that is expected to return true.
void AddTest(std::string, std::function<bool(void)>);
/// \brief Register a new simple test.
///
/// \param label The text that will identify test when
/// running.
/// \param test This test should return true if the test has
/// passed.
void AddTest(std::string label, std::function<bool(void)> test);
// AddFailingTest is used to add a test that is expected to return false.
void AddFailingTest(std::string, std::function<bool(void)>);
/// \brief Register a test that is expected to return false.
///
/// \param label The text that will identify test when
/// running.
/// \param test This test should return false if the test has
/// passed.
void AddFailingTest(std::string label, std::function<bool(void)> test);
bool Run(void);
/// \brief Run all the registered tests.
///
/// \return True if all tests have passed.
bool Run();
// Reporting methods.
/// Reporting methods.
// Reset clears the report statistics.
void Reset(void) { report.Failing = report.Total = 0; hasRun = false; };
/// \brief Reset clears the report statistics.
///
/// Reset will preserve the setup and teardown functions, just
/// resetting the suite's internal state.
void Reset();
// IsReportReady returns true if a report is ready.
bool IsReportReady(void) { return hasRun; }
/// \brief
// HasRun returns true if a report is ready.
bool HasRun() const;
// Report returns a Report.
Report GetReport(void);
private:
private:
bool quiet;
std::function<bool(void)> fnSetup, fnTeardown;
std::vector<TestCase> tests;
std::function<bool(void)> fnSetup, fnTeardown;
std::vector<UnitTest> tests;
// Report functions.
Report report;
bool hasRun; // Have the tests been run yet?
Report report;
bool hasRun; // Have the tests been run yet?
bool hasPassed;
};
} // end namespace test
std::ostream& operator<<(std::ostream& os, SimpleSuite &suite);
} // namespace sctest
#endif

View File

@ -109,12 +109,19 @@ Buffer::Append(const std::string s)
bool
Buffer::Append(const uint8_t *data, const size_t datalen)
{
if (datalen == 0) {
return false;
}
auto resized = false;
auto newCap = this->mustGrow(datalen);
if (newCap > 0) {
this->Resize(newCap);
resized = true;
} else if (this->contents == nullptr) {
this->Resize(this->capacity);
resized = true;
}
assert(this->contents != nullptr);

View File

@ -22,16 +22,96 @@
/// PERFORMANCE OF THIS SOFTWARE.
#include <chrono>
#include <iomanip>
#include <ostream>
#include <sctest/Report.h>
namespace sctest {
_Report::_Report()
: Failing (0), Total(0), Start(std::chrono::steady_clock::now()),
End(std::chrono::steady_clock::now()), Duration(0) {}
Report::Report()
{
this->Reset(0);
}
} // end namespace test
size_t
Report::Failing() const
{
return this->failing;
}
size_t
Report::Total() const
{
return this->total;
}
void
Report::Failed()
{
this->failing++;
}
void
Report::AddTest(size_t testCount)
{
this->total += testCount;
}
void
Report::Reset(size_t testCount)
{
auto now = std::chrono::steady_clock::now();
this->total = testCount;
this->failing = 0;
this->Start();
this->end = now;
}
void
Report::Start()
{
this->start = std::chrono::steady_clock::now();
}
void
Report::End()
{
this->end = std::chrono::steady_clock::now();
}
std::chrono::duration<double, std::milli>
Report::Elapsed() const
{
return this->end - this->start;
}
std::ostream&
operator<<(std::ostream &os, const Report &report)
{
auto elapsed = report.Elapsed();
os << report.Total() - report.Failing() << "/"
<< report.Total() << " tests passed in "
<< std::setw(3) << elapsed.count() << "ms";
return os;
}
} // end namespace sctest

View File

@ -20,7 +20,6 @@
/// PERFORMANCE OF THIS SOFTWARE.
///
#include <chrono>
#include <iostream>
#include <sctest/SimpleSuite.h>
@ -39,14 +38,22 @@ SimpleSuite::SimpleSuite()
: quiet(false), fnSetup(stub), fnTeardown(stub), tests(),
report(), hasRun(false)
{
this->Reset();
}
void
SimpleSuite::Silence()
{
// Silence will fall.
quiet = true;
}
void
SimpleSuite::AddTest(std::string name, std::function<bool()> test)
{
TestCase test_case = {name, test};
UnitTest const test_case = {name, test};
tests.push_back(test_case);
}
@ -55,7 +62,7 @@ void
SimpleSuite::AddFailingTest(std::string name, std::function<bool()> test)
{
// auto ntest = [&test]() { return !test(); };
TestCase test_case = {name, [&test]() { return !test(); }};
UnitTest test_case = {name, [&test]() { return !test(); }};
tests.push_back(test_case);
}
@ -63,38 +70,55 @@ SimpleSuite::AddFailingTest(std::string name, std::function<bool()> test)
bool
SimpleSuite::Run()
{
report.Start = std::chrono::steady_clock::now();
report.Reset(this->tests.size());
unless(quiet) { std::cout << "Setting up the tests.\n"; }
unless(fnSetup()) { return false; }
// Reset the failed test counts.
report.Failing = 0;
this->hasRun = true;
this->hasPassed = true;
bool result = true;
hasRun = true;
report.Total = tests.size();
for (size_t i = 0; i < report.Total && result; i++) {
TestCase tc = tests.at(i);
for (size_t i = 0; i < this->report.Total() && this->hasPassed; i++) {
const UnitTest testCase = this->tests.at(i);
unless(quiet) {
std::cout << "[" << i + 1 << "/" << report.Total << "] Running test " << tc.name << ": ";
std::cout << "[" << i + 1 << "/"
<< this -> report.Total()
<< "] Running test "
<< testCase.name << ": ";
}
result = tc.test();
this->hasPassed = testCase.test();
if (quiet) { continue; }
if (result) {
if (this->hasPassed) {
std::cout << "[PASS]";
} else {
std::cout << "[FAIL]";
report.Failing++;
report.Failed();
}
std::cout << "\n";
}
unless(quiet) { std::cout << "Tearing down the tests.\n"; }
unless(fnTeardown()) { return false; }
report.End = std::chrono::steady_clock::now();
return result;
report.End();
return this->hasPassed;
}
void
SimpleSuite::Reset()
{
this->report.Reset(0);
this->hasRun = false;
this->hasPassed = false;
}
bool
SimpleSuite::HasRun() const
{
return this->hasRun;
}
@ -105,4 +129,17 @@ SimpleSuite::GetReport()
}
std::ostream &
operator<<(std::ostream &os, SimpleSuite &suite)
{
if (suite.HasRun()) {
os << "OK: " << suite.GetReport();
} else {
os << "Test suite hasn't run.";
}
return os;
}
} // end namespace sctest

View File

@ -25,21 +25,23 @@
#include <scmp/Math.h>
#include <scmp/geom/Coord2D.h>
#include <sctest/SimpleSuite.h>
#include <sctest/Checks.h>
#include <sctest/SimpleSuite.h>
using namespace scmp::geom;
using namespace sctest;
namespace {
#define CHECK_ROTATE(theta, expected) if (!scmp::WithinTolerance(scmp::RotateRadians((double)theta, 0), (double)expected, (double)0.0001)) { \
std::cerr << "Expected " << theta << " to wrap to " << expected << std::endl; \
std::cerr << " have " << scmp::RotateRadians(theta, 0) << std::endl; \
std::cerr << "Expected " << theta << " to wrap to " << expected << "\n"; \
std::cerr << " have " << scmp::RotateRadians(theta, 0) << "\n"; \
return false; \
}
static bool
geom_validate_angular_rotation(void)
bool
geomValidateAngularRotation()
{
CHECK_ROTATE(0, 0);
CHECK_ROTATE(M_PI/4, M_PI/4);
@ -54,17 +56,18 @@ geom_validate_angular_rotation(void)
return true;
}
static bool
geom_conversion_identities(void)
bool
geomConversionIdentities()
{
Point2D points[4] = {
const std::array<Point2D,4> points = {
Point2D(1, 0),
Point2D(0, 1),
Point2D(-1, 0),
Point2D(0, -1)
};
Polar2D polars[4] = {
const std::array<Polar2D,4> polars = {
Polar2D(1, 0),
Polar2D(1, scmp::DegreesToRadiansD(90)),
Polar2D(1, scmp::DegreesToRadiansD(180)),
@ -72,92 +75,103 @@ geom_conversion_identities(void)
};
for (auto i = 0; i < 4; i++) {
Polar2D pol(points[i]);
if (pol != polars[i]) {
std::cerr << "! measured value outside tolerance (" << i << ")" << std::endl;
std::cerr << " " << points[i] << "" << pol << "" << polars[i] << std::endl;
const Polar2D pol(points.at(i));
if (pol != polars.at(i)) {
std::cerr << "! measured value outside tolerance ("
<< i << ")\n";
std::cerr << " " << points.at(i) << "" << pol
<< "" << polars.at(i) << "\n";
return false;
}
Point2D pt(pol);
SCTEST_CHECK(pt == points[i]);
const Point2D point(pol);
SCTEST_CHECK(point == points.at(i));
}
return true;
}
static bool
geom_verify_basic_properties(void)
{
Point2D p1(1, 1);
Point2D p2(2, 2);
Point2D p3(3, 3);
SCTEST_CHECK((p1 + p2) == p3);
SCTEST_CHECK((p3 - p2) == p1);
bool
geomVerifyBasicProperties()
{
const Point2D pt1(1, 1);
const Point2D pt2(2, 2);
const Point2D pt3(3, 3);
SCTEST_CHECK((pt1 + pt2) == pt3);
SCTEST_CHECK((pt3 - pt2) == pt1);
// commutative
SCTEST_CHECK((p1 + p2) == (p2 + p1));
SCTEST_CHECK((p1 + p3) == (p3 + p1));
SCTEST_CHECK((p2 + p3) == (p3 + p2));
SCTEST_CHECK((pt1 + pt2) == (pt2 + pt1));
SCTEST_CHECK((pt1 + pt3) == (pt3 + pt1));
SCTEST_CHECK((pt2 + pt3) == (pt3 + pt2));
// associative
SCTEST_CHECK(((p1 + p2) + p3) == (p1 + (p2 + p3)));
SCTEST_CHECK(((pt1 + pt2) + pt3) == (pt1 + (pt2 + pt3)));
// transitive
Point2D p4(1, 1);
Point2D p5(1, 1);
SCTEST_CHECK(p1 == p4);
SCTEST_CHECK(p4 == p5);
SCTEST_CHECK(p1 == p5);
const Point2D pt4(1, 1);
const Point2D pt5(1, 1);
SCTEST_CHECK(pt1 == pt4);
SCTEST_CHECK(pt4 == pt5);
SCTEST_CHECK(pt1 == pt5);
// scaling
Point2D p6(2, 3);
Point2D p7(8, 12);
SCTEST_CHECK((p6 * 4) == p7);
const Point2D pt6(2, 3);
const Point2D pt7(8, 12);
SCTEST_CHECK((pt6 * 4) == pt7);
return true;
}
static bool
geom_compare_point2d(void)
{
Point2D p1(1, 1);
Point2D p2(1, 1);
Point2D p3(0, 1);
SCTEST_CHECK(p1 == p2);
SCTEST_CHECK_FALSE(p2 == p3);
bool
geomComparePoint2D()
{
const Point2D pt1(1, 1);
const Point2D pt2(1, 1);
const Point2D pt3(0, 1);
SCTEST_CHECK(pt1 == pt2);
SCTEST_CHECK_FALSE(pt2 == pt3);
return true;
}
static bool
geom_rotate_point2d(void)
bool
geomRotatePoint2D()
{
Point2D vertices[4] = {
std::array<Point2D, 4> vertices = {
Point2D(1, 0), // θ = 0
Point2D(0, 1), // θ = π/2
Point2D(-1, 0), // θ = π
Point2D(0, -1) // θ = 3π/2
};
Point2D vertex;
vertices[0].Rotate(vertex, 1.5708);
for (auto i = 0; i < 4; i++) {
auto first = i % 4;
auto expected = (i + 1) % 4;
if (vertex != vertices[1]) {
std::cerr << "expected: " << vertices[1] << std::endl;
std::cerr << " have: " << vertex << std::endl;
return false;
Point2D vertex;
vertices.at(first).Rotate(vertex, 1.5708);
if (vertex != vertices.at(expected)) {
std::cerr << "expected: " << expected << "\n";
std::cerr << " have: " << vertex << "\n";
return false;
}
}
return true;
}
static bool
geom_rotate_points_about_origin(void)
bool
geomRotatePointsAboutOrigin()
{
Point2D origin(3, 3);
double theta = 0;
std::vector<Polar2D> vertices {
const std::vector<Polar2D> vertices {
Polar2D(2, 0),
Polar2D(1.41421, 2.35619),
Polar2D(1.41421, -2.35619)
@ -203,25 +217,22 @@ geom_rotate_points_about_origin(void)
return true;
}
} // anonymous namespace
int
main(void)
main()
{
SimpleSuite ts;
ts.AddTest("geom_validate_angular_rotation", geom_validate_angular_rotation);
ts.AddTest("geom_conversion_identities", geom_conversion_identities);
ts.AddTest("geom_verify_basic_properties", geom_verify_basic_properties);
ts.AddTest("geom_compare_point2d", geom_compare_point2d);
ts.AddTest("geom_rotate_point2d", geom_rotate_point2d);
ts.AddTest("geom_rotate_points_about_origin", geom_rotate_points_about_origin);
SimpleSuite suite;
suite.AddTest("geomValidateAngularRotation", geomValidateAngularRotation);
suite.AddTest("geomConversionIdentities", geomConversionIdentities);
suite.AddTest("geomVerifyBasicProperties", geomVerifyBasicProperties);
suite.AddTest("geomComparePoint2D", geomComparePoint2D);
suite.AddTest("geomRotatePoint2D", geomRotatePoint2D);
suite.AddTest("geomRotatePointsAboutOrigin", geomRotatePointsAboutOrigin);
if (ts.Run()) {
std::cout << "OK" << std::endl;
return 0;
}
else {
auto r = ts.GetReport();
std::cerr << r.Failing << "/" << r.Total << " tests failed." << std::endl;
return 1;
}
auto result = suite.Run();
std::cout << suite << "\n";
return result ? 0 : 1;
}

View File

@ -15,23 +15,157 @@ using namespace scmp;
bool
SimpleAngularOrientation()
SimpleAngularOrientationFloat()
{
filter::Madgwickd mf;
geom::Vector3d gyro{0.174533, 0.0, 0.0}; // 10° X rotation.
geom::Quaterniond frame20Deg{0.984808, 0.173648, 0, 0}; // 20° final Orientation.
double delta = 0.00917; // assume 109 updates per second, as per the paper.
double twentyDegrees = scmp::DegreesToRadiansD(20.0);
filter::Madgwickf mflt;
const geom::Vector3f gyro{0.174533, 0.0, 0.0}; // 10° X rotation.
const geom::Quaternionf frame20Deg{0.984808, 0.173648, 0, 0}; // 20° final Orientation.
const float delta = 0.00917; // assume 109 updates per second, as per the paper.
const float twentyDegrees = scmp::DegreesToRadiansF(20.0);
// The paper specifies a minimum of 109 IMU readings to stabilize; for
// two seconds, that means 218 updates.
for (int i = 0; i < 218; i++) {
mf.UpdateAngularOrientation(gyro, delta);
mflt.UpdateAngularOrientation(gyro, delta);
}
SCTEST_CHECK_EQ(mf.Orientation(), frame20Deg);
SCTEST_CHECK_EQ(mflt.Orientation(), frame20Deg);
auto euler = mf.Euler();
auto euler = mflt.Euler();
SCTEST_CHECK_FEQ_EPS(euler[0], twentyDegrees, 0.01);
SCTEST_CHECK_FEQ_EPS(euler[1], 0.0, 0.01);
SCTEST_CHECK_FEQ_EPS(euler[2], 0.0, 0.01);
return true;
}
bool
SimpleAngularOrientationDouble()
{
filter::Madgwickd mflt;
const geom::Vector3d gyro{0.174533, 0.0, 0.0}; // 10° X rotation.
const geom::Quaterniond frame20Deg{0.984808, 0.173648, 0, 0}; // 20° final Orientation.
const double delta = 0.00917; // assume 109 updates per second, as per the paper.
const double twentyDegrees = scmp::DegreesToRadiansD(20.0);
// The paper specifies a minimum of 109 IMU readings to stabilize; for
// two seconds, that means 218 updates.
for (int i = 0; i < 218; i++) {
mflt.UpdateAngularOrientation(gyro, delta);
}
SCTEST_CHECK_EQ(mflt.Orientation(), frame20Deg);
auto euler = mflt.Euler();
SCTEST_CHECK_DEQ_EPS(euler[0], twentyDegrees, 0.01);
SCTEST_CHECK_DEQ_EPS(euler[1], 0.0, 0.01);
SCTEST_CHECK_DEQ_EPS(euler[2], 0.0, 0.01);
return true;
}
bool
SimpleAngularOrientation2InitialVector3f()
{
const geom::Vector3f initialFrame{0, 0, 0};
filter::Madgwickf mflt(initialFrame);
const geom::Vector3f gyro{0.174533, 0.0, 0.0}; // 10° X rotation.
const geom::Quaternionf frame20Deg{0.984808, 0.173648, 0, 0}; // 20° final Orientation.
const float delta = 0.00917; // assume 109 updates per second, as per the paper.
const float twentyDegrees = scmp::DegreesToRadiansF(20.0);
// The paper specifies a minimum of 109 IMU readings to stabilize; for
// two seconds, that means 218 updates.
for (int i = 0; i < 218; i++) {
mflt.UpdateAngularOrientation(gyro, delta);
}
SCTEST_CHECK_EQ(mflt.Orientation(), frame20Deg);
auto euler = mflt.Euler();
SCTEST_CHECK_FEQ_EPS(euler[0], twentyDegrees, 0.01);
SCTEST_CHECK_FEQ_EPS(euler[1], 0.0, 0.01);
SCTEST_CHECK_FEQ_EPS(euler[2], 0.0, 0.01);
return true;
}
bool
SimpleAngularOrientation2InitialQuaternionf()
{
const auto initialFrame = geom::quaternionf_from_euler({0, 0, 0});
filter::Madgwickf mflt(initialFrame);
const geom::Vector3f gyro{0.174533, 0.0, 0.0}; // 10° X rotation.
const geom::Quaternionf frame20Deg{0.984808, 0.173648, 0, 0}; // 20° final Orientation.
const float delta = 0.00917; // assume 109 updates per second, as per the paper.
const float twentyDegrees = scmp::DegreesToRadiansF(20.0);
// The paper specifies a minimum of 109 IMU readings to stabilize; for
// two seconds, that means 218 updates.
for (int i = 0; i < 218; i++) {
mflt.UpdateAngularOrientation(gyro, delta);
}
SCTEST_CHECK_EQ(mflt.Orientation(), frame20Deg);
auto euler = mflt.Euler();
SCTEST_CHECK_FEQ_EPS(euler[0], twentyDegrees, 0.01);
SCTEST_CHECK_FEQ_EPS(euler[1], 0.0, 0.01);
SCTEST_CHECK_FEQ_EPS(euler[2], 0.0, 0.01);
return true;
}
bool
SimpleAngularOrientation2InitialVector3d()
{
const geom::Vector3d initialFrame{0, 0, 0};
filter::Madgwickd mflt(initialFrame);
const geom::Vector3d gyro{0.174533, 0.0, 0.0}; // 10° X rotation.
const geom::Quaterniond frame20Deg{0.984808, 0.173648, 0, 0}; // 20° final Orientation.
const double delta = 0.00917; // assume 109 updates per second, as per the paper.
const double twentyDegrees = scmp::DegreesToRadiansD(20.0);
// The paper specifies a minimum of 109 IMU readings to stabilize; for
// two seconds, that means 218 updates.
for (int i = 0; i < 218; i++) {
mflt.UpdateAngularOrientation(gyro, delta);
}
SCTEST_CHECK_EQ(mflt.Orientation(), frame20Deg);
auto euler = mflt.Euler();
SCTEST_CHECK_DEQ_EPS(euler[0], twentyDegrees, 0.01);
SCTEST_CHECK_DEQ_EPS(euler[1], 0.0, 0.01);
SCTEST_CHECK_DEQ_EPS(euler[2], 0.0, 0.01);
return true;
}
bool
SimpleAngularOrientation2InitialQuaterniond()
{
const auto initialFrame = geom::quaterniond_from_euler({0, 0, 0});
filter::Madgwickd mflt(initialFrame);
const geom::Vector3d gyro{0.174533, 0.0, 0.0}; // 10° X rotation.
const geom::Quaterniond frame20Deg{0.984808, 0.173648, 0, 0}; // 20° final Orientation.
const double delta = 0.00917; // assume 109 updates per second, as per the paper.
const double twentyDegrees = scmp::DegreesToRadiansD(20.0);
// The paper specifies a minimum of 109 IMU readings to stabilize; for
// two seconds, that means 218 updates.
for (int i = 0; i < 218; i++) {
mflt.UpdateAngularOrientation(gyro, delta);
}
SCTEST_CHECK_EQ(mflt.Orientation(), frame20Deg);
auto euler = mflt.Euler();
SCTEST_CHECK_DEQ_EPS(euler[0], twentyDegrees, 0.01);
SCTEST_CHECK_DEQ_EPS(euler[1], 0.0, 0.01);
SCTEST_CHECK_DEQ_EPS(euler[2], 0.0, 0.01);
@ -43,21 +177,27 @@ SimpleAngularOrientation()
int
main(int argc, char **argv)
{
(void)argc;
(void)argv;
sctest::SimpleSuite suite;
suite.AddTest("SimpleAngularOrientation", SimpleAngularOrientation);
suite.AddTest("SimpleAngularOrientationDouble",
SimpleAngularOrientationFloat);
suite.AddTest("SimpleAngularOrientationDouble",
SimpleAngularOrientationDouble);
suite.AddTest("SimpleAngularOrientationDouble (iniital vector3f)",
SimpleAngularOrientation2InitialVector3f);
suite.AddTest("SimpleAngularOrientationDouble (iniital vector3d)",
SimpleAngularOrientation2InitialVector3d);
suite.AddTest("SimpleAngularOrientationDouble (iniital quaternionf)",
SimpleAngularOrientation2InitialQuaternionf);
suite.AddTest("SimpleAngularOrientationDouble (iniital quaterniond)",
SimpleAngularOrientation2InitialQuaterniond);
auto result = suite.Run();
if (suite.IsReportReady()) {
auto report = suite.GetReport();
std::cout << report.Failing << " / " << report.Total;
std::cout << " tests failed.\n";
}
std::cout << suite.GetReport() << "\n";
return result ? 0 : 1;
if (result) {
return 0;
}
else {
return 1;
}
}

View File

@ -1,32 +1,40 @@
#include <sctest/Checks.h>
#include <sctest/SimpleSuite.h>
#include <scsl/Flag.h>
#include <scmp/Math.h>
#include <scmp/geom/Vector.h>
#include <scmp/geom/Orientation.h>
#include <sctest/Checks.h>
#include <sctest/SimpleSuite.h>
using namespace std;
using namespace scmp;
using namespace sctest;
static bool
namespace {
bool
UnitConversions_RadiansToDegreesF()
{
for (int i = 0; i < 360; i++) {
auto deg = static_cast<float>(i);
SCTEST_CHECK_FEQ(scmp::RadiansToDegreesF(scmp::DegreesToRadiansF(deg)), deg);
auto rads = scmp::DegreesToRadiansF(i);
auto deg = scmp::RadiansToDegreesF(rads);
SCTEST_CHECK_FEQ(deg, static_cast<float>(i));
}
return true;
}
static bool
bool
UnitConversions_RadiansToDegreesD()
{
for (int i = 0; i < 360; i++) {
auto deg = static_cast<double>(i);
auto deg = static_cast<double>(i);
SCTEST_CHECK_DEQ(scmp::RadiansToDegreesD(scmp::DegreesToRadiansD(deg)), deg);
}
@ -34,10 +42,10 @@ UnitConversions_RadiansToDegreesD()
}
static bool
bool
Orientation2f_Heading()
{
geom::Vector2f a {2.0, 2.0};
geom::Vector2f a{2.0, 2.0};
SCTEST_CHECK_FEQ(geom::Heading2f(a), scmp::DegreesToRadiansF(45));
@ -45,10 +53,10 @@ Orientation2f_Heading()
}
static bool
bool
Orientation3f_Heading()
{
geom::Vector3f a {2.0, 2.0, 2.0};
geom::Vector3f a{2.0, 2.0, 2.0};
SCTEST_CHECK_FEQ(geom::Heading3f(a), scmp::DegreesToRadiansF(45));
@ -56,43 +64,56 @@ Orientation3f_Heading()
}
static bool
bool
Orientation2d_Heading()
{
geom::Vector2d a {2.0, 2.0};
geom::Vector2d a{2.0, 2.0};
return scmp::WithinTolerance(geom::Heading2d(a), scmp::DegreesToRadiansD(45), 0.000001);
return scmp::WithinTolerance(geom::Heading2d(a), scmp::DegreesToRadiansD(45), 0.000001);
}
static bool
bool
Orientation3d_Heading()
{
geom::Vector3d a {2.0, 2.0, 2.0};
geom::Vector3d a{2.0, 2.0, 2.0};
return scmp::WithinTolerance(geom::Heading3d(a), scmp::DegreesToRadiansD(45), 0.000001);
}
} // anonymous namespace
int
main(void)
main(int argc, char *argv[])
{
SimpleSuite ts;
auto quiet = false;
auto flags = new scsl::Flags("test_orientation",
"This test validates various orientation-related components in scmp.");
flags->Register("-q", false, "suppress test output");
ts.AddTest("UnitConversions_RadiansToDegreesF", UnitConversions_RadiansToDegreesF);
ts.AddTest("UnitConversions_RadiansToDegreesD", UnitConversions_RadiansToDegreesD);
ts.AddTest("Orientation2f_Heading", Orientation2f_Heading);
ts.AddTest("Orientation3f_Heading", Orientation3f_Heading);
ts.AddTest("Orientation2d_Heading", Orientation2d_Heading);
ts.AddTest("Orientation3d_Heading", Orientation3d_Heading);
auto parsed = flags->Parse(argc, argv);
if (parsed != scsl::Flags::ParseStatus::OK) {
std::cerr << "Failed to parse flags: "
<< scsl::Flags::ParseStatusToString(parsed) << "\n";
}
if (ts.Run()) {
std::cout << "OK" << std::endl;
return 0;
}
else {
auto r = ts.GetReport();
std::cerr << r.Failing << "/" << r.Total << " tests failed." << std::endl;
return 1;
SimpleSuite suite;
flags->GetBool("-q", quiet);
if (quiet) {
suite.Silence();
}
suite.AddTest("UnitConversions_RadiansToDegreesF", UnitConversions_RadiansToDegreesF);
suite.AddTest("UnitConversions_RadiansToDegreesD", UnitConversions_RadiansToDegreesD);
suite.AddTest("Orientation2f_Heading", Orientation2f_Heading);
suite.AddTest("Orientation3f_Heading", Orientation3f_Heading);
suite.AddTest("Orientation2d_Heading", Orientation2d_Heading);
suite.AddTest("Orientation3d_Heading", Orientation3d_Heading);
delete flags;
auto result = suite.Run();
std::cout << suite.GetReport() << "\n";
return result ? 0 : 1;
}

View File

@ -429,49 +429,43 @@ QuaternionMiscellanous_InitializerConstructor()
int
main(void)
{
SimpleSuite ts;
SimpleSuite suite;
ts.AddTest("Quaternion_SelfTest", Quaternion_SelfTest);
ts.AddTest("QuaternionMiscellanous_InitializerConstructor",
QuaternionMiscellanous_InitializerConstructor);
ts.AddTest("QuaternionMiscellaneous_SanityChecks",
QuaternionMiscellaneous_SanityChecks);
ts.AddTest("QuaternionMiscellaneous_OutputStream",
QuaternionMiscellaneous_OutputStream);
suite.AddTest("Quaternion_SelfTest", Quaternion_SelfTest);
suite.AddTest("QuaternionMiscellanous_InitializerConstructor",
QuaternionMiscellanous_InitializerConstructor);
suite.AddTest("QuaternionMiscellaneous_SanityChecks",
QuaternionMiscellaneous_SanityChecks);
suite.AddTest("QuaternionMiscellaneous_OutputStream",
QuaternionMiscellaneous_OutputStream);
ts.AddTest("Quaterniond_Addition", Quaterniond_Addition);
ts.AddTest("Quaterniond_Conjugate", Quaterniond_Conjugate);
ts.AddTest("Quaterniond_Euler", Quaterniond_Euler);
ts.AddTest("Quaterniond_Identity", Quaterniond_Identity);
ts.AddTest("Quaterniond_Inverse", Quaterniond_Inverse);
ts.AddTest("Quaterniond_Norm", Quaterniond_Norm);
ts.AddTest("Quaterniond_Product", Quaterniond_Product);
ts.AddTest("Quaterniond_Rotate", Quaterniond_Rotate);
ts.AddTest("Quaterniond_ShortestSLERP", Quaterniond_ShortestSLERP);
ts.AddTest("Quaterniond_ShortestSLERP2", Quaterniond_ShortestSLERP2);
ts.AddTest("Quaterniond_Unit", Quaterniond_Unit);
ts.AddTest("Quaterniond_UtilityCreator", Quaterniond_UtilityCreator);
suite.AddTest("Quaterniond_Addition", Quaterniond_Addition);
suite.AddTest("Quaterniond_Conjugate", Quaterniond_Conjugate);
suite.AddTest("Quaterniond_Euler", Quaterniond_Euler);
suite.AddTest("Quaterniond_Identity", Quaterniond_Identity);
suite.AddTest("Quaterniond_Inverse", Quaterniond_Inverse);
suite.AddTest("Quaterniond_Norm", Quaterniond_Norm);
suite.AddTest("Quaterniond_Product", Quaterniond_Product);
suite.AddTest("Quaterniond_Rotate", Quaterniond_Rotate);
suite.AddTest("Quaterniond_ShortestSLERP", Quaterniond_ShortestSLERP);
suite.AddTest("Quaterniond_ShortestSLERP2", Quaterniond_ShortestSLERP2);
suite.AddTest("Quaterniond_Unit", Quaterniond_Unit);
suite.AddTest("Quaterniond_UtilityCreator", Quaterniond_UtilityCreator);
ts.AddTest("Quaternionf_Addition", Quaternionf_Addition);
ts.AddTest("Quaternionf_Conjugate", Quaternionf_Conjugate);
ts.AddTest("Quaternionf_Euler", Quaternionf_Euler);
ts.AddTest("Quaternionf_Identity", Quaternionf_Identity);
ts.AddTest("Quaternionf_Inverse", Quaternionf_Inverse);
ts.AddTest("Quaternionf_Norm", Quaternionf_Norm);
ts.AddTest("Quaternionf_Product", Quaternionf_Product);
ts.AddTest("Quaternionf_Rotate", Quaternionf_Rotate);
ts.AddTest("Quaternionf_ShortestSLERP", Quaternionf_ShortestSLERP);
ts.AddTest("Quaternionf_ShortestSLERP2", Quaternionf_ShortestSLERP2);
ts.AddTest("Quaternionf_Unit", Quaternionf_Unit);
ts.AddTest("Quaternionf_UtilityCreator", Quaternionf_UtilityCreator);
suite.AddTest("Quaternionf_Addition", Quaternionf_Addition);
suite.AddTest("Quaternionf_Conjugate", Quaternionf_Conjugate);
suite.AddTest("Quaternionf_Euler", Quaternionf_Euler);
suite.AddTest("Quaternionf_Identity", Quaternionf_Identity);
suite.AddTest("Quaternionf_Inverse", Quaternionf_Inverse);
suite.AddTest("Quaternionf_Norm", Quaternionf_Norm);
suite.AddTest("Quaternionf_Product", Quaternionf_Product);
suite.AddTest("Quaternionf_Rotate", Quaternionf_Rotate);
suite.AddTest("Quaternionf_ShortestSLERP", Quaternionf_ShortestSLERP);
suite.AddTest("Quaternionf_ShortestSLERP2", Quaternionf_ShortestSLERP2);
suite.AddTest("Quaternionf_Unit", Quaternionf_Unit);
suite.AddTest("Quaternionf_UtilityCreator", Quaternionf_UtilityCreator);
if (ts.Run()) {
std::cout << "OK" << std::endl;
return 0;
}
else {
auto r = ts.GetReport();
std::cerr << r.Failing << "/" << r.Total << " tests failed." << std::endl;
return 1;
}
auto result = suite.Run();
std::cout << suite.GetReport() << "\n";
return result ? 0 : 1;
}

View File

@ -1,30 +1,33 @@
//
// Project: scccl
// File: test/math/simple_suite_example.cpp
// Author: Kyle Isom
// Date: 2017-06-05
//
// simple_suite_example demonstrates the usage of the SimpleSuite test class
// and serves to unit test the unit tester (qui custodiet ipsos custodes)?
//
// Copyright 2017 Kyle Isom <kyle@imap.cc>
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
///
/// \file test/simple_suite_example.cc
/// \author K. Isom <kyle@imap.cc>
/// \date 2017-06-05
///
/// simple_suite_example demonstrates the usage of the SimpleSuite test class
/// and serves to unit test the unit tester (qui custodiet ipsos custodes)?
///
///
/// Copyright 2017 K. Isom <kyle@imap.cc>
///
/// Permission to use, copy, modify, and/or distribute this software for
/// any purpose with or without fee is hereby granted, provided that the
/// above copyright notice and this permission notice appear in all copies.
///
/// THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL
/// WARRANTIES WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED
/// WARRANTIES OF MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR
/// BE LIABLE FOR ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES
/// OR ANY DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS,
/// WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION,
/// ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS
/// SOFTWARE.
///
#include <iostream>
#include <sctest/SimpleSuite.h>
static bool
prepareTests()
{
@ -33,6 +36,7 @@ prepareTests()
return true;
}
static bool
destroyTests()
{
@ -41,6 +45,7 @@ destroyTests()
return true;
}
static bool addOne() { return 1 + 1 == 2; }
static bool four() { return 2 + 2 == 4; }
static bool nope() { return 2 + 2 == 5; }
@ -49,24 +54,14 @@ static bool nope() { return 2 + 2 == 5; }
int
main()
{
sctest::SimpleSuite TestSuite;
TestSuite.Setup(prepareTests);
TestSuite.Teardown(destroyTests);
TestSuite.AddTest("1 + 1", addOne);
TestSuite.AddTest("fourness", four);
TestSuite.AddFailingTest("self-evident truth", nope);
sctest::SimpleSuite suite;
suite.Setup(prepareTests);
suite.Teardown(destroyTests);
suite.AddTest("1 + 1", addOne);
suite.AddTest("fourness", four);
suite.AddFailingTest("self-evident truth", nope);
auto result = suite.Run();
bool result = TestSuite.Run();
if (TestSuite.IsReportReady()) {
auto report = TestSuite.GetReport();
std::cout << report.Failing << " / " << report.Total;
std::cout << " tests failed.\n";
}
if (result) {
return 0;
}
else {
return 1;
}
std::cout << suite.GetReport() << "\n";
return result ? 0 : 1;
}

View File

@ -1,5 +1,5 @@
///
/// \file stringutil_test.cc
/// \file test/stringutil_test.cc
/// \author kyle
/// \date 10/14/23
/// \brief Ensure the stringutil functions work.
@ -21,17 +21,21 @@
///
#include <functional>
#include <iostream>
#include <sstream>
#include <scsl/StringUtil.h>
#include <sctest/Assert.h>
#include <sctest/SimpleSuite.h>
using namespace scsl;
static void
namespace {
void
TestTrimming(std::string line, std::string lExpected, std::string rExpected, std::string expected)
{
std::string result;
@ -66,42 +70,17 @@ TestTrimming(std::string line, std::string lExpected, std::string rExpected, std
}
static std::string
vec2string(std::vector<std::string> v)
{
std::stringstream ss;
ss << "(";
ss << v.size();
ss << ")";
ss << "{";
for (size_t i = 0; i < v.size(); i++) {
if (i > 0) { ss << ", "; }
ss << v[i];
}
ss << "}";
return ss.str();
}
static void
std::function<bool()>
TestSplit(std::string line, std::string delim, size_t maxCount, std::vector<std::string> expected)
{
std::cout << "test split\n";
std::cout << "\t line: \"" << line << "\"\n";
std::cout << "\t delim: \"" << delim << "\"\n";
std::cout << "\t count: " << maxCount << "\n";
std::cout << "\texpect: " << vec2string(expected) << "\n";
auto result = U::S::SplitN(line, delim, maxCount);
std::cout << "\tresult: " << U::S::VectorToString(result) << "\n";
sctest::Assert(result == expected, U::S::VectorToString(result));
std::cout << "OK!\n";
return [line, delim, maxCount, expected]() {
return U::S::SplitN(line, delim, maxCount) == expected;
};
}
static void
bool
TestWrapping()
{
std::string testLine = "A much longer line, something that can be tested with WrapText. ";
@ -119,34 +98,52 @@ TestWrapping()
};
auto wrapped = U::S::WrapText(testLine, 16);
sctest::Assert(wrapped.size() == expected.size(),
U::S::VectorToString(wrapped) + " != " + U::S::VectorToString(expected));
if (wrapped.size() != expected.size()) {
std::cerr << U::S::VectorToString(wrapped)
<< " != "
<< U::S::VectorToString(expected)
<< "\n";
}
for (size_t i = 0; i < wrapped.size(); i++) {
sctest::Assert(wrapped[i] == expected[i],
"\"" + wrapped[i] + "\" != \"" + expected[i] + "\"");
if (wrapped[i] == expected[i]) {
continue;
}
std::cerr << "[" << i << "] \"" << wrapped[i] << "\" != \""
<< expected[i] << "\"\n";
return false;
}
U::S::WriteTabIndented(std::cout, wrapped, 4, true);
return true;
}
} // anonymous namespace
int
main()
{
sctest::SimpleSuite suite;
TestTrimming(" foo\t ", "foo\t ", " foo", "foo");
TestTrimming(" foo\tbar ", "foo\tbar ", " foo\tbar", "foo\tbar");
TestSplit("abc:def:ghij:klm", ":", 0,
std::vector<std::string>{"abc", "def", "ghij", "klm"});
TestSplit("abc:def:ghij:klm", ":", 3,
std::vector<std::string>{"abc", "def", "ghij:klm"});
TestSplit("abc:def:ghij:klm", ":", 2,
std::vector<std::string>{"abc", "def:ghij:klm"});
TestSplit("abc:def:ghij:klm", ":", 1,
std::vector<std::string>{"abc:def:ghij:klm"});
TestSplit("abc::def:ghi", ":", 0,
std::vector<std::string>{"abc", "", "def", "ghi"});
TestWrapping();
suite.AddTest("SplitN(0)", TestSplit("abc:def:ghij:klm", ":", 0,
std::vector<std::string>{"abc", "def", "ghij", "klm"}));
suite.AddTest("SplitN(3)", TestSplit("abc:def:ghij:klm", ":", 3,
std::vector<std::string>{"abc", "def", "ghij:klm"}));
suite.AddTest("SplitN(2)", TestSplit("abc:def:ghij:klm", ":", 2,
std::vector<std::string>{"abc", "def:ghij:klm"}));
suite.AddTest("SplitN(1)", TestSplit("abc:def:ghij:klm", ":", 1,
std::vector<std::string>{"abc:def:ghij:klm"}));
suite.AddTest("SplitN(0) with empty element",
TestSplit("abc::def:ghi", ":", 0,
std::vector<std::string>{"abc", "", "def", "ghi"}));
suite.AddTest("TextWrapping", TestWrapping);
auto result = suite.Run();
std::cout << suite.GetReport() << "\n";
return result ? 0 : 1;
}

View File

@ -428,71 +428,65 @@ Vector3DoubleTests_CrossProduct()
int
main(void)
main()
{
SimpleSuite ts;
ts.AddTest("Vector3Miscellaneous_ExtractionOperator3d",
Vector3Miscellaneous_ExtractionOperator3d);
ts.AddTest("Vector3Miscellaneous_ExtractionOperator3f",
Vector3Miscellaneous_ExtractionOperator3f);
ts.AddTest("Vector3Miscellaneous_SetEpsilon",
Vector3Miscellaneous_SetEpsilon);
ts.AddTest("Vector3FloatTests_Magnitude",
Vector3FloatTests_Magnitude);
ts.AddTest("Vector3FloatTests_Equality",
Vector3FloatTests_Equality);
ts.AddTest("Vector3FloatTests_Addition",
Vector3FloatTests_Addition);
ts.AddTest("Vector3FloatTests_Subtraction",
Vector3FloatTests_Subtraction);
ts.AddTest("Vector3FloatTests_ScalarMultiplication",
Vector3FloatTests_ScalarMultiplication);
ts.AddTest("Vector3FloatTests_ScalarDivision",
Vector3FloatTests_ScalarDivision);
ts.AddTest("Vector3FloatTests_DotProduct",
Vector3FloatTests_DotProduct);
ts.AddTest("Vector3FloatTests_UnitVector",
Vector3FloatTests_UnitVector);
ts.AddTest("Vector3FloatTests_Angle",
Vector3FloatTests_Angle);
ts.AddTest("Vector3FloatTests_ParallelOrthogonalVectors",
Vector3FloatTests_ParallelOrthogonalVectors);
ts.AddTest("Vector3FloatTests_Projections",
Vector3FloatTests_Projections);
ts.AddTest("Vector3FloatTests_CrossProduct",
Vector3FloatTests_CrossProduct);
ts.AddTest("Vector3DoubleTests_Magnitude",
Vector3DoubleTests_Magnitude);
ts.AddTest("Vector3DoubleTests_Equality",
Vector3DoubleTests_Equality);
ts.AddTest("Vector3DoubleTests_Addition",
Vector3DoubleTests_Addition);
ts.AddTest("Vector3DoubleTests_Subtraction",
Vector3DoubleTests_Subtraction);
ts.AddTest("Vector3DoubleTests_ScalarMultiplication",
Vector3DoubleTests_ScalarMultiplication);
ts.AddTest("Vector3DoubleTests_ScalarDivision",
Vector3DoubleTests_ScalarDivision);
ts.AddTest("Vector3DoubleTests_DotProduct",
Vector3DoubleTests_DotProduct);
ts.AddTest("Vector3DoubleTests_UnitVector",
Vector3DoubleTests_UnitVector);
ts.AddTest("Vector3DoubleTests_Angle",
Vector3DoubleTests_Angle);
ts.AddTest("Vector3DoubleTests_ParallelOrthogonalVectors",
Vector3DoubleTests_ParallelOrthogonalVectors);
ts.AddTest("Vector3DoubleTests_Projections",
Vector3DoubleTests_Projections);
ts.AddTest("Vector3DoubleTests_CrossProduct",
Vector3DoubleTests_CrossProduct);
SimpleSuite suite;
suite.AddTest("Vector3Miscellaneous_ExtractionOperator3d",
Vector3Miscellaneous_ExtractionOperator3d);
suite.AddTest("Vector3Miscellaneous_ExtractionOperator3f",
Vector3Miscellaneous_ExtractionOperator3f);
suite.AddTest("Vector3Miscellaneous_SetEpsilon",
Vector3Miscellaneous_SetEpsilon);
suite.AddTest("Vector3FloatTests_Magnitude",
Vector3FloatTests_Magnitude);
suite.AddTest("Vector3FloatTests_Equality",
Vector3FloatTests_Equality);
suite.AddTest("Vector3FloatTests_Addition",
Vector3FloatTests_Addition);
suite.AddTest("Vector3FloatTests_Subtraction",
Vector3FloatTests_Subtraction);
suite.AddTest("Vector3FloatTests_ScalarMultiplication",
Vector3FloatTests_ScalarMultiplication);
suite.AddTest("Vector3FloatTests_ScalarDivision",
Vector3FloatTests_ScalarDivision);
suite.AddTest("Vector3FloatTests_DotProduct",
Vector3FloatTests_DotProduct);
suite.AddTest("Vector3FloatTests_UnitVector",
Vector3FloatTests_UnitVector);
suite.AddTest("Vector3FloatTests_Angle",
Vector3FloatTests_Angle);
suite.AddTest("Vector3FloatTests_ParallelOrthogonalVectors",
Vector3FloatTests_ParallelOrthogonalVectors);
suite.AddTest("Vector3FloatTests_Projections",
Vector3FloatTests_Projections);
suite.AddTest("Vector3FloatTests_CrossProduct",
Vector3FloatTests_CrossProduct);
suite.AddTest("Vector3DoubleTests_Magnitude",
Vector3DoubleTests_Magnitude);
suite.AddTest("Vector3DoubleTests_Equality",
Vector3DoubleTests_Equality);
suite.AddTest("Vector3DoubleTests_Addition",
Vector3DoubleTests_Addition);
suite.AddTest("Vector3DoubleTests_Subtraction",
Vector3DoubleTests_Subtraction);
suite.AddTest("Vector3DoubleTests_ScalarMultiplication",
Vector3DoubleTests_ScalarMultiplication);
suite.AddTest("Vector3DoubleTests_ScalarDivision",
Vector3DoubleTests_ScalarDivision);
suite.AddTest("Vector3DoubleTests_DotProduct",
Vector3DoubleTests_DotProduct);
suite.AddTest("Vector3DoubleTests_UnitVector",
Vector3DoubleTests_UnitVector);
suite.AddTest("Vector3DoubleTests_Angle",
Vector3DoubleTests_Angle);
suite.AddTest("Vector3DoubleTests_ParallelOrthogonalVectors",
Vector3DoubleTests_ParallelOrthogonalVectors);
suite.AddTest("Vector3DoubleTests_Projections",
Vector3DoubleTests_Projections);
suite.AddTest("Vector3DoubleTests_CrossProduct",
Vector3DoubleTests_CrossProduct);
auto result = suite.Run();
if (ts.Run()) {
std::cout << "OK" << std::endl;
return 0;
}
else {
auto r = ts.GetReport();
std::cerr << r.Failing << "/" << r.Total << " tests failed." << std::endl;
return 1;
}
std::cout << suite.GetReport() << "\n";
return result ? 0 : 1;
}