Skip to content

Commit

Permalink
Adds %rename tag to interface files in order to match pep-8 naiming s…
Browse files Browse the repository at this point in the history
…tyle.

Signed-off-by: LolaSegura <[email protected]>
  • Loading branch information
LolaSegura committed Aug 18, 2021
1 parent 931cb41 commit ad00569
Show file tree
Hide file tree
Showing 9 changed files with 420 additions and 418 deletions.
3 changes: 3 additions & 0 deletions src/Matrix3.i
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,9 @@ namespace ignition
template<typename T>
class Matrix3
{
%rename("%(undercase)s", %$isfunction, %$ismember, %$not %$isconstructor) "";
%rename("%(uppercase)s", %$isstatic, %$isvariable) "";

public: static const Matrix3<T> Identity;
public: static const Matrix3<T> Zero;
public: Matrix3();
Expand Down
120 changes: 60 additions & 60 deletions src/Matrix3_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,22 +31,22 @@ def test_matrix3d(self):
self.assertAlmostEqual(matrix1, Matrix3d(1, 2, 3, 4, 5, 6, 7, 8, 9))

matrix = Matrix3d()
matrix.Axes(Vector3d(1, 1, 1), Vector3d(2, 2, 2),
matrix.axes(Vector3d(1, 1, 1), Vector3d(2, 2, 2),
Vector3d(3, 3, 3))
self.assertAlmostEqual(matrix, Matrix3d(1, 2, 3, 1, 2, 3, 1, 2, 3))

matrix.Axis(Vector3d(1, 1, 1), math.pi)
matrix.axis(Vector3d(1, 1, 1), math.pi)
self.assertAlmostEqual(matrix, Matrix3d(1, 2, 2, 2, 1, 2, 2, 2, 1))

matrix.Col(0, Vector3d(3, 4, 5))
matrix.col(0, Vector3d(3, 4, 5))
self.assertAlmostEqual(matrix, Matrix3d(3, 2, 2, 4, 1, 2, 5, 2, 1))

matrix.Col(3, Vector3d(1, 1, 1))
matrix.col(3, Vector3d(1, 1, 1))
self.assertAlmostEqual(matrix, Matrix3d(3, 2, 1, 4, 1, 1, 5, 2, 1))

def test_sub(self):
matZero = Matrix3d.Zero
matIdent = Matrix3d.Identity
matZero = Matrix3d.ZERO
matIdent = Matrix3d.IDENTITY

mat = matIdent - matZero
self.assertAlmostEqual(mat, matIdent)
Expand All @@ -65,8 +65,8 @@ def test_sub(self):

def test_add(self):

matZero = Matrix3d.Zero
matIdent = Matrix3d.Identity
matZero = Matrix3d.ZERO
matIdent = Matrix3d.IDENTITY

mat = matIdent + matZero
self.assertAlmostEqual(mat, matIdent)
Expand All @@ -84,8 +84,8 @@ def test_add(self):
77, 88, 99))

def test_mul(self):
matZero = Matrix3d.Zero
matIdent = Matrix3d.Identity
matZero = Matrix3d.ZERO
matIdent = Matrix3d.IDENTITY

mat = matIdent * matZero
self.assertAlmostEqual(mat, matZero)
Expand Down Expand Up @@ -116,14 +116,14 @@ def test_vector3_mul(self):
matrix = Matrix3d(1, 2, 3, 4, 5, 6, 7, 8, 9)

# Scalar
self.assertAlmostEqual(Matrix3d.Zero, matrix * 0)
self.assertAlmostEqual(Matrix3d.ZERO, matrix * 0)

# Vector3.Zero
# Vector3.ZERO
self.assertAlmostEqual(Vector3d.Zero, matrix * Vector3d.Zero)

# Matrix3.Zero
self.assertAlmostEqual(Matrix3d.Zero, matrix * Matrix3d.Zero)
self.assertAlmostEqual(Matrix3d.Zero, Matrix3d.Zero * matrix)
# Matrix3.ZERO
self.assertAlmostEqual(Matrix3d.ZERO, matrix * Matrix3d.ZERO)
self.assertAlmostEqual(Matrix3d.ZERO, Matrix3d.ZERO * matrix)

matrix = Matrix3d(1, 2, 3, 4, 5, 6, 7, 8, 9)

Expand All @@ -139,9 +139,9 @@ def test_vector3_mul(self):
self.assertAlmostEqual(Vector3d(matrix(0, 2), matrix(1, 2),
matrix(2, 2)), matrix * Vector3d.UnitZ)

