Browse Source

Fix testing mechanism.

master
James Goppert 9 years ago
parent
commit
38211e1aff
  1. 49
      matrix/Matrix.hpp
  2. 126
      test/attitude.cpp
  3. 8
      test/filter.cpp
  4. 8
      test/helper.cpp
  5. 6
      test/integration.cpp
  6. 8
      test/inverse.cpp
  7. 30
      test/matrixAssignment.cpp
  8. 12
      test/matrixMult.cpp
  9. 6
      test/matrixScalarMult.cpp
  10. 7
      test/setIdentity.cpp
  11. 8
      test/squareMatrix.cpp
  12. 12
      test/test_macros.hpp
  13. 6
      test/transpose.cpp
  14. 8
      test/vector.cpp
  15. 21
      test/vector2.cpp
  16. 10
      test/vector3.cpp
  17. 27
      test/vectorAssignment.cpp

49
matrix/Matrix.hpp

@ -13,6 +13,8 @@ @@ -13,6 +13,8 @@
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include <cassert>
#include <stdexcept>
#if defined(SUPPORT_STDIOSTREAM)
#include <iostream>
#include <iomanip>
@ -264,20 +266,37 @@ public: @@ -264,20 +266,37 @@ public:
* Misc. Functions
*/
void print() const
void write_string(char * buf, size_t n) const
{
const Matrix<Type, M, N> &self = *this;
printf("\n");
char data_buf[500] = {0};
for (size_t i = 0; i < M; i++) {
printf("[");
char data_line[100] = {0};
char data_line_formatted[100] = {0};
for (size_t j = 0; j < N; j++) {
printf("%10g\t", double(self(i, j)));
char val_buf[15];
if (j == N-1) {
snprintf(val_buf, 15, "\t%10g", double(self(i, j)));
} else {
snprintf(val_buf, 15, "\t%10g,", double(self(i, j)));
}
strncat(data_line, val_buf, 300);
}
printf("]\n");
if (i == M-1) {
snprintf(data_line_formatted, n, "[%s]", data_line);
} else {
snprintf(data_line_formatted, n, "[%s],\n", data_line);
}
strncat(data_buf, data_line_formatted, n);
}
snprintf(buf, n, "[%s]", data_buf);
}
void print() const
{
char buf[200];
write_string(buf, 200);
printf("%s\n", buf);
}
Matrix<Type, N, M> transpose() const
@ -294,7 +313,6 @@ public: @@ -294,7 +313,6 @@ public:
return res;
}
// tranpose alias
inline Matrix<Type, N, M> T() const
{
@ -423,6 +441,19 @@ Matrix<Type, M, N> operator*(Type scalar, const Matrix<Type, M, N> &other) @@ -423,6 +441,19 @@ Matrix<Type, M, N> operator*(Type scalar, const Matrix<Type, M, N> &other)
return other * scalar;
}
template<typename Type, size_t M, size_t N>
bool isEqual(const Matrix<Type, M, N> &x,
const Matrix<Type, M, N> & y) {
if (!(x == y)) {
char buf_x[100];
char buf_y[100];
x.write_string(buf_x, 100);
y.write_string(buf_y, 100);
printf("not equal\nx:\n%s\ny:\n%s\n", buf_x, buf_y);
}
return x == y;
}
#if defined(SUPPORT_STDIOSTREAM)
template<typename Type, size_t M, size_t N>
std::ostream& operator<<(std::ostream& os,

126
test/attitude.cpp

@ -1,7 +1,8 @@ @@ -1,7 +1,8 @@
#include <cassert>
#include <cstdio>
#include <stdexcept>
#include <matrix/math.hpp>
#include "test_macros.hpp"
using namespace matrix;
@ -24,14 +25,13 @@ int main() @@ -24,14 +25,13 @@ int main()
Dcmf dcm_check(dcm_data);
// euler ctor
euler_check.T().print();
assert(euler_check == Vector3f(0.1f, 0.2f, 0.3f));
TEST(isEqual(euler_check, Vector3f(0.1f, 0.2f, 0.3f)));
// euler default ctor
Eulerf e;
Eulerf e_zero = zeros<float, 3, 1>();
assert(e == e_zero);
assert(e == e);
TEST(isEqual(e, e_zero));
TEST(isEqual(e, e));
// euler vector ctor
Vector<float, 3> v;
@ -39,99 +39,87 @@ int main() @@ -39,99 +39,87 @@ int main()
v(1) = 0.2f;
v(2) = 0.3f;
Eulerf euler_copy(v);
assert(euler_copy == euler_check);
TEST(isEqual(euler_copy, euler_check));
// quaternion ctor
Quatf q(1, 2, 3, 4);
assert(fabs(q(0) - 1) < eps);
assert(fabs(q(1) - 2) < eps);
assert(fabs(q(2) - 3) < eps);
assert(fabs(q(3) - 4) < eps);
TEST(fabs(q(0) - 1) < eps);
TEST(fabs(q(1) - 2) < eps);
TEST(fabs(q(2) - 3) < eps);
TEST(fabs(q(3) - 4) < eps);
// quat normalization
q.T().print();
q.normalize();
q.T().print();
assert(q == Quatf(0.18257419f, 0.36514837f,
0.54772256f, 0.73029674f));
TEST(isEqual(q, Quatf(0.18257419f, 0.36514837f,
0.54772256f, 0.73029674f)));
// quat default ctor
q = Quatf();
assert(q == Quatf(1, 0, 0, 0));
TEST(isEqual(q, Quatf(1, 0, 0, 0)));
// euler to quaternion
q = Quatf(euler_check);
q.T().print();
assert(q == q_check);
TEST(isEqual(q, q_check));
// euler to dcm
Dcmf dcm(euler_check);
dcm.print();
assert(dcm == dcm_check);
TEST(isEqual(dcm, dcm_check));
// quaternion to euler
Eulerf e1(q_check);
assert(e1 == euler_check);
TEST(isEqual(e1, euler_check));
// quaternion to dcm
Dcmf dcm1(q_check);
dcm1.print();
assert(dcm1 == dcm_check);
TEST(isEqual(dcm1, dcm_check));
// dcm default ctor
Dcmf dcm2;
dcm2.print();
SquareMatrix<float, 3> I = eye<float, 3>();
assert(dcm2 == I);
TEST(isEqual(dcm2, I));
// dcm to euler
Eulerf e2(dcm_check);
assert(e2 == euler_check);
TEST(isEqual(e2, euler_check));
// dcm to quaterion
Quatf q2(dcm_check);
assert(q2 == q_check);
TEST(isEqual(q2, q_check));
// euler gimbal lock check
// note if theta = pi/2, then roll is set to zero
float pi_2 = float(M_PI_2);
Eulerf euler_gimbal_lock(0.1f, pi_2, 0.2f);
Eulerf euler_gimbal_lock(0.0f, pi_2, 0.2f);
Dcmf dcm_lock(euler_gimbal_lock);
Eulerf euler_gimbal_lock_out(dcm_lock);
euler_gimbal_lock_out.T().print();
euler_gimbal_lock.T().print();
assert(euler_gimbal_lock == euler_gimbal_lock_out);
TEST(isEqual(euler_gimbal_lock, euler_gimbal_lock_out));
// note if theta = pi/2, then roll is set to zero
Eulerf euler_gimbal_lock2(0.1f, -pi_2, 0.2f);
Eulerf euler_gimbal_lock2(0.0f, -pi_2, 0.2f);
Dcmf dcm_lock2(euler_gimbal_lock2);
Eulerf euler_gimbal_lock_out2(dcm_lock2);
euler_gimbal_lock_out2.T().print();
euler_gimbal_lock2.T().print();
assert(euler_gimbal_lock2 == euler_gimbal_lock_out2);
TEST(isEqual(euler_gimbal_lock2, euler_gimbal_lock_out2));
// quaterion copy ctors
float data_v4[] = {1, 2, 3, 4};
Vector<float, 4> v4(data_v4);
Quatf q_from_v(v4);
assert(q_from_v == v4);
TEST(isEqual(q_from_v, v4));
Matrix<float, 4, 1> m4(data_v4);
Quatf q_from_m(m4);
assert(q_from_m == m4);
TEST(isEqual(q_from_m, m4));
// quaternion derivate
Vector<float, 4> q_dot = q.derivative(Vector3f(1, 2, 3));
printf("q_dot:\n");
q_dot.T().print();
// quaternion product
Quatf q_prod_check(
0.93394439f, 0.0674002f, 0.20851f, 0.28236266f);
assert(q_prod_check == q_check*q_check);
TEST(isEqual(q_prod_check, q_check*q_check));
q_check *= q_check;
assert(q_prod_check == q_check);
TEST(isEqual(q_prod_check, q_check));
// Quaternion scalar multiplication
float scalar = 0.5;
@ -139,26 +127,26 @@ int main() @@ -139,26 +127,26 @@ int main()
Quatf q_scalar_mul_check(1.0f * scalar, 2.0f * scalar,
3.0f * scalar, 4.0f * scalar);
Quatf q_scalar_mul_res = scalar * q_scalar_mul;
assert(q_scalar_mul_check == q_scalar_mul_res);
TEST(isEqual(q_scalar_mul_check, q_scalar_mul_res));
Quatf q_scalar_mul_res2 = q_scalar_mul * scalar;
assert(q_scalar_mul_check == q_scalar_mul_res2);
TEST(isEqual(q_scalar_mul_check, q_scalar_mul_res2));
Quatf q_scalar_mul_res3(q_scalar_mul);
q_scalar_mul_res3 *= scalar;
assert(q_scalar_mul_check == q_scalar_mul_res3);
TEST(isEqual(q_scalar_mul_check, q_scalar_mul_res3));
// quaternion inverse
q = q_check.inversed();
assert(fabsf(q_check(0) - q(0)) < eps);
assert(fabsf(q_check(1) + q(1)) < eps);
assert(fabsf(q_check(2) + q(2)) < eps);
assert(fabsf(q_check(3) + q(3)) < eps);
TEST(fabsf(q_check(0) - q(0)) < eps);
TEST(fabsf(q_check(1) + q(1)) < eps);
TEST(fabsf(q_check(2) + q(2)) < eps);
TEST(fabsf(q_check(3) + q(3)) < eps);
q = q_check;
q.invert();
assert(fabsf(q_check(0) - q(0)) < eps);
assert(fabsf(q_check(1) + q(1)) < eps);
assert(fabsf(q_check(2) + q(2)) < eps);
assert(fabsf(q_check(3) + q(3)) < eps);
TEST(fabsf(q_check(0) - q(0)) < eps);
TEST(fabsf(q_check(1) + q(1)) < eps);
TEST(fabsf(q_check(2) + q(2)) < eps);
TEST(fabsf(q_check(3) + q(3)) < eps);
// rotate quaternion (nonzero rotation)
Quatf qI(1.0f, 0.0f, 0.0f, 0.0f);
@ -167,10 +155,10 @@ int main() @@ -167,10 +155,10 @@ int main()
rot(1) = rot(2) = 0.0f;
qI.rotate(rot);
Quatf q_true(cosf(1.0f / 2), sinf(1.0f / 2), 0.0f, 0.0f);
assert(fabsf(qI(0) - q_true(0)) < eps);
assert(fabsf(qI(1) - q_true(1)) < eps);
assert(fabsf(qI(2) - q_true(2)) < eps);
assert(fabsf(qI(3) - q_true(3)) < eps);
TEST(fabsf(qI(0) - q_true(0)) < eps);
TEST(fabsf(qI(1) - q_true(1)) < eps);
TEST(fabsf(qI(2) - q_true(2)) < eps);
TEST(fabsf(qI(3) - q_true(3)) < eps);
// rotate quaternion (zero rotation)
qI = Quatf(1.0f, 0.0f, 0.0f, 0.0f);
@ -178,33 +166,33 @@ int main() @@ -178,33 +166,33 @@ int main()
rot(1) = rot(2) = 0.0f;
qI.rotate(rot);
q_true = Quatf(cosf(0.0f), sinf(0.0f), 0.0f, 0.0f);
assert(fabsf(qI(0) - q_true(0)) < eps);
assert(fabsf(qI(1) - q_true(1)) < eps);
assert(fabsf(qI(2) - q_true(2)) < eps);
assert(fabsf(qI(3) - q_true(3)) < eps);
TEST(fabsf(qI(0) - q_true(0)) < eps);
TEST(fabsf(qI(1) - q_true(1)) < eps);
TEST(fabsf(qI(2) - q_true(2)) < eps);
TEST(fabsf(qI(3) - q_true(3)) < eps);
// get rotation axis from quaternion (nonzero rotation)
q = Quatf(cosf(1.0f / 2), 0.0f, sinf(1.0f / 2), 0.0f);
rot = q.to_axis_angle();
assert(fabsf(rot(0)) < eps);
assert(fabsf(rot(1) -1.0f) < eps);
assert(fabsf(rot(2)) < eps);
TEST(fabsf(rot(0)) < eps);
TEST(fabsf(rot(1) -1.0f) < eps);
TEST(fabsf(rot(2)) < eps);
// get rotation axis from quaternion (zero rotation)
q = Quatf(1.0f, 0.0f, 0.0f, 0.0f);
rot = q.to_axis_angle();
assert(fabsf(rot(0)) < eps);
assert(fabsf(rot(1)) < eps);
assert(fabsf(rot(2)) < eps);
TEST(fabsf(rot(0)) < eps);
TEST(fabsf(rot(1)) < eps);
TEST(fabsf(rot(2)) < eps);
// from axis angle (zero rotation)
rot(0) = rot(1) = rot(2) = 0.0f;
q.from_axis_angle(rot, 0.0f);
q_true = Quatf(1.0f, 0.0f, 0.0f, 0.0f);
assert(fabsf(q(0) - q_true(0)) < eps);
assert(fabsf(q(1) - q_true(1)) < eps);
assert(fabsf(q(2) - q_true(2)) < eps);
assert(fabsf(q(3) - q_true(3)) < eps);
TEST(fabsf(q(0) - q_true(0)) < eps);
TEST(fabsf(q(1) - q_true(1)) < eps);
TEST(fabsf(q(2) - q_true(2)) < eps);
TEST(fabsf(q(3) - q_true(3)) < eps);
};

