Skip to content

Commit

Permalink
buffer_protocol for vectors and matrices
Browse files Browse the repository at this point in the history
Also IndexError is raised on invalid vector __getitem__/__setitem__
access.
This way list(vector) works correctly instead of spinning

Signed-off-by: Benoit Maurin <[email protected]>
  • Loading branch information
unjambonakap committed Aug 11, 2024
1 parent 197e189 commit 7185147
Show file tree
Hide file tree
Showing 20 changed files with 222 additions and 132 deletions.
66 changes: 9 additions & 57 deletions include/gz/math/Matrix3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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<T> &_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
Expand Down Expand Up @@ -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]
Expand Down Expand Up @@ -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<T> &, const Vector3<T> &,
/// const Vector3<T> &,)
public: void GZ_DEPRECATED(7) Axes(const Vector3<T> &_xAxis,
const Vector3<T> &_yAxis,
const Vector3<T> &_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.
Expand All @@ -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> &, T)
public: void GZ_DEPRECATED(7) Axis(const Vector3<T> &_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
Expand All @@ -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<T> &, const Vector3<T> &)
public: void GZ_DEPRECATED(7) From2Axes(
const Vector3<T> &_v1, const Vector3<T> &_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.
Expand Down Expand Up @@ -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<T> &_v)
public: void GZ_DEPRECATED(7) Col(unsigned int _c, const Vector3<T> &_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].
Expand All @@ -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<T> &operator=(const Matrix3<T> &_mat) = default;

/// \brief Subtraction operator.
/// \param[in] _m Matrix to subtract.
/// \return The element wise difference of two matrices.
Expand Down Expand Up @@ -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];
};
Expand Down
21 changes: 9 additions & 12 deletions include/gz/math/Matrix4.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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<T> &_m) = default;

/// \brief Constructor
/// \param[in] _v00 Row 0, Col 0 value
/// \param[in] _v01 Row 0, Col 1 value
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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<T> &operator=(const Matrix4<T> &_mat) = default;

/// \brief Equal operator for 3x3 matrix
/// \param _mat Incoming matrix
/// \return itself
Expand Down Expand Up @@ -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];
};
Expand Down
18 changes: 9 additions & 9 deletions include/gz/math/Matrix6.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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<T> &_m) = default;

/// \brief Constructor
/// \param[in] _v00 Row 0, Col 0 value
/// \param[in] _v01 Row 0, Col 1 value
Expand Down Expand Up @@ -294,11 +290,6 @@ namespace gz::math
this->data[5][5]);
}

/// \brief Assignment operator. this = _mat
/// \param _mat Incoming matrix
/// \return itself
public: Matrix6<T> &operator=(const Matrix6<T> &_mat) = default;

/// \brief Multiplication assignment operator. This matrix will
/// become equal to this * _m2.
/// \param[in] _m2 Incoming matrix.
Expand Down Expand Up @@ -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];
};
Expand Down
21 changes: 9 additions & 12 deletions include/gz/math/Vector2.hh
Original file line number Diff line number Diff line change
Expand Up @@ -59,13 +59,6 @@ namespace gz::math
{
}

/// \brief Copy constructor
/// \param[in] _v the value
public: Vector2(const Vector2<T> &_v) = default;

/// \brief Destructor
public: ~Vector2() = default;

/// \brief Return the sum of the values
/// \return the sum
public: T Sum() const
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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];
};
Expand Down
21 changes: 9 additions & 12 deletions include/gz/math/Vector3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -71,13 +71,6 @@ namespace gz::math
{
}

/// \brief Copy constructor
/// \param[in] _v a vector
public: Vector3(const Vector3<T> &_v) = default;

/// \brief Destructor
public: ~Vector3() = default;

/// \brief Return the sum of the values
/// \return the sum
public: T Sum() const
Expand Down Expand Up @@ -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<T> &_v) = default;

/// \brief Assignment operator
/// \param[in] _v assigned to all elements
/// \return this
Expand Down Expand Up @@ -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];
};
Expand Down
21 changes: 9 additions & 12 deletions include/gz/math/Vector4.hh
Original file line number Diff line number Diff line change
Expand Up @@ -61,13 +61,6 @@ namespace gz::math
{
}

/// \brief Copy constructor
/// \param[in] _v vector
public: Vector4(const Vector4<T> &_v) = default;

/// \brief Destructor
public: ~Vector4() = default;

/// \brief Calc distance to the given point
/// \param[in] _pt the point
/// \return the distance
Expand Down Expand Up @@ -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<T> &operator=(const Vector4<T> &_v) = default;

/// \brief Assignment operator
/// \param[in] _value
public: Vector4<T> &operator=(T _value)
Expand Down Expand Up @@ -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];
};
Expand Down
11 changes: 11 additions & 0 deletions src/python_pybind11/src/Matrix3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ template<typename T>
void helpDefineMathMatrix3(py::module &m, const std::string &typestr)
{
using Class = gz::math::Matrix3<T>;
const int mat_size = 3;
auto toString = [](const Class &si) {
std::stringstream stream;
stream << si;
Expand Down Expand Up @@ -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<T>::format(),
2,
{ mat_size, mat_size },
{ mat_size * sizeof(T), sizeof(T) }
);
})
.def("__str__", toString)
.def("__repr__", toString);
}
Expand Down
11 changes: 11 additions & 0 deletions src/python_pybind11/src/Matrix4.hh
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ template<typename T>
void helpDefineMathMatrix4(py::module &m, const std::string &typestr)
{
using Class = gz::math::Matrix4<T>;
const int mat_size = 4;
auto toString = [](const Class &si) {
std::stringstream stream;
stream << si;
Expand Down Expand Up @@ -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<T>::format(),
2,
{ mat_size, mat_size },
{ mat_size * sizeof(T), sizeof(T) }
);
})
.def("__str__", toString)
.def("__repr__", toString);
}
Expand Down
Loading

0 comments on commit 7185147

Please sign in to comment.