Skip to content

Commit

Permalink
Adds python interface to Quaternion, Pose3, Matrix3 and Matrix4 (#221)
Browse files Browse the repository at this point in the history
* Adds scripting interface to Quaternion and a python test
* Adds scripting interface to Matrix3 and a python test
* Adds scripting interface to Pose3 and a python test
* Solves bug in the Reset() method inside Pose3
* Adds scripting interface to Matrix4 and a python test
* Solves bug in the Construct test for Matrix4 class
* Adds %rename tag to interface files in order to match pep-8 naiming style.
* Adds a python method to convert from a Matrix3 to a Quaternion.
* Adds to_quaternion() method to Matrix3.

Signed-off-by: LolaSegura <[email protected]>

* Adds python binding for Quaternion::ToAxis method.

Signed-off-by: Franco Cipollone <[email protected]>

* Matrix3_TEST: improve multiplication test

This changes the test matrices that are multiplied
togther so that they aren't scalar multiples of each other.
This confirms non-commutativity in the test.

* Matrix3_TEST.py: add stream out test

Signed-off-by: Steve Peters <[email protected]>

Co-authored-by: Franco Cipollone <[email protected]>
Co-authored-by: Franco Cipollone <[email protected]>
Co-authored-by: Steve Peters <[email protected]>
Signed-off-by: Arjo Chakravarty <[email protected]>
  • Loading branch information
4 people authored and arjo129 committed Sep 20, 2021
1 parent 9979f83 commit 5c9343f
Show file tree
Hide file tree
Showing 13 changed files with 2,109 additions and 51 deletions.
2 changes: 1 addition & 1 deletion include/ignition/math/Pose3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -327,7 +327,7 @@ namespace ignition
{
// set the position to zero
this->p.Set();
this->q = Quaterniond::Identity;
this->q = Quaternion<T>::Identity;
}

/// \brief Rotate vector part of a pose about the origin
Expand Down
24 changes: 12 additions & 12 deletions src/Matrix3_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -131,24 +131,24 @@ TEST(Matrix3dTest, OperatorMul)
4, 5, 6,
7, 8, 9);

math::Matrix3d matB(10, 20, 30,
40, 50, 60,
70, 80, 90);
math::Matrix3d matB(11, 21, 31,
41, 51, 61,
71, 81, 91);

mat = matA * matB;
EXPECT_EQ(mat, math::Matrix3d(300, 360, 420,
660, 810, 960,
1020, 1260, 1500));
EXPECT_EQ(mat, math::Matrix3d(306, 366, 426,
675, 825, 975,
1044, 1284, 1524));

mat = matB * matA;
EXPECT_EQ(mat, math::Matrix3d(300, 360, 420,
660, 810, 960,
1020, 1260, 1500));
EXPECT_EQ(mat, math::Matrix3d(312, 375, 438,
672, 825, 978,
1032, 1275, 1518));

mat = mat * 2.0;
EXPECT_EQ(mat, math::Matrix3d(600, 720, 840,
1320, 1620, 1920,
2040, 2520, 3000));
EXPECT_EQ(mat, math::Matrix3d(624, 750, 876,
1344, 1650, 1956,
2064, 2550, 3036));
}

/////////////////////////////////////////////////
Expand Down
78 changes: 40 additions & 38 deletions src/Matrix4_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ TEST(Matrix4dTest, Construct)
{
for (int j = 0; j < 4; ++j)
{
EXPECT_DOUBLE_EQ(mat(i, i), 0.0);
EXPECT_DOUBLE_EQ(mat(i, j), 0.0);
}
}

Expand All @@ -41,17 +41,16 @@ TEST(Matrix4dTest, Construct)
{
for (int j = 0; j < 4; ++j)
{
EXPECT_DOUBLE_EQ(mat2(i, i), 0.0);
EXPECT_DOUBLE_EQ(mat2(i, j), 0.0);
}
}
EXPECT_TRUE(mat2 == mat);


// Set individual values.
math::Matrix4d mat3(0.0, 1.0, 2.0, 3.0,
4.0, 5.0, 6.0, 7.0,
8.0, 9.0, 10.0, 11.0,
12.0, 13.0, 14.0, 15.0);
4.0, 5.0, 6.0, 7.0,
8.0, 9.0, 10.0, 11.0,
12.0, 13.0, 14.0, 15.0);