8
test/filter.cpp

@ -1,7 +1,7 @@ @@ -1,7 +1,7 @@
#include <assert.h>
#include <stdio.h>
#include <matrix/filter.hpp>
#include "test_macros.hpp"
using namespace matrix;
@ -21,13 +21,9 @@ int main() @@ -21,13 +21,9 @@ int main()
float beta = 0;
kalman_correct<float, 6, 5>(P, C, R, r, dx, dP, beta);
dx.T().print();
printf("beta: %g\n", beta);
float data_check[] = {0.5,1,1.5,2,2.5,0};
Vector<float, n_x> dx_check(data_check);
assert(dx == dx_check);
TEST(isEqual(dx, dx_check));
return 0;
}

8
test/helper.cpp

@ -1,16 +1,16 @@ @@ -1,16 +1,16 @@
#include <assert.h>
#include <stdio.h>
#include <matrix/helper_functions.hpp>
#include "test_macros.hpp"
using namespace matrix;
int main()
{
assert(fabs(wrap_pi(4.0) - (4.0 - 2*M_PI)) < 1e-5);
assert(fabs(wrap_pi(-4.0) - (-4.0 + 2*M_PI)) < 1e-5);
assert(fabs(wrap_pi(3.0) - (3.0)) < 1e-3);
TEST(fabs(wrap_pi(4.0) - (4.0 - 2*M_PI)) < 1e-5);
TEST(fabs(wrap_pi(-4.0) - (-4.0 + 2*M_PI)) < 1e-5);
TEST(fabs(wrap_pi(3.0) - (3.0)) < 1e-3);
wrap_pi(NAN);
return 0;
}