# Matrix3.Identity
self.assertAlmostEqual(matrix, matrix * Matrix3d.Identity)
self.assertAlmostEqual(matrix, Matrix3d.Identity * matrix)
# Matrix3.IDENTITY
self.assertAlmostEqual(matrix, matrix * Matrix3d.IDENTITY)
self.assertAlmostEqual(matrix, Matrix3d.IDENTITY * matrix)

# Multiply arbitrary matrix by itself
matrix = Matrix3d(1, 2, 3, 4, 5, 6, 7, 8, 9)
Expand Down Expand Up @@ -170,47 +170,47 @@ def test_not_equal(self):
self.assertFalse(matrix1 != matrix2)

def test_equal_tolerance(self):
self.assertFalse(Matrix3d.Zero.Equal(Matrix3d.Identity, 1e-6))
self.assertFalse(Matrix3d.Zero.Equal(Matrix3d.Identity, 1e-3))
self.assertFalse(Matrix3d.Zero.Equal(Matrix3d.Identity, 1e-1))
self.assertTrue(Matrix3d.Zero.Equal(Matrix3d.Identity, 1))
self.assertTrue(Matrix3d.Zero.Equal(Matrix3d.Identity, 1.1))
self.assertFalse(Matrix3d.ZERO.equal(Matrix3d.IDENTITY, 1e-6))
self.assertFalse(Matrix3d.ZERO.equal(Matrix3d.IDENTITY, 1e-3))
self.assertFalse(Matrix3d.ZERO.equal(Matrix3d.IDENTITY, 1e-1))
self.assertTrue(Matrix3d.ZERO.equal(Matrix3d.IDENTITY, 1))
self.assertTrue(Matrix3d.ZERO.equal(Matrix3d.IDENTITY, 1.1))

def test_inverse(self):
self.assertAlmostEqual(Matrix3d.Identity, Matrix3d.Identity.Inverse())
self.assertAlmostEqual(Matrix3d.IDENTITY, Matrix3d.IDENTITY.inverse())

# Matrix multiplied by its inverse results in the identity matrix
matrix1 = Matrix3d(-2, 4, 0, 0.1, 9, 55, -7, 1, 26)
matrix2 = matrix1.Inverse()
self.assertAlmostEqual(matrix1 * matrix2, Matrix3d.Identity)
self.assertAlmostEqual(matrix2 * matrix1, Matrix3d.Identity)
matrix2 = matrix1.inverse()
self.assertAlmostEqual(matrix1 * matrix2, Matrix3d.IDENTITY)
self.assertAlmostEqual(matrix2 * matrix1, Matrix3d.IDENTITY)

# Inverse of inverse results in the same matrix
self.assertAlmostEqual((matrix1.Inverse()).Inverse(), matrix1)
self.assertAlmostEqual((matrix1.inverse()).inverse(), matrix1)

# Invert multiplication by scalar
scalar = 2.5
self.assertAlmostEqual((matrix1 * scalar).Inverse(),
matrix1.Inverse() * (1.0/scalar))
self.assertAlmostEqual((matrix1 * scalar).inverse(),
matrix1.inverse() * (1.0/scalar))

def test_determinant(self):
# |Zero matrix| = 0.0
self.assertAlmostEqual(0.0, Matrix3d.Zero.Determinant())
# |ZERO matrix| = 0.0
self.assertAlmostEqual(0.0, Matrix3d.ZERO.determinant())

# |Identity matrix| = 1.0
self.assertAlmostEqual(1.0, Matrix3d.Identity.Determinant())
# |IDENTITY matrix| = 1.0
self.assertAlmostEqual(1.0, Matrix3d.IDENTITY.determinant())

# Determinant of arbitrary matrix
m = Matrix3d(-2, 4, 0, 0.1, 9, 55, -7, 1, 26)
self.assertAlmostEqual(-1908.4, m.Determinant())
self.assertAlmostEqual(-1908.4, m.determinant())

def test_transpose(self):
# Transpose of zero matrix is itself
self.assertAlmostEqual(Matrix3d.Zero, Matrix3d.Zero.Transposed())
# transpose of zero matrix is itself
self.assertAlmostEqual(Matrix3d.ZERO, Matrix3d.ZERO.transposed())

# Transpose of identity matrix is itself
self.assertAlmostEqual(Matrix3d.Identity,
Matrix3d.Identity.Transposed())
# transpose of identity matrix is itself
self.assertAlmostEqual(Matrix3d.IDENTITY,
Matrix3d.IDENTITY.transposed())

# Matrix and expected transpose
m = Matrix3d(-2, 4, 0,
Expand All @@ -220,79 +220,79 @@ def test_transpose(self):
4, 9, 1,
0, 55, 26)
self.assertNotEqual(m, mT)
self.assertAlmostEqual(m.Transposed(), mT)
self.assertAlmostEqual(m.Determinant(), m.Transposed().Determinant())
self.assertAlmostEqual(m.transposed(), mT)
self.assertAlmostEqual(m.determinant(), m.transposed().determinant())

