From 7185147652f3aa5e8bfd4219b1e0a98ba0a8c7d9 Mon Sep 17 00:00:00 2001 From: Benoit Maurin Date: Sun, 11 Aug 2024 23:17:56 +0200 Subject: [PATCH] buffer_protocol for vectors and matrices Also IndexError is raised on invalid vector __getitem__/__setitem__ access. This way list(vector) works correctly instead of spinning Signed-off-by: Benoit Maurin --- include/gz/math/Matrix3.hh | 66 ++++-------------------- include/gz/math/Matrix4.hh | 21 ++++---- include/gz/math/Matrix6.hh | 18 +++---- include/gz/math/Vector2.hh | 21 ++++---- include/gz/math/Vector3.hh | 21 ++++---- include/gz/math/Vector4.hh | 21 ++++---- src/python_pybind11/src/Matrix3.hh | 11 ++++ src/python_pybind11/src/Matrix4.hh | 11 ++++ src/python_pybind11/src/Matrix6.hh | 11 ++++ src/python_pybind11/src/Quaternion.hh | 5 +- src/python_pybind11/src/Vector2.hh | 23 +++++++-- src/python_pybind11/src/Vector3.hh | 23 +++++++-- src/python_pybind11/src/Vector4.hh | 23 +++++++-- src/python_pybind11/test/Matrix3_TEST.py | 7 ++- src/python_pybind11/test/Matrix4_TEST.py | 6 ++- src/python_pybind11/test/Matrix6_TEST.py | 8 ++- src/python_pybind11/test/Vector2_TEST.py | 9 +++- src/python_pybind11/test/Vector3_TEST.py | 9 ++++ src/python_pybind11/test/Vector4_TEST.py | 5 ++ src/python_pybind11/test/test_common.py | 35 +++++++++++++ 20 files changed, 222 insertions(+), 132 deletions(-) create mode 100644 src/python_pybind11/test/test_common.py diff --git a/include/gz/math/Matrix3.hh b/include/gz/math/Matrix3.hh index e96d76079..590cc6be2 100644 --- a/include/gz/math/Matrix3.hh +++ b/include/gz/math/Matrix3.hh @@ -105,10 +105,6 @@ namespace gz::math std::memset(this->data, 0, sizeof(this->data[0][0])*9); } - /// \brief Copy constructor. - /// \param _m Matrix to copy - public: Matrix3(const Matrix3 &_m) = default; - /// \brief Construct a matrix3 using nine values. /// \param[in] _v00 Row 0, Col 0 value /// \param[in] _v01 Row 0, Col 1 value @@ -145,9 +141,6 @@ namespace gz::math 1 - 2 * qt.X()*qt.X() - 2 * qt.Y()*qt.Y()); } - /// \brief Desctructor - public: ~Matrix3() = default; - /// \brief Set a single value. /// \param[in] _row row index. _row is clamped to the range [0,2] /// \param[in] _col column index. _col is clamped to the range [0,2] @@ -183,19 +176,6 @@ namespace gz::math this->data[2][2] = _v22; } - /// \brief Set the matrix from three axis (1 per column). - /// \param[in] _xAxis The x axis, the first column of the matrix. - /// \param[in] _yAxis The y axis, the second column of the matrix. - /// \param[in] _zAxis The z axis, the third column of the matrix. - /// \deprecated Use SetAxes(const Vector3 &, const Vector3 &, - /// const Vector3 &,) - public: void GZ_DEPRECATED(7) Axes(const Vector3 &_xAxis, - const Vector3 &_yAxis, - const Vector3 &_zAxis) - { - this->SetAxes(_xAxis, _yAxis, _zAxis); - } - /// \brief Set the matrix from three axis (1 per column). /// \param[in] _xAxis The x axis, the first column of the matrix. /// \param[in] _yAxis The y axis, the second column of the matrix. @@ -209,15 +189,6 @@ namespace gz::math this->SetCol(2, _zAxis); } - /// \brief Set as a rotation matrix from an axis and angle. - /// \param[in] _axis the axis - /// \param[in] _angle ccw rotation around the axis in radians - /// \deprecated Use SetFromAxisAngle(const Vector3 &, T) - public: void GZ_DEPRECATED(7) Axis(const Vector3 &_axis, T _angle) - { - this->SetFromAxisAngle(_axis, _angle); - } - /// \brief Set as a rotation matrix from an axis and angle. /// \param[in] _axis the axis /// \param[in] _angle ccw rotation around the axis in radians @@ -240,19 +211,6 @@ namespace gz::math this->data[2][2] = _axis.Z()*_axis.Z()*C + c; } - /// \brief Set as a rotation matrix to represent rotation from - /// vector _v1 to vector _v2, so that - /// _v2.Normalize() == this * _v1.Normalize() holds. - /// - /// \param[in] _v1 The first vector - /// \param[in] _v2 The second vector - /// \deprecated Use SetFrom2Axes(const Vector3 &, const Vector3 &) - public: void GZ_DEPRECATED(7) From2Axes( - const Vector3 &_v1, const Vector3 &_v2) - { - this->SetFrom2Axes(_v1, _v2); - } - /// \brief Set as a rotation matrix to represent rotation from /// vector _v1 to vector _v2, so that /// _v2.Normalize() == this * _v1.Normalize() holds. @@ -296,16 +254,6 @@ namespace gz::math this->SetFromAxisAngle(cross, acos(dot)); } - /// \brief Set a column. - /// \param[in] _c The colum index [0, 1, 2]. _col is clamped to the - /// range [0, 2]. - /// \param[in] _v The value to set in each row of the column. - /// \deprecated Use SetCol(unsigned int _c, const Vector3 &_v) - public: void GZ_DEPRECATED(7) Col(unsigned int _c, const Vector3 &_v) - { - this->SetCol(_c, _v); - } - /// \brief Set a column. /// \param[in] _c The colum index [0, 1, 2]. _col is clamped to the /// range [0, 2]. @@ -319,11 +267,6 @@ namespace gz::math this->data[2][c] = _v.Z(); } - /// \brief Equal operator. this = _mat - /// \param _mat Matrix to copy. - /// \return This matrix. - public: Matrix3 &operator=(const Matrix3 &_mat) = default; - /// \brief Subtraction operator. /// \param[in] _m Matrix to subtract. /// \return The element wise difference of two matrices. @@ -633,6 +576,15 @@ namespace gz::math return _in; } + /// \brief Underlying data pointer + /// \remarks This method is intended for python bindings (numpy). + /// \remarks It's preferable not to rely on it. + /// \return The pointer to the underlying data. + public: T* Data() + { + return this->data[0]; + } + /// \brief the 3x3 matrix private: T data[3][3]; }; diff --git a/include/gz/math/Matrix4.hh b/include/gz/math/Matrix4.hh index 24834096d..40970731b 100644 --- a/include/gz/math/Matrix4.hh +++ b/include/gz/math/Matrix4.hh @@ -47,10 +47,6 @@ namespace gz::math memset(this->data, 0, sizeof(this->data[0][0])*16); } - /// \brief Copy constructor - /// \param _m Matrix to copy - public: Matrix4(const Matrix4 &_m) = default; - /// \brief Constructor /// \param[in] _v00 Row 0, Col 0 value /// \param[in] _v01 Row 0, Col 1 value @@ -110,9 +106,6 @@ namespace gz::math this->SetTranslation(_pose.Pos()); } - /// \brief Destructor - public: ~Matrix4() = default; - /// \brief Change the values /// \param[in] _v00 Row 0, Col 0 value /// \param[in] _v01 Row 0, Col 1 value @@ -539,11 +532,6 @@ namespace gz::math this->data[0][3], this->data[1][3], this->data[2][3], this->data[3][3]); } - /// \brief Equal operator. this = _mat - /// \param _mat Incoming matrix - /// \return itself - public: Matrix4 &operator=(const Matrix4 &_mat) = default; - /// \brief Equal operator for 3x3 matrix /// \param _mat Incoming matrix /// \return itself @@ -841,6 +829,15 @@ namespace gz::math 0, 0, 0, 1); } + /// \brief Underlying data pointer + /// \remarks This method is intended for python bindings (numpy). + /// \remarks It's preferable not to rely on it. + /// \return The pointer to the underlying data. + public: T* Data() + { + return this->data[0]; + } + /// \brief The 4x4 matrix private: T data[4][4]; }; diff --git a/include/gz/math/Matrix6.hh b/include/gz/math/Matrix6.hh index b6aeae29e..5f0b33d8b 100644 --- a/include/gz/math/Matrix6.hh +++ b/include/gz/math/Matrix6.hh @@ -67,10 +67,6 @@ namespace gz::math memset(this->data, 0, sizeof(this->data[0][0])*MatrixSize*MatrixSize); } - /// \brief Copy constructor - /// \param _m Matrix to copy - public: Matrix6(const Matrix6 &_m) = default; - /// \brief Constructor /// \param[in] _v00 Row 0, Col 0 value /// \param[in] _v01 Row 0, Col 1 value @@ -294,11 +290,6 @@ namespace gz::math this->data[5][5]); } - /// \brief Assignment operator. this = _mat - /// \param _mat Incoming matrix - /// \return itself - public: Matrix6 &operator=(const Matrix6 &_mat) = default; - /// \brief Multiplication assignment operator. This matrix will /// become equal to this * _m2. /// \param[in] _m2 Incoming matrix. @@ -550,6 +541,15 @@ namespace gz::math return _in; } + /// \brief Underlying data pointer + /// \remarks This method is intended for python bindings (numpy). + /// \remarks It's preferable not to rely on it. + /// \return The pointer to the underlying data. + public: T* Data() + { + return this->data[0]; + } + /// \brief The 6x6 matrix private: T data[MatrixSize][MatrixSize]; }; diff --git a/include/gz/math/Vector2.hh b/include/gz/math/Vector2.hh index 031582bbe..a7a2b069b 100644 --- a/include/gz/math/Vector2.hh +++ b/include/gz/math/Vector2.hh @@ -59,13 +59,6 @@ namespace gz::math { } - /// \brief Copy constructor - /// \param[in] _v the value - public: Vector2(const Vector2 &_v) = default; - - /// \brief Destructor - public: ~Vector2() = default; - /// \brief Return the sum of the values /// \return the sum public: T Sum() const @@ -219,11 +212,6 @@ namespace gz::math return std::min(this->data[0], this->data[1]); } - /// \brief Assignment operator - /// \param[in] _v a value for x and y element - /// \return this - public: Vector2 &operator=(const Vector2 &_v) = default; - /// \brief Assignment operator /// \param[in] _v the value for x and y element /// \return this @@ -568,6 +556,15 @@ namespace gz::math return _in; } + /// \brief Underlying data pointer + /// \remarks This method is intended for python bindings (numpy). + /// \remarks It's preferable not to rely on it. + /// \return The pointer to the underlying data. + public: T* Data() + { + return this->data; + } + /// \brief The x and y values. private: T data[2]; }; diff --git a/include/gz/math/Vector3.hh b/include/gz/math/Vector3.hh index 00d58ec8f..5e88cd815 100644 --- a/include/gz/math/Vector3.hh +++ b/include/gz/math/Vector3.hh @@ -71,13 +71,6 @@ namespace gz::math { } - /// \brief Copy constructor - /// \param[in] _v a vector - public: Vector3(const Vector3 &_v) = default; - - /// \brief Destructor - public: ~Vector3() = default; - /// \brief Return the sum of the values /// \return the sum public: T Sum() const @@ -322,11 +315,6 @@ namespace gz::math return min; } - /// \brief Assignment operator - /// \param[in] _v a new value - /// \return this - public: Vector3 &operator=(const Vector3 &_v) = default; - /// \brief Assignment operator /// \param[in] _v assigned to all elements /// \return this @@ -758,6 +746,15 @@ namespace gz::math return _in; } + /// \brief Underlying data pointer + /// \remarks This method is intended for python bindings (numpy). + /// \remarks It's preferable not to rely on it. + /// \return The pointer to the underlying data. + public: T* Data() + { + return this->data; + } + /// \brief The x, y, and z values private: T data[3]; }; diff --git a/include/gz/math/Vector4.hh b/include/gz/math/Vector4.hh index c27a370e6..c519f4dc6 100644 --- a/include/gz/math/Vector4.hh +++ b/include/gz/math/Vector4.hh @@ -61,13 +61,6 @@ namespace gz::math { } - /// \brief Copy constructor - /// \param[in] _v vector - public: Vector4(const Vector4 &_v) = default; - - /// \brief Destructor - public: ~Vector4() = default; - /// \brief Calc distance to the given point /// \param[in] _pt the point /// \return the distance @@ -258,11 +251,6 @@ namespace gz::math return this->data[0] + this->data[1] + this->data[2] + this->data[3]; } - /// \brief Assignment operator - /// \param[in] _v the vector - /// \return a reference to this vector - public: Vector4 &operator=(const Vector4 &_v) = default; - /// \brief Assignment operator /// \param[in] _value public: Vector4 &operator=(T _value) @@ -718,6 +706,15 @@ namespace gz::math return _in; } + /// \brief Underlying data pointer + /// \remarks This method is intended for python bindings (numpy). + /// \remarks It's preferable not to rely on it. + /// \return The pointer to the underlying data. + public: T* Data() + { + return this->data; + } + /// \brief Data values, 0==x, 1==y, 2==z, 3==w private: T data[4]; }; diff --git a/src/python_pybind11/src/Matrix3.hh b/src/python_pybind11/src/Matrix3.hh index fd8c4193d..012e150d3 100644 --- a/src/python_pybind11/src/Matrix3.hh +++ b/src/python_pybind11/src/Matrix3.hh @@ -51,6 +51,7 @@ template void helpDefineMathMatrix3(py::module &m, const std::string &typestr) { using Class = gz::math::Matrix3; + const int mat_size = 3; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -122,6 +123,16 @@ void helpDefineMathMatrix3(py::module &m, const std::string &typestr) }, "memo"_a) .def_readonly_static("IDENTITY", &Class::Identity, "Identity matrix") .def_readonly_static("ZERO", &Class::Zero, "Zero matrix") + .def_buffer([](Class &self) -> py::buffer_info { + return py::buffer_info( + self.Data(), + sizeof(T), + py::format_descriptor::format(), + 2, + { mat_size, mat_size }, + { mat_size * sizeof(T), sizeof(T) } + ); + }) .def("__str__", toString) .def("__repr__", toString); } diff --git a/src/python_pybind11/src/Matrix4.hh b/src/python_pybind11/src/Matrix4.hh index c58d79e9f..bc43f7de8 100644 --- a/src/python_pybind11/src/Matrix4.hh +++ b/src/python_pybind11/src/Matrix4.hh @@ -51,6 +51,7 @@ template void helpDefineMathMatrix4(py::module &m, const std::string &typestr) { using Class = gz::math::Matrix4; + const int mat_size = 4; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -144,6 +145,16 @@ void helpDefineMathMatrix4(py::module &m, const std::string &typestr) }, "memo"_a) .def_readonly_static("IDENTITY", &Class::Identity, "Identity matrix") .def_readonly_static("ZERO", &Class::Zero, "Zero matrix") + .def_buffer([](Class &self) -> py::buffer_info { + return py::buffer_info( + self.Data(), + sizeof(T), + py::format_descriptor::format(), + 2, + { mat_size, mat_size }, + { mat_size * sizeof(T), sizeof(T) } + ); + }) .def("__str__", toString) .def("__repr__", toString); } diff --git a/src/python_pybind11/src/Matrix6.hh b/src/python_pybind11/src/Matrix6.hh index 07dc647ef..6f6bbc5aa 100644 --- a/src/python_pybind11/src/Matrix6.hh +++ b/src/python_pybind11/src/Matrix6.hh @@ -51,6 +51,7 @@ template void helpDefineMathMatrix6(py::module &_m, const std::string &_typestr) { using Class = Matrix6; + const int mat_size = 6; auto toString = [](const Class &_si) { std::stringstream stream; stream << _si; @@ -98,6 +99,16 @@ void helpDefineMathMatrix6(py::module &_m, const std::string &_typestr) }, "memo"_a) .def_readonly_static("IDENTITY", &Class::Identity, "Identity matrix") .def_readonly_static("ZERO", &Class::Zero, "Zero matrix") + .def_buffer([](Class &self) -> py::buffer_info { + return py::buffer_info( + self.Data(), + sizeof(T), + py::format_descriptor::format(), + 2, + { mat_size, mat_size }, + { mat_size * sizeof(T), sizeof(T) } + ); + }) .def("__str__", toString) .def("__repr__", toString); } diff --git a/src/python_pybind11/src/Quaternion.hh b/src/python_pybind11/src/Quaternion.hh index 5ae9c5503..451ed6a49 100644 --- a/src/python_pybind11/src/Quaternion.hh +++ b/src/python_pybind11/src/Quaternion.hh @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -62,7 +63,6 @@ void helpDefineMathQuaternion(py::module &m, const std::string &typestr) std::string pyclass_name = typestr; py::class_(m, pyclass_name.c_str(), - py::buffer_protocol(), py::dynamic_attr()) .def(py::init<>()) .def(py::init()) @@ -210,6 +210,9 @@ void helpDefineMathQuaternion(py::module &m, const std::string &typestr) }, "memo"_a) .def_readonly_static("IDENTITY", &Class::Identity, "Identity matrix") .def_readonly_static("ZERO", &Class::Zero, "Zero matrix") + .def("xyzw", [](const Class &self){ + return std::vector { self.X(), self.Y(), self.Z(), self.W() }; + }, "Number of elements in the vector") .def("__str__", toString) .def("__repr__", toString); } diff --git a/src/python_pybind11/src/Vector2.hh b/src/python_pybind11/src/Vector2.hh index 5f1b965fa..9cf3a2cd3 100644 --- a/src/python_pybind11/src/Vector2.hh +++ b/src/python_pybind11/src/Vector2.hh @@ -43,6 +43,7 @@ template void helpDefineMathVector2(py::module &m, const std::string &typestr) { using Class = gz::math::Vector2; + const int vec_size = 2; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -132,10 +133,24 @@ void helpDefineMathVector2(py::module &m, const std::string &typestr) .def("__deepcopy__", [](const Class &self, py::dict) { return Class(self); }, "memo"_a) - .def("__getitem__", - py::overload_cast(&Class::operator[], py::const_)) - .def("__setitem__", - [](Class* vec, unsigned index, T val) { (*vec)[index] = val; }) + .def("__getitem__", [](const Class &self, unsigned index) { + if (index >= vec_size) throw py::index_error("Invalid index"); + return self[index]; + }) + .def("__setitem__", [](Class* vec, unsigned index, T val) { + if (index >= vec_size) throw py::index_error("Invalid index"); + (*vec)[index] = val; + }) + .def_buffer([](Class &self) -> py::buffer_info { + return py::buffer_info( + self.Data(), + sizeof(T), + py::format_descriptor::format(), + 1, + { vec_size }, + { sizeof(T) } + ); + }) .def("__str__", toString) .def("__repr__", toString); } diff --git a/src/python_pybind11/src/Vector3.hh b/src/python_pybind11/src/Vector3.hh index f08718c4c..488c4cc14 100644 --- a/src/python_pybind11/src/Vector3.hh +++ b/src/python_pybind11/src/Vector3.hh @@ -43,6 +43,7 @@ template void helpDefineMathVector3(py::module &m, const std::string &typestr) { using Class = gz::math::Vector3; + const int vec_size = 3; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -159,10 +160,24 @@ void helpDefineMathVector3(py::module &m, const std::string &typestr) .def("__deepcopy__", [](const Class &self, py::dict) { return Class(self); }, "memo"_a) - .def("__getitem__", - py::overload_cast(&Class::operator[], py::const_)) - .def("__setitem__", - [](Class* vec, unsigned index, T val) { (*vec)[index] = val; }) + .def("__getitem__", [](const Class &self, unsigned index) { + if (index >= vec_size) throw py::index_error("Invalid index"); + return self[index]; + }) + .def("__setitem__", [](Class* vec, unsigned index, T val) { + if (index >= vec_size) throw py::index_error("Invalid index"); + (*vec)[index] = val; + }) + .def_buffer([](Class &self) -> py::buffer_info { + return py::buffer_info( + self.Data(), + sizeof(T), + py::format_descriptor::format(), + 1, + { vec_size }, + { sizeof(T) } + ); + }) .def("__str__", toString) .def("__repr__", toString); } diff --git a/src/python_pybind11/src/Vector4.hh b/src/python_pybind11/src/Vector4.hh index 0977d7c6d..1347a1355 100644 --- a/src/python_pybind11/src/Vector4.hh +++ b/src/python_pybind11/src/Vector4.hh @@ -43,6 +43,7 @@ template void helpDefineMathVector4(py::module &m, const std::string &typestr) { using Class = gz::math::Vector4; + const int vec_size = 4; auto toString = [](const Class &si) { std::stringstream stream; stream << si; @@ -139,10 +140,24 @@ void helpDefineMathVector4(py::module &m, const std::string &typestr) .def("__deepcopy__", [](const Class &self, py::dict) { return Class(self); }, "memo"_a) - .def("__getitem__", - py::overload_cast(&Class::operator[], py::const_)) - .def("__setitem__", - [](Class* vec, unsigned index, T val) { (*vec)[index] = val; }) + .def("__getitem__", [](const Class &self, unsigned index) { + if (index >= vec_size) throw py::index_error("Invalid index"); + return self[index]; + }) + .def("__setitem__", [](Class* vec, unsigned index, T val) { + if (index >= vec_size) throw py::index_error("Invalid index"); + (*vec)[index] = val; + }) + .def_buffer([](Class &self) -> py::buffer_info { + return py::buffer_info( + self.Data(), + sizeof(T), + py::format_descriptor::format(), + 1, + { vec_size }, + { sizeof(T) } + ); + }) .def("__str__", toString) .def("__repr__", toString); } diff --git a/src/python_pybind11/test/Matrix3_TEST.py b/src/python_pybind11/test/Matrix3_TEST.py index 15756457e..38256b780 100644 --- a/src/python_pybind11/test/Matrix3_TEST.py +++ b/src/python_pybind11/test/Matrix3_TEST.py @@ -14,9 +14,10 @@ import math import unittest -from gz.math7 import Matrix3d +from gz.math7 import Matrix3d, Matrix3f from gz.math7 import Quaterniond from gz.math7 import Vector3d +import test_common class TestMatrix3(unittest.TestCase): @@ -334,6 +335,10 @@ def test_to_quaternion(self): q2 = Quaterniond(mat) self.assertTrue(q == q2) + def test_buffer(self): + test_common.test_matrix(self, 3, Matrix3d) + test_common.test_matrix(self, 3, Matrix3f) + if __name__ == '__main__': unittest.main() diff --git a/src/python_pybind11/test/Matrix4_TEST.py b/src/python_pybind11/test/Matrix4_TEST.py index 23efc90e8..26f8262b7 100644 --- a/src/python_pybind11/test/Matrix4_TEST.py +++ b/src/python_pybind11/test/Matrix4_TEST.py @@ -14,10 +14,11 @@ import math import unittest -from gz.math7 import Matrix4d +from gz.math7 import Matrix4d, Matrix4f from gz.math7 import Pose3d from gz.math7 import Quaterniond from gz.math7 import Vector3d +import test_common class TestMatrix4(unittest.TestCase): @@ -515,6 +516,9 @@ def test_look_at(self): Vector3d(0, 1, 1)).pose(), Pose3d(1, 1, 1, math.pi/4, 0, math.pi)) + def test_buffer(self): + test_common.test_matrix(self, 4, Matrix4d) + test_common.test_matrix(self, 4, Matrix4f) if __name__ == '__main__': unittest.main() diff --git a/src/python_pybind11/test/Matrix6_TEST.py b/src/python_pybind11/test/Matrix6_TEST.py index c122ad425..cebccc342 100644 --- a/src/python_pybind11/test/Matrix6_TEST.py +++ b/src/python_pybind11/test/Matrix6_TEST.py @@ -14,7 +14,8 @@ import math import unittest -from gz.math7 import Matrix3d, Matrix6d, Matrix6dCorner +from gz.math7 import Matrix3d, Matrix6d, Matrix6dCorner, Matrix6f +import test_common class TestMatrix6(unittest.TestCase): @@ -254,5 +255,10 @@ def test_set_submatrix(self): 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35)) + def test_buffer(self): + test_common.test_matrix(self, 6, Matrix6d) + test_common.test_matrix(self, 6, Matrix6f) + + if __name__ == '__main__': unittest.main() diff --git a/src/python_pybind11/test/Vector2_TEST.py b/src/python_pybind11/test/Vector2_TEST.py index e2b252cf2..df783b21f 100644 --- a/src/python_pybind11/test/Vector2_TEST.py +++ b/src/python_pybind11/test/Vector2_TEST.py @@ -16,8 +16,8 @@ import math import unittest -from gz.math7 import Vector2d -from gz.math7 import Vector2f +from gz.math7 import Vector2d, Vector2f +import test_common class TestVector2(unittest.TestCase): @@ -317,5 +317,10 @@ def test_nan(self): self.assertEqual(Vector2f.ZERO, nanVecF) self.assertTrue(nanVecF.is_finite()) + def test_buffer(self): + test_common.test_vector(self, 2, Vector2d) + test_common.test_vector(self, 2, Vector2f) + + if __name__ == '__main__': unittest.main() diff --git a/src/python_pybind11/test/Vector3_TEST.py b/src/python_pybind11/test/Vector3_TEST.py index ed055417c..7f7e3b88a 100644 --- a/src/python_pybind11/test/Vector3_TEST.py +++ b/src/python_pybind11/test/Vector3_TEST.py @@ -15,6 +15,7 @@ import copy import math import unittest +import test_common from gz.math7 import Vector3d from gz.math7 import Vector3f @@ -374,5 +375,13 @@ def test_nan(self): self.assertEqual(Vector3f.ZERO, nanVecF) self.assertTrue(nanVecF.is_finite()) + def test_buffer(self): + test_common.test_vector(self, 3, Vector3d) + test_common.test_vector(self, 3, Vector3f) + + +if __name__ == '__main__': + unittest.main() + if __name__ == '__main__': unittest.main() diff --git a/src/python_pybind11/test/Vector4_TEST.py b/src/python_pybind11/test/Vector4_TEST.py index e247f21aa..4e2ec1033 100644 --- a/src/python_pybind11/test/Vector4_TEST.py +++ b/src/python_pybind11/test/Vector4_TEST.py @@ -15,6 +15,7 @@ import copy import math import unittest +import test_common from gz.math7 import Vector4d from gz.math7 import Vector4f @@ -281,5 +282,9 @@ def test_nan(self): self.assertEqual(Vector4f.ZERO, nanVecF) self.assertTrue(nanVecF.is_finite()) + def test_buffer(self): + test_common.test_vector(self, 4, Vector4d) + test_common.test_vector(self, 4, Vector4f) + if __name__ == '__main__': unittest.main() diff --git a/src/python_pybind11/test/test_common.py b/src/python_pybind11/test/test_common.py new file mode 100644 index 000000000..65f7c5ebe --- /dev/null +++ b/src/python_pybind11/test/test_common.py @@ -0,0 +1,35 @@ +import unittest +import numpy as np + +def test_matrix(self: unittest.TestCase, size:int, cl): + elements = list(np.arange(size*size, dtype=float) + 1) + matrix = cl(*elements) + + self.assertEqual(matrix(1,2), memoryview(matrix)[1,2]) + self.assertTrue(memoryview(matrix).c_contiguous) + # Have to cast through bytes for some reason... + aslist = memoryview(matrix).tolist() + self.assertEqual(np.array(elements).reshape((size,size)).tolist(), aslist) + + v = np.array(matrix, copy=False) + self.assertEqual(matrix(0,1), 2) + v[0,1] = 5 + self.assertEqual(matrix(0,1), 5) # can mutate origina matrix + +def test_vector(self: unittest.TestCase, size:int, cl): + elements = list(np.arange(size, dtype=float) + 1) + vector = cl(*elements) + + self.assertEqual(vector[1], memoryview(vector)[1]) + self.assertTrue(memoryview(vector).c_contiguous) + # Have to cast through bytes for some reason... + aslist = memoryview(vector).tolist() + self.assertEqual(elements, aslist) + + v = np.array(vector, copy=False) + self.assertEqual(vector[1], 2) + v[1] = 5 + self.assertEqual(vector[1], 5) # can mutate original vector + + self.assertEqual(elements, list(elements)) +