6
test/integration.cpp

@ -1,7 +1,7 @@ @@ -1,7 +1,7 @@
#include <assert.h>
#include <stdio.h>
#include <matrix/integration.hpp>
#include "test_macros.hpp"
using namespace matrix;
@ -17,10 +17,8 @@ int main() @@ -17,10 +17,8 @@ int main()
Vector<float, 3> u = ones<float, 3, 1>();
float t = 1;
float h = 0.1f;
y.T().print();
integrate_rk4(f, y, u, t, h, y);
y.T().print();
assert(y == (ones<float, 6, 1>()*1.1f));
TEST(isEqual(y, (ones<float, 6, 1>()*1.1f)));
return 0;
}

8
test/inverse.cpp

@ -1,7 +1,7 @@ @@ -1,7 +1,7 @@
#include <assert.h>
#include <stdio.h>
#include <matrix/math.hpp>
#include "test_macros.hpp"
using namespace matrix;
@ -25,9 +25,7 @@ int main() @@ -25,9 +25,7 @@ int main()
SquareMatrix<float, 3> A(data);
SquareMatrix<float, 3> A_I = inv(A);
SquareMatrix<float, 3> A_I_check(data_check);
A_I.print();
A_I_check.print();
assert((A_I - A_I_check).abs().max() < 1e-5);
TEST((A_I - A_I_check).abs().max() < 1e-5);
// stess test
SquareMatrix<float, n_large> A_large;
@ -37,7 +35,7 @@ int main() @@ -37,7 +35,7 @@ int main()
for (size_t i = 0; i < n_large; i++) {
A_large_I = inv(A_large);
assert(A_large == A_large_I);
TEST(isEqual(A_large, A_large_I));
}
SquareMatrix<float, 3> zero_test = zeros<float, 3, 3>();