mT.Transpose()
mT.transpose()
self.assertAlmostEqual(m, mT)

def test_from2axes(self):
def test_from_2axes(self):
v1 = Vector3d(1.0, 0.0, 0.0)
v2 = Vector3d(0.0, 1.0, 0.0)

m1 = Matrix3d()
m1.From2Axes(v1, v2)
m1.from_2axes(v1, v2)

m2 = Matrix3d()
m2.From2Axes(v2, v1)
m2.from_2axes(v2, v1)

m1Correct = Matrix3d(0, -1, 0,
1, 0, 0,
0, 0, 1)
m2Correct = Matrix3d(m1Correct)
m2Correct.Transpose()
m2Correct.transpose()

self.assertNotEqual(m1, m2)
self.assertAlmostEqual(m1Correct, m1)
self.assertAlmostEqual(m2Correct, m2)
self.assertAlmostEqual(Matrix3d.Identity, m1 * m2)
self.assertAlmostEqual(Matrix3d.IDENTITY, m1 * m2)
self.assertAlmostEqual(v2, m1 * v1)
self.assertAlmostEqual(v1, m2 * v2)

# rotation about 45 degrees
v1.Set(1.0, 0.0, 0.0)
v2.Set(1.0, 1.0, 0.0)
m2.From2Axes(v1, v2)
m2.from_2axes(v1, v2)
# m1 is 90 degrees rotation
self.assertAlmostEqual(m1, m2*m2)

# with non-unit vectors
v1.Set(0.5, 0.5, 0)
v2.Set(-0.5, 0.5, 0)

m1.From2Axes(v1, v2)
m2.From2Axes(v2, v1)
m1.from_2axes(v1, v2)
m2.from_2axes(v2, v1)

self.assertNotEqual(m1, m2)
self.assertAlmostEqual(m1Correct, m1)
self.assertAlmostEqual(m2Correct, m2)
self.assertAlmostEqual(Matrix3d.Identity, m1 * m2)
self.assertAlmostEqual(Matrix3d.IDENTITY, m1 * m2)
self.assertAlmostEqual(v2, m1 * v1)
self.assertAlmostEqual(v1, m2 * v2)

# For zero-length vectors, a unit matrix is returned
v1.Set(0, 0, 0)
v2.Set(-0.5, 0.5, 0)
m1.From2Axes(v1, v2)
self.assertAlmostEqual(Matrix3d.Identity, m1)
m1.from_2axes(v1, v2)
self.assertAlmostEqual(Matrix3d.IDENTITY, m1)

# For zero-length vectors, a unit matrix is returned
v1.Set(-0.5, 0.5, 0)
v2.Set(0, 0, 0)
m1.From2Axes(v1, v2)
self.assertAlmostEqual(Matrix3d.Identity, m1)
m1.from_2axes(v1, v2)
self.assertAlmostEqual(Matrix3d.IDENTITY, m1)

# Parallel vectors
v1.Set(1, 0, 0)
v2.Set(2, 0, 0)
m1.From2Axes(v1, v2)
self.assertAlmostEqual(Matrix3d.Identity, m1)
m1.from_2axes(v1, v2)
self.assertAlmostEqual(Matrix3d.IDENTITY, m1)

# Opposite vectors
v1.Set(1, 0, 0)
v2.Set(-2, 0, 0)
m1.From2Axes(v1, v2)
self.assertAlmostEqual(Matrix3d.Zero - Matrix3d.Identity, m1)
m1.from_2axes(v1, v2)
self.assertAlmostEqual(Matrix3d.ZERO - Matrix3d.IDENTITY, m1)


if __name__ == '__main__':
Expand Down
5 changes: 3 additions & 2 deletions src/Matrix4.i
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,9 @@ namespace ignition
template<typename T>
class Matrix4
{
%rename("%(undercase)s", %$isfunction, %$ismember, %$not %$isconstructor) "";
%rename("%(uppercase)s", %$isstatic, %$isvariable) "";

public: static const Matrix4<T> Identity;
public: static const Matrix4<T> Zero;

Expand Down Expand Up @@ -76,8 +79,6 @@ namespace ignition
public: bool operator!=(const Matrix4<T> &_m) const;
public: static Matrix4<T> LookAt(const Vector3<T> &_eye,
const Vector3<T> &_target, const Vector3<T> &_up = Vector3<T>::UnitZ);

private: T data[4][4];
};

%extend Matrix4{
Expand Down
Loading

0 comments on commit ad00569

Please sign in to comment.