math::Matrix4d mat4;
mat4 = mat3;
Expand Down Expand Up @@ -126,7 +125,7 @@ TEST(Matrix4dTest, ConstructFromPose3d)
// Rotate pitch by pi/2 so yaw coincides with roll causing a gimbal lock
{
math::Vector3d trans(3, 2, 1);
math::Quaterniond qt(0, IGN_PI/2, 0);
math::Quaterniond qt(0, IGN_PI / 2, 0);
math::Pose3d pose(trans, qt);
math::Matrix4d mat(pose);

Expand All @@ -138,9 +137,9 @@ TEST(Matrix4dTest, ConstructFromPose3d)

{
// setup a ZXZ rotation to ensure non-commutative rotations
math::Pose3d pose1(1, -2, 3, 0, 0, IGN_PI/4);
math::Pose3d pose2(0, 1, -1, -IGN_PI/4, 0, 0);
math::Pose3d pose3(-1, 0, 0, 0, 0, -IGN_PI/4);
math::Pose3d pose1(1, -2, 3, 0, 0, IGN_PI / 4);
math::Pose3d pose2(0, 1, -1, -IGN_PI / 4, 0, 0);
math::Pose3d pose3(-1, 0, 0, 0, 0, -IGN_PI / 4);

math::Matrix4d m1(pose1);
math::Matrix4d m2(pose2);
Expand Down Expand Up @@ -238,7 +237,7 @@ TEST(Matrix4dTest, MultiplyV)
{
for (int j = 0; j < 4; ++j)
{
mat(i, j) = i-j;
mat(i, j) = i - j;
}
}

Expand All @@ -254,8 +253,8 @@ TEST(Matrix4dTest, Multiply4)
{
for (int j = 0; j < 4; ++j)
{
mat(i, j) = i-j;
mat1(j, i) = i+j;
mat(i, j) = i - j;
mat1(j, i) = i + j;
}
}

Expand All @@ -277,28 +276,28 @@ TEST(Matrix4dTest, Multiply4)
TEST(Matrix4dTest, Inverse)
{
math::Matrix4d mat(2, 3, 1, 5,
1, 0, 3, 1,
0, 2, -3, 2,
0, 2, 3, 1);
1, 0, 3, 1,
0, 2, -3, 2,
0, 2, 3, 1);

math::Matrix4d mat1 = mat.Inverse();
EXPECT_EQ(mat1, math::Matrix4d(18, -35, -28, 1,
9, -18, -14, 1,
-2, 4, 3, 0,
-12, 24, 19, -1));
9, -18, -14, 1,
-2, 4, 3, 0,
-12, 24, 19, -1));
}

/////////////////////////////////////////////////
TEST(Matrix4dTest, GetAsPose3d)
{
math::Matrix4d mat(2, 3, 1, 5,
1, 0, 3, 1,
0, 2, -3, 2,
0, 2, 3, 1);
1, 0, 3, 1,
0, 2, -3, 2,
0, 2, 3, 1);
math::Pose3d pose = mat.Pose();

EXPECT_EQ(pose,
math::Pose3d(5, 1, 2, -0.204124, 1.22474, 0.816497, 0.204124));
math::Pose3d(5, 1, 2, -0.204124, 1.22474, 0.816497, 0.204124));
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -408,7 +407,6 @@ TEST(Matrix4dTest, RotationDiagLessThanZero)
EXPECT_EQ(euler, math::Vector3d(-1.5708, 4.26136, -1.3734));
}


{
mat(0, 0) = -0.1;
mat(1, 1) = -0.2;
Expand All @@ -428,7 +426,6 @@ TEST(Matrix4dTest, RotationDiagLessThanZero)
}
}


/////////////////////////////////////////////////
TEST(Matrix4dTest, Rotation)
{
Expand Down Expand Up @@ -632,14 +629,14 @@ TEST(Matrix4dTest, Transpose)
EXPECT_EQ(math::Matrix4d::Identity, math::Matrix4d::Identity.Transposed());

// Matrix and expected transpose
math::Matrix4d m(-2, 4, 0, -3.5,
0.1, 9, 55, 1.2,
math::Matrix4d m(-2, 4, 0, -3.5,
0.1, 9, 55, 1.2,
-7, 1, 26, 11.5,
.2, 3, -5, -0.1);
math::Matrix4d mT(-2, 0.1, -7, .2,
4, 9, 1, 3,
0, 55, 26, -5,
-3.5, 1.2, 11.5, -0.1);
math::Matrix4d mT(-2, 0.1, -7, .2,
4, 9, 1, 3,
0, 55, 26, -5,
-3.5, 1.2, 11.5, -0.1);
EXPECT_NE(m, mT);
EXPECT_EQ(m.Transposed(), mT);
EXPECT_DOUBLE_EQ(m.Determinant(), m.Transposed().Determinant());
Expand All @@ -652,19 +649,23 @@ TEST(Matrix4dTest, Transpose)
TEST(Matrix4dTest, LookAt)
{
EXPECT_EQ(math::Matrix4d::LookAt(-math::Vector3d::UnitX,
math::Vector3d::Zero).Pose(),
math::Vector3d::Zero)
.Pose(),
math::Pose3d(-1, 0, 0, 0, 0, 0));

EXPECT_EQ(math::Matrix4d::LookAt(math::Vector3d(3, 2, 0),
math::Vector3d(0, 2, 0)).Pose(),
math::Vector3d(0, 2, 0))
.Pose(),
math::Pose3d(3, 2, 0, 0, 0, IGN_PI));

EXPECT_EQ(math::Matrix4d::LookAt(math::Vector3d(1, 6, 1),
math::Vector3d::One).Pose(),
math::Vector3d::One)
.Pose(),
math::Pose3d(1, 6, 1, 0, 0, -IGN_PI_2));