30
test/matrixAssignment.cpp

@ -1,6 +1,5 @@ @@ -1,6 +1,5 @@
#include <assert.h>
#include <matrix/math.hpp>
#include "test_macros.hpp"
using namespace matrix;
@ -20,36 +19,33 @@ int main() @@ -20,36 +19,33 @@ int main()
m(2, 1) = 8;
m(2, 2) = 9;
m.print();
float data[9] = {1, 2, 3, 4, 5, 6, 7, 8, 9};
Matrix3f m2(data);
m2.print();
for(int i=0; i<9; i++) {
assert(fabs(data[i] - m2.data()[i]) < 1e-6f);
TEST(fabs(data[i] - m2.data()[i]) < 1e-6f);
}
float data_times_2[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18};
Matrix3f m3(data_times_2);
assert(m == m2);
assert(!(m == m3));
TEST(isEqual(m, m2));
TEST(!(m == m3));
m2 *= 2;
assert(m2 == m3);
TEST(m2 == m3);
m2 /= 2;
m2 -= 1;
float data_minus_1[9] = {0, 1, 2, 3, 4, 5, 6, 7, 8};
assert(Matrix3f(data_minus_1) == m2);
TEST(Matrix3f(data_minus_1) == m2);
m2 += 1;
assert(Matrix3f(data) == m2);
TEST(Matrix3f(data) == m2);
m3 -= m2;
assert(m3 == m2);
TEST(m3 == m2);
float data_row_02_swap[9] = {
7, 8, 9,
@ -65,18 +61,18 @@ int main() @@ -65,18 +61,18 @@ int main()
Matrix3f m4(data);
assert(-m4 == m4*(-1));
TEST(-m4 == m4*(-1));
m4.swapCols(0, 2);
assert(m4 == Matrix3f(data_col_02_swap));
TEST(m4 == Matrix3f(data_col_02_swap));
m4.swapCols(0, 2);
m4.swapRows(0, 2);
assert(m4 == Matrix3f(data_row_02_swap));
assert(fabs(m4.min() - 1) < 1e-5);
TEST(m4 == Matrix3f(data_row_02_swap));
TEST(fabs(m4.min() - 1) < 1e-5);
Scalar<float> s;
s = 1;
assert(fabs(s - 1) < 1e-5);
TEST(fabs(s - 1) < 1e-5);
return 0;
}

