Skip to content

Commit

Permalink
Disable test diagnostic prints by default (#238)
Browse files Browse the repository at this point in the history
  • Loading branch information
calcmogul authored Dec 14, 2023
1 parent 05af705 commit 25bc6f0
Show file tree
Hide file tree
Showing 18 changed files with 188 additions and 66 deletions.
5 changes: 1 addition & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -255,10 +255,7 @@ if(BUILD_TESTING)
${CMAKE_CURRENT_SOURCE_DIR}/test/include
${CMAKE_CURRENT_SOURCE_DIR}/thirdparty/units/include
)
target_link_libraries(
SleipnirTest
PRIVATE Sleipnir GTest::gtest GTest::gtest_main
)
target_link_libraries(SleipnirTest PRIVATE Sleipnir GTest::gtest)
if(NOT CMAKE_TOOLCHAIN_FILE)
gtest_discover_tests(SleipnirTest)
endif()
Expand Down
4 changes: 3 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,9 @@ The following build types can be specified via `-DCMAKE_BUILD_TYPE` during CMake
* Perf
* RelWithDebInfo build type, but with frame pointer so perf utility can use it

## Test problem solutions
## Test diagnostics

Passing the `--enable-diagnostics` flag to the test executable enables solver diagnostic prints.

Some test problems generate CSV files containing their solutions. These can be plotted with [tools/plot_test_problem_solutions.py](https://github.com/SleipnirGroup/Sleipnir/blob/main/tools/plot_test_problem_solutions.py).

Expand Down
12 changes: 7 additions & 5 deletions src/optimization/OptimizationProblem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -349,11 +349,13 @@ Eigen::VectorXd OptimizationProblem::InteriorPoint(

// Check for overconstrained problem
if (m_equalityConstraints.size() > m_decisionVariables.size()) {
fmt::print("The problem has too few degrees of freedom.\n");
fmt::print("Violated constraints (cₑ(x) = 0) in order of declaration:\n");
for (int row = 0; row < c_e.rows(); ++row) {
if (c_e(row) < 0.0) {
fmt::print(" {}/{}: {} = 0\n", row + 1, c_e.rows(), c_e(row));
if (m_config.diagnostics) {
fmt::print("The problem has too few degrees of freedom.\n");
fmt::print("Violated constraints (cₑ(x) = 0) in order of declaration:\n");
for (int row = 0; row < c_e.rows(); ++row) {
if (c_e(row) < 0.0) {
fmt::print(" {}/{}: {} = 0\n", row + 1, c_e.rows(), c_e(row));
}
}
}

Expand Down
25 changes: 25 additions & 0 deletions test/include/CmdlineArguments.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
// Copyright (c) Sleipnir contributors

#pragma once

#include <span>
#include <string_view>

/// Test commandline argument that enables solver diagnostics
inline constexpr std::string_view kEnableDiagnostics = "--enable-diagnostics";

/**
* Initializes the commandline argument list for tests to retreive.
*/
void SetCmdlineArgs(char* argv[], int argc);

/**
* Returns the test executable's commandline arguments.
*/
std::span<char*> GetCmdlineArgs();

/**
* Returns true if the given argument is present in the test executable's
* commandline arguments.
*/
bool CmdlineArgPresent(std::string_view arg);
21 changes: 21 additions & 0 deletions test/src/CmdlineArguments.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
// Copyright (c) Sleipnir contributors

#include "CmdlineArguments.hpp"

#include <algorithm>

namespace {
static std::span<char*> args;
} // namespace

void SetCmdlineArgs(char* argv[], int argc) {
args = std::span(argv, argc);
}

std::span<char*> GetCmdlineArgs() {
return args;
}

bool CmdlineArgPresent(std::string_view arg) {
return std::find(args.begin(), args.end(), arg) != args.end();
}
13 changes: 13 additions & 0 deletions test/src/Main.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
// Copyright (c) Sleipnir contributors

#include <gtest/gtest.h>

#include "CmdlineArguments.hpp"

int main(int argc, char* argv[]) {
testing::InitGoogleTest(&argc, argv);

SetCmdlineArgs(argv, argc);

return RUN_ALL_TESTS();
}
17 changes: 11 additions & 6 deletions test/src/control/OCPCartPoleTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#include <units/length.h>
#include <units/time.h>

#include "CmdlineArguments.hpp"

namespace {
/**
* Performs 4th order Runge-Kutta integration of dx/dt = f(x, u) for dt.
Expand Down Expand Up @@ -238,13 +240,16 @@ TEST(OCPSolverTest, DISABLED_CartPoleProblem) {
}
problem.Minimize(J);

auto end1 = std::chrono::system_clock::now();
using std::chrono::duration_cast;
using std::chrono::microseconds;
fmt::print("Setup time: {} ms\n\n",
duration_cast<microseconds>(end1 - start).count() / 1000.0);
[[maybe_unused]] auto end1 = std::chrono::system_clock::now();
if (CmdlineArgPresent(kEnableDiagnostics)) {
using std::chrono::duration_cast;
using std::chrono::microseconds;
fmt::print("Setup time: {} ms\n\n",
duration_cast<microseconds>(end1 - start).count() / 1000.0);
}

auto status = problem.Solve({.diagnostics = true});
auto status =
problem.Solve({.diagnostics = CmdlineArgPresent(kEnableDiagnostics)});

EXPECT_EQ(sleipnir::ExpressionType::kQuadratic, status.costFunctionType);
EXPECT_EQ(sleipnir::ExpressionType::kNonlinear,
Expand Down
17 changes: 11 additions & 6 deletions test/src/control/OCPFlywheelTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@
#include <units/time.h>
#include <units/voltage.h>

#include "CmdlineArguments.hpp"

namespace {
bool Near(double expected, double actual, double tolerance) {
return std::abs(expected - actual) < tolerance;
Expand Down Expand Up @@ -55,13 +57,16 @@ void TestFlywheel(std::string testName, Eigen::Matrix<double, 1, 1> A,
(r_mat_vmat - solver.X()) * (r_mat_vmat - solver.X()).T();
solver.Minimize(objective);

auto end1 = std::chrono::system_clock::now();
using std::chrono::duration_cast;
using std::chrono::microseconds;
fmt::print("Setup time: {} ms\n\n",
duration_cast<microseconds>(end1 - start).count() / 1000.0);
[[maybe_unused]] auto end1 = std::chrono::system_clock::now();
if (CmdlineArgPresent(kEnableDiagnostics)) {
using std::chrono::duration_cast;
using std::chrono::microseconds;
fmt::print("Setup time: {} ms\n\n",
duration_cast<microseconds>(end1 - start).count() / 1000.0);
}

auto status = solver.Solve({.diagnostics = true});
auto status =
solver.Solve({.diagnostics = CmdlineArgPresent(kEnableDiagnostics)});

EXPECT_EQ(sleipnir::ExpressionType::kQuadratic, status.costFunctionType);
if (method == sleipnir::TranscriptionMethod::kSingleShooting) {
Expand Down
19 changes: 12 additions & 7 deletions test/src/control/OCPRobotTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@
#include <sleipnir/control/OCPSolver.hpp>
#include <units/time.h>

#include "CmdlineArguments.hpp"

TEST(OCPSolverTest, Robot) {
auto start = std::chrono::system_clock::now();

Expand Down Expand Up @@ -64,14 +66,17 @@ TEST(OCPSolverTest, Robot) {
solverMinTime.Minimize(solverMinTime.DT() *
Eigen::Matrix<double, N + 1, 1>::Ones());

auto end1 = std::chrono::system_clock::now();
using std::chrono::duration_cast;
using std::chrono::microseconds;
fmt::print("Setup time: {} ms\n\n",
duration_cast<microseconds>(end1 - start).count() / 1000.0);
[[maybe_unused]] auto end1 = std::chrono::system_clock::now();
if (CmdlineArgPresent(kEnableDiagnostics)) {
using std::chrono::duration_cast;
using std::chrono::microseconds;
fmt::print("Setup time: {} ms\n\n",
duration_cast<microseconds>(end1 - start).count() / 1000.0);
}

auto status =
solverMinTime.Solve({.maxIterations = 1000, .diagnostics = true});
auto status = solverMinTime.Solve(
{.maxIterations = 1000,
.diagnostics = CmdlineArgPresent(kEnableDiagnostics)});

EXPECT_EQ(sleipnir::ExpressionType::kLinear, status.costFunctionType);
EXPECT_EQ(sleipnir::ExpressionType::kNonlinear,
Expand Down
5 changes: 4 additions & 1 deletion test/src/optimization/ArmOnElevatorProblemTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@
#include <units/time.h>
#include <units/velocity.h>

#include "CmdlineArguments.hpp"

// This problem tests the case where regularization fails
TEST(ArmOnElevatorProblemTest, DirectTranscription) {
constexpr int N = 800;
Expand Down Expand Up @@ -92,7 +94,8 @@ TEST(ArmOnElevatorProblemTest, DirectTranscription) {
}
problem.Minimize(J);

auto status = problem.Solve({.diagnostics = true});
auto status =
problem.Solve({.diagnostics = CmdlineArgPresent(kEnableDiagnostics)});

EXPECT_EQ(sleipnir::ExpressionType::kQuadratic, status.costFunctionType);
EXPECT_EQ(sleipnir::ExpressionType::kLinear, status.equalityConstraintType);
Expand Down
17 changes: 11 additions & 6 deletions test/src/optimization/CartPoleProblemTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#include <units/length.h>
#include <units/time.h>

#include "CmdlineArguments.hpp"

/**
* Performs 4th order Runge-Kutta integration of dx/dt = f(x, u) for dt.
*
Expand Down Expand Up @@ -243,13 +245,16 @@ TEST(CartPoleProblemTest, DISABLED_DirectTranscription) {
}
problem.Minimize(J);

auto end1 = std::chrono::system_clock::now();
using std::chrono::duration_cast;
using std::chrono::microseconds;
fmt::print("Setup time: {} ms\n\n",
duration_cast<microseconds>(end1 - start).count() / 1000.0);
[[maybe_unused]] auto end1 = std::chrono::system_clock::now();
if (CmdlineArgPresent(kEnableDiagnostics)) {
using std::chrono::duration_cast;
using std::chrono::microseconds;
fmt::print("Setup time: {} ms\n\n",
duration_cast<microseconds>(end1 - start).count() / 1000.0);
}

auto status = problem.Solve({.diagnostics = true});
auto status =
problem.Solve({.diagnostics = CmdlineArgPresent(kEnableDiagnostics)});

EXPECT_EQ(sleipnir::ExpressionType::kQuadratic, status.costFunctionType);
EXPECT_EQ(sleipnir::ExpressionType::kNonlinear,
Expand Down
17 changes: 11 additions & 6 deletions test/src/optimization/DoubleIntegratorProblemTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@
#include <sleipnir/optimization/OptimizationProblem.hpp>
#include <units/time.h>

#include "CmdlineArguments.hpp"

TEST(DoubleIntegratorProblemTest, MinimumTime) {
auto start = std::chrono::system_clock::now();

Expand Down Expand Up @@ -62,13 +64,16 @@ TEST(DoubleIntegratorProblemTest, MinimumTime) {
}
problem.Minimize(J);

auto end1 = std::chrono::system_clock::now();
using std::chrono::duration_cast;
using std::chrono::microseconds;
fmt::print("Setup time: {} ms\n\n",
duration_cast<microseconds>(end1 - start).count() / 1000.0);
[[maybe_unused]] auto end1 = std::chrono::system_clock::now();
if (CmdlineArgPresent(kEnableDiagnostics)) {
using std::chrono::duration_cast;
using std::chrono::microseconds;
fmt::print("Setup time: {} ms\n\n",
duration_cast<microseconds>(end1 - start).count() / 1000.0);
}

auto status = problem.Solve({.diagnostics = true});
auto status =
problem.Solve({.diagnostics = CmdlineArgPresent(kEnableDiagnostics)});

EXPECT_EQ(sleipnir::ExpressionType::kQuadratic, status.costFunctionType);
EXPECT_EQ(sleipnir::ExpressionType::kLinear, status.equalityConstraintType);
Expand Down
17 changes: 11 additions & 6 deletions test/src/optimization/FlywheelProblemTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#include <units/time.h>
#include <units/voltage.h>

#include "CmdlineArguments.hpp"

namespace {
bool Near(double expected, double actual, double tolerance) {
return std::abs(expected - actual) < tolerance;
Expand Down Expand Up @@ -56,13 +58,16 @@ TEST(FlywheelProblemTest, DirectTranscription) {
}
problem.Minimize(J);

auto end1 = std::chrono::system_clock::now();
using std::chrono::duration_cast;
using std::chrono::microseconds;
fmt::print("Setup time: {} ms\n\n",
duration_cast<microseconds>(end1 - start).count() / 1000.0);
[[maybe_unused]] auto end1 = std::chrono::system_clock::now();
if (CmdlineArgPresent(kEnableDiagnostics)) {
using std::chrono::duration_cast;
using std::chrono::microseconds;
fmt::print("Setup time: {} ms\n\n",
duration_cast<microseconds>(end1 - start).count() / 1000.0);
}

auto status = problem.Solve({.diagnostics = true});
auto status =
problem.Solve({.diagnostics = CmdlineArgPresent(kEnableDiagnostics)});

EXPECT_EQ(sleipnir::ExpressionType::kQuadratic, status.costFunctionType);
EXPECT_EQ(sleipnir::ExpressionType::kLinear, status.equalityConstraintType);
Expand Down
5 changes: 4 additions & 1 deletion test/src/optimization/LinearProblemTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@
#include <gtest/gtest.h>
#include <sleipnir/optimization/OptimizationProblem.hpp>

#include "CmdlineArguments.hpp"

TEST(LinearProblemTest, Maximize) {
sleipnir::OptimizationProblem problem;

Expand All @@ -20,7 +22,8 @@ TEST(LinearProblemTest, Maximize) {
problem.SubjectTo(x >= 0);
problem.SubjectTo(y >= 0);

auto status = problem.Solve({.diagnostics = true});
auto status =
problem.Solve({.diagnostics = CmdlineArgPresent(kEnableDiagnostics)});

EXPECT_EQ(sleipnir::ExpressionType::kLinear, status.costFunctionType);
EXPECT_EQ(sleipnir::ExpressionType::kNone, status.equalityConstraintType);
Expand Down
11 changes: 8 additions & 3 deletions test/src/optimization/NonlinearProblemTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@
#include <gtest/gtest.h>
#include <sleipnir/optimization/OptimizationProblem.hpp>

#include "CmdlineArguments.hpp"

std::vector<double> Range(double start, double end, double step) {
std::vector<double> ret;

Expand All @@ -27,7 +29,8 @@ TEST(NonlinearProblemTest, Quartic) {

problem.SubjectTo(x >= 1);

auto status = problem.Solve({.diagnostics = true});
auto status =
problem.Solve({.diagnostics = CmdlineArgPresent(kEnableDiagnostics)});

EXPECT_EQ(sleipnir::ExpressionType::kNonlinear, status.costFunctionType);
EXPECT_EQ(sleipnir::ExpressionType::kNone, status.equalityConstraintType);
Expand All @@ -54,7 +57,8 @@ TEST(NonlinearProblemTest, RosenbrockWithCubicAndLineConstraint) {
problem.SubjectTo(sleipnir::pow(x - 1, 3) - y + 1 <= 0);
problem.SubjectTo(x + y - 2 <= 0);

auto status = problem.Solve();
auto status =
problem.Solve({.diagnostics = CmdlineArgPresent(kEnableDiagnostics)});

EXPECT_EQ(sleipnir::ExpressionType::kNonlinear, status.costFunctionType);
EXPECT_EQ(sleipnir::ExpressionType::kNone, status.equalityConstraintType);
Expand Down Expand Up @@ -94,7 +98,8 @@ TEST(NonlinearProblemTest, RosenbrockWithDiskConstraint) {

problem.SubjectTo(sleipnir::pow(x, 2) + sleipnir::pow(y, 2) <= 2);

auto status = problem.Solve();
auto status =
problem.Solve({.diagnostics = CmdlineArgPresent(kEnableDiagnostics)});

EXPECT_EQ(sleipnir::ExpressionType::kNonlinear, status.costFunctionType);
EXPECT_EQ(sleipnir::ExpressionType::kNone, status.equalityConstraintType);
Expand Down
Loading

0 comments on commit 25bc6f0

Please sign in to comment.