EXPECT_EQ(math::Matrix4d::LookAt(math::Vector3d(-1, -1, 0),
math::Vector3d(1, 1, 0)).Pose(),
math::Vector3d(1, 1, 0))
.Pose(),
math::Pose3d(-1, -1, 0, 0, 0, IGN_PI_4));

// Default up is Z
Expand Down Expand Up @@ -711,12 +712,13 @@ TEST(Matrix4dTest, LookAt)
// Different ups
EXPECT_EQ(math::Matrix4d::LookAt(math::Vector3d::One,
math::Vector3d(0, 1, 1),
math::Vector3d::UnitY).Pose(),
math::Vector3d::UnitY)
.Pose(),
math::Pose3d(1, 1, 1, IGN_PI_2, 0, IGN_PI));

EXPECT_EQ(math::Matrix4d::LookAt(math::Vector3d::One,
math::Vector3d(0, 1, 1),
math::Vector3d(0, 1, 1)).Pose(),
math::Vector3d(0, 1, 1))
.Pose(),
math::Pose3d(1, 1, 1, IGN_PI_4, 0, IGN_PI));
}

4 changes: 4 additions & 0 deletions src/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -93,8 +93,12 @@ if (PYTHONLIBS_FOUND)
Kmeans_TEST
Line2_TEST
Line3_TEST
Matrix3_TEST
Matrix4_TEST
PID_TEST
Pose3_TEST
python_TEST
Quaternion_TEST
Rand_TEST
RollingMean_TEST
SemanticVersion_TEST
Expand Down
97 changes: 97 additions & 0 deletions src/python/Matrix3.i
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* 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.
*
*/

%module matrix3
%{
#include <ignition/math/config.hh>
#include <ignition/math/Helpers.hh>
#include <ignition/math/Matrix3.hh>
#include <ignition/math/Quaternion.hh>
#include <ignition/math/Vector3.hh>
%}

%include "std_string.i"
%include Quaternion.i

namespace ignition
{
namespace math
{
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();
public: Matrix3(const Matrix3<T> &_m);
public: Matrix3(T _v00, T _v01, T _v02,
T _v10, T _v11, T _v12,
T _v20, T _v21, T _v22);
public: explicit Matrix3(const Quaternion<T> &_q);
public: virtual ~Matrix3() {}
public: void Set(T _v00, T _v01, T _v02,
T _v10, T _v11, T _v12,
T _v20, T _v21, T _v22);
public: void Axes(const Vector3<T> &_xAxis,
const Vector3<T> &_yAxis,
const Vector3<T> &_zAxis);
public: void Axis(const Vector3<T> &_axis, T _angle);
%rename(from_2_axes) From2Axes;
public: void From2Axes(const Vector3<T> &_v1, const Vector3<T> &_v2);
public: void Col(unsigned int _c, const Vector3<T> &_v);
public: Matrix3<T> operator-(const Matrix3<T> &_m) const;
public: Matrix3<T> operator+(const Matrix3<T> &_m) const;
public: Matrix3<T> operator*(const T &_s) const;
public: Matrix3<T> operator*(const Matrix3<T> &_m) const;
public: Vector3<T> operator*(const Vector3<T> &_vec) const;
public: bool Equal(const Matrix3 &_m, const T &_tol) const;
public: bool operator==(const Matrix3<T> &_m) const;
public: bool operator!=(const Matrix3<T> &_m) const;;
public: T Determinant() const;
public: Matrix3<T> Inverse() const;
public: void Transpose();
public: Matrix3<T> Transposed() const;
};

%extend Matrix3{
T __call__(size_t row, size_t col) const {
return (*$self)(row, col);
}
}

%extend Matrix3 {
std::string __str__() const {
std::ostringstream out;
out << *$self;
return out.str();
}
}

%extend Matrix3 {
ignition::math::Quaternion<T> to_quaternion() {
return ignition::math::Quaternion<T>(*$self);
}
}

%template(Matrix3i) Matrix3<int>;
%template(Matrix3d) Matrix3<double>;
%template(Matrix3f) Matrix3<float>;
}
}
Loading

0 comments on commit 5c9343f

Please sign in to comment.