12
test/matrixMult.cpp

@ -1,7 +1,7 @@ @@ -1,7 +1,7 @@
#include <assert.h>
#include <stdio.h>
#include <matrix/math.hpp>
#include "test_macros.hpp"
using namespace matrix;
@ -13,22 +13,18 @@ int main() @@ -13,22 +13,18 @@ int main()
Matrix3f A_I(data_check);
Matrix3f I;
I.setIdentity();
A.print();
A_I.print();
Matrix3f R = A * A_I;
R.print();
assert(R == I);
TEST(isEqual(R, I));
Matrix3f R2 = A;
R2 *= A_I;
R2.print();
assert(R2 == I);
TEST(isEqual(R2, I));
Matrix3f A2 = eye<float, 3>()*2;
Matrix3f B = A2.emult(A2);
Matrix3f B_check = eye<float, 3>()*4;
assert(B == B_check);
TEST(isEqual(B, B_check));
return 0;
}

6
test/matrixScalarMult.cpp

@ -1,7 +1,7 @@ @@ -1,7 +1,7 @@
#include <assert.h>
#include <stdio.h>
#include <matrix/math.hpp>
#include "test_macros.hpp"
using namespace matrix;
@ -12,9 +12,7 @@ int main() @@ -12,9 +12,7 @@ int main()
A = A * 2;
float data_check[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18};
Matrix3f A_check(data_check);
A.print();
A_check.print();
assert(A == A_check);
TEST(isEqual(A, A_check));
return 0;
}

7
test/setIdentity.cpp

@ -1,6 +1,5 @@ @@ -1,6 +1,5 @@
#include <assert.h>
#include <matrix/math.hpp>
#include "test_macros.hpp"
using namespace matrix;
@ -14,10 +13,10 @@ int main() @@ -14,10 +13,10 @@ int main()
for (int i = 0; i < 3; i++) {
for (int j = 0; j < 3; j++) {
if (i == j) {
assert( fabs(A(i, j) - 1) < 1e-7);
TEST( fabs(A(i, j) - 1) < 1e-7);
} else {
assert( fabs(A(i, j) - 0) < 1e-7);
TEST( fabs(A(i, j) - 0) < 1e-7);
}
}
}

8
test/squareMatrix.cpp

@ -1,5 +1,5 @@ @@ -1,5 +1,5 @@
#include <assert.h>
#include <stdio.h>
#include "test_macros.hpp"
#include <matrix/math.hpp>
@ -15,9 +15,8 @@ int main() @@ -15,9 +15,8 @@ int main()
};
SquareMatrix<float, 3> A(data);
Vector3<float> diag_check(1, 5, 10);
A.diag().T().print();
assert(A.diag() == diag_check);
TEST(isEqual(A.diag(), diag_check));
float data_check[9] = {
1.01158503f, 0.02190432f, 0.03238144f,
@ -25,11 +24,10 @@ int main() @@ -25,11 +24,10 @@ int main()
0.07576783f, 0.08708946f, 1.10894048f
};
printf("expm(A*t)\n");
float dt = 0.01f;
SquareMatrix<float, 3> eA = expm(SquareMatrix<float, 3>(A*dt), 5);
SquareMatrix<float, 3> eA_check(data_check);
assert((eA - eA_check).abs().max() < 1e-3);
TEST((eA - eA_check).abs().max() < 1e-3);
return 0;
}

12
test/test_macros.hpp

@ -0,0 +1,12 @@ @@ -0,0 +1,12 @@
/**
* @file test_marcos.hpp
*
* Helps with cmake testing.
*
* @author James Goppert <james.goppert@gmail.com>
*/
#pragma once
#include <cstdio>
#define TEST(X) if(!(X)) { fprintf(stderr, "test failed on %s:%d\n", __FILE__, __LINE__); return -1;}

6
test/transpose.cpp

@ -1,7 +1,7 @@ @@ -1,7 +1,7 @@
#include <assert.h>
#include <stdio.h>
#include <matrix/math.hpp>
#include "test_macros.hpp"
using namespace matrix;
@ -15,9 +15,7 @@ int main() @@ -15,9 +15,7 @@ int main()
Matrix<float, 3, 2> A_T = A.transpose();
float data_check[6] = {1, 4, 2, 5, 3, 6};
Matrix<float, 3, 2> A_T_check(data_check);
A_T.print();
A_T_check.print();
assert(A_T == A_T_check);
TEST(isEqual(A_T, A_T_check));
return 0;
}

8
test/vector.cpp

@ -1,7 +1,7 @@ @@ -1,7 +1,7 @@
#include <assert.h>
#include <stdio.h>
#include <matrix/math.hpp>
#include "test_macros.hpp"
using namespace matrix;
@ -12,12 +12,12 @@ int main() @@ -12,12 +12,12 @@ int main()
float data1[] = {1,2,3,4,5};
float data2[] = {6,7,8,9,10};
Vector<float, 5> v1(data1);
assert(fabs(v1.norm() - 7.416198487095663f) < 1e-5);
TEST(fabs(v1.norm() - 7.416198487095663f) < 1e-5);
Vector<float, 5> v2(data2);
assert(fabs(v1.dot(v2) - 130.0f) < 1e-5);
TEST(fabs(v1.dot(v2) - 130.0f) < 1e-5);
v2.normalize();
Vector<float, 5> v3(v2);
assert(v2 == v3);
TEST(v2 == v3);
return 0;
}

21
test/vector2.cpp

@ -1,8 +1,9 @@ @@ -1,8 +1,9 @@
#include <assert.h>
#include <stdio.h>
#include <matrix/math.hpp>
#include "test_macros.hpp"
using namespace matrix;
template class Vector<float, 2>;
@ -11,24 +12,24 @@ int main() @@ -11,24 +12,24 @@ int main()
{
Vector2f a(1, 0);
Vector2f b(0, 1);
assert(fabs(a % b - 1.0f) < 1e-5);
TEST(fabs(a % b - 1.0f) < 1e-5);
Vector2f c;
assert(fabs(c(0) - 0) < 1e-5);
assert(fabs(c(1) - 0) < 1e-5);
TEST(fabs(c(0) - 0) < 1e-5);
TEST(fabs(c(1) - 0) < 1e-5);
Matrix<float, 2, 1> d(a);
assert(fabs(d(0,0) - 1) < 1e-5);
assert(fabs(d(1,0) - 0) < 1e-5);
TEST(fabs(d(0,0) - 1) < 1e-5);
TEST(fabs(d(1,0) - 0) < 1e-5);
Vector2f e(d);
assert(fabs(e(0) - 1) < 1e-5);
assert(fabs(e(1) - 0) < 1e-5);
TEST(fabs(e(0) - 1) < 1e-5);
TEST(fabs(e(1) - 0) < 1e-5);
float data[] = {4,5};
Vector2f f(data);
assert(fabs(f(0) - 4) < 1e-5);
assert(fabs(f(1) - 5) < 1e-5);
TEST(fabs(f(0) - 4) < 1e-5);
TEST(fabs(f(1) - 5) < 1e-5);
return 0;
}

10
test/vector3.cpp

@ -1,7 +1,7 @@ @@ -1,7 +1,7 @@
#include <assert.h>
#include <stdio.h>
#include <matrix/math.hpp>
#include "test_macros.hpp"
using namespace matrix;
@ -13,15 +13,15 @@ int main() @@ -13,15 +13,15 @@ int main()
Vector3f b(0, 1, 0);
Vector3f c = a.cross(b);
c.print();
assert (c == Vector3f(0,0,1));
TEST (c == Vector3f(0,0,1));
c = a % b;
assert (c == Vector3f(0,0,1));
TEST (c == Vector3f(0,0,1));
Matrix<float, 3, 1> d(c);
Vector3f e(d);
assert (e == d);
TEST (e == d);
float data[] = {4, 5, 6};
Vector3f f(data);
assert (f == Vector3f(4, 5, 6));
TEST (f == Vector3f(4, 5, 6));
return 0;
}

27
test/vectorAssignment.cpp

@ -1,7 +1,7 @@ @@ -1,7 +1,7 @@
#include <assert.h>
#include <matrix/math.hpp>
#include "test_macros.hpp"
using namespace matrix;
template class Vector<float, 3>;
@ -13,26 +13,23 @@ int main() @@ -13,26 +13,23 @@ int main()
v(1) = 2;
v(2) = 3;
v.print();
static const float eps = 1e-7f;
assert(fabs(v(0) - 1) < eps);
assert(fabs(v(1) - 2) < eps);
assert(fabs(v(2) - 3) < eps);
TEST(fabs(v(0) - 1) < eps);
TEST(fabs(v(1) - 2) < eps);
TEST(fabs(v(2) - 3) < eps);
Vector3f v2(4, 5, 6);
v2.print();
assert(fabs(v2(0) - 4) < eps);
assert(fabs(v2(1) - 5) < eps);
assert(fabs(v2(2) - 6) < eps);
TEST(fabs(v2(0) - 4) < eps);
TEST(fabs(v2(1) - 5) < eps);
TEST(fabs(v2(2) - 6) < eps);
SquareMatrix<float, 3> m = diag(Vector3f(1,2,3));
assert(fabs(m(0, 0) - 1) < eps);
assert(fabs(m(1, 1) - 2) < eps);
assert(fabs(m(2, 2) - 3) < eps);
TEST(fabs(m(0, 0) - 1) < eps);
TEST(fabs(m(1, 1) - 2) < eps);
TEST(fabs(m(2, 2) - 3) < eps);
return 0;
}

Loading…
Cancel
Save