Skip to content

Commit

Permalink
Merge branch 'ign-math6' into mass_matrix3_tolerance_bug
Browse files Browse the repository at this point in the history
  • Loading branch information
scpeters committed May 9, 2022
2 parents 40fe3c4 + b330afe commit 8dc8e93
Show file tree
Hide file tree
Showing 11 changed files with 18 additions and 24 deletions.
2 changes: 1 addition & 1 deletion include/ignition/math/Pose3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -422,7 +422,7 @@ namespace ignition
return this->q;
}

/// \brief Get a mutuable reference to the rotation.
/// \brief Get a mutable reference to the rotation.
/// \return Quaternion representation of the rotation.
public: inline Quaternion<T> &Rot()
{
Expand Down
8 changes: 4 additions & 4 deletions src/python_pybind11/src/AxisAlignedBox.cc
Original file line number Diff line number Diff line change
Expand Up @@ -79,12 +79,12 @@ void defineMathAxisAlignedBox(py::module &m, const std::string &typestr)
.def(py::self == py::self)
.def(py::self != py::self)
.def("min",
py::overload_cast<>(&Class::Min, py::const_),
py::return_value_policy::reference,
py::overload_cast<>(&Class::Min),
py::return_value_policy::reference_internal,
"Get the minimum corner.")
.def("max",
py::overload_cast<>(&Class::Max, py::const_),
py::return_value_policy::reference,
py::overload_cast<>(&Class::Max),
py::return_value_policy::reference_internal,
"Get the maximum corner.")
.def("intersects",
&Class::Intersects,
Expand Down
1 change: 0 additions & 1 deletion src/python_pybind11/src/Cylinder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,6 @@ void defineMathCylinder(py::module &m, const std::string &typestr)
"Set the rotation offset.")
.def("mat",
&Class::Mat,
py::return_value_policy::reference,
"Get the material associated with this box.")
.def("set_mat",
&Class::SetMat,
Expand Down
3 changes: 0 additions & 3 deletions src/python_pybind11/src/Inertial.hh
Original file line number Diff line number Diff line change
Expand Up @@ -65,14 +65,12 @@ void defineMathInertial(py::module &m, const std::string &typestr)
"Set the mass and inertia matrix.")
.def("mass_matrix",
&Class::MassMatrix,
py::return_value_policy::reference,
"Get the mass and inertia matrix.")
.def("set_pose",
&Class::SetPose,
"Set the pose of the center of mass reference frame.")
.def("pose",
&Class::Pose,
py::return_value_policy::reference,
"Get the pose of the center of mass reference frame.")
.def("moi",
&Class::Moi,
Expand All @@ -86,7 +84,6 @@ void defineMathInertial(py::module &m, const std::string &typestr)
&Class::SetMassMatrixRotation,
py::arg("_q") = ignition::math::Quaternion<T>::Identity,
py::arg("_tol") = 1e-6,
py::return_value_policy::reference,
"Set the MassMatrix rotation (eigenvectors of inertia matrix) "
"without affecting the MOI in the base coordinate frame.")
.def("__copy__", [](const Class &self) {
Expand Down
2 changes: 1 addition & 1 deletion src/python_pybind11/src/Matrix3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ void helpDefineMathMatrix3(py::module &m, const std::string &typestr)
.def(py::self != py::self)
.def("__call__",
py::overload_cast<size_t, size_t>(&Class::operator()),
py::return_value_policy::reference)
py::return_value_policy::reference_internal)
// .def(py::self *= py::self)
.def("set",
&Class::Set,
Expand Down
2 changes: 1 addition & 1 deletion src/python_pybind11/src/Matrix4.hh
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ void helpDefineMathMatrix4(py::module &m, const std::string &typestr)
.def(py::self != py::self)
.def("__call__",
py::overload_cast<size_t, size_t>(&Class::operator()),
py::return_value_policy::reference)
py::return_value_policy::reference_internal)
.def("set",
&Class::Set,
"Set values")
Expand Down
1 change: 0 additions & 1 deletion src/python_pybind11/src/OrientedBox.hh
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,6 @@ void defineMathOrientedBox(py::module &m, const std::string &typestr)
"Set the box pose, which is the pose of its center.")
.def("pose",
py::overload_cast<>(&Class::Pose, py::const_),
py::return_value_policy::reference,
"Get the box pose, which is the pose of its center.")
.def("size",
py::overload_cast<>(&Class::Size, py::const_),
Expand Down
6 changes: 3 additions & 3 deletions src/python_pybind11/src/Plane.hh
Original file line number Diff line number Diff line change
Expand Up @@ -93,12 +93,12 @@ void defineMathPlane(py::module &m, const std::string &typestr)
"The side of the plane a point is on.")
.def("size",
py::overload_cast<>(&Class::Size),
py::return_value_policy::reference,
py::return_value_policy::reference_internal,
"Get the plane size")
.def("normal",
py::overload_cast<>(&Class::Normal),
py::return_value_policy::reference,
"Get the plane size")
py::return_value_policy::reference_internal,
"Get the plane normal")
.def("offset",
&Class::Offset,
"Get the plane offset")
Expand Down
8 changes: 4 additions & 4 deletions src/python_pybind11/src/Pose3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -124,8 +124,8 @@ void helpDefineMathPose3(py::module &m, const std::string &typestr)
&Class::Round,
"Round all values to _precision decimal places")
.def("pos",
py::overload_cast<>(&Class::Pos, py::const_),
py::return_value_policy::reference,
py::overload_cast<>(&Class::Pos),
py::return_value_policy::reference_internal,
"Get the position.")
.def("x", &Class::X, "Get the X value of the position")
.def("y", &Class::Y, "Get the Y value of the position")
Expand All @@ -134,8 +134,8 @@ void helpDefineMathPose3(py::module &m, const std::string &typestr)
.def("set_y", &Class::SetY, "Set the Y value of the position")
.def("set_z", &Class::SetZ, "Set the Z value of the position")
.def("rot",
py::overload_cast<>(&Class::Rot, py::const_),
py::return_value_policy::reference,
py::overload_cast<>(&Class::Rot),
py::return_value_policy::reference_internal,
"Get the rotation.")
.def("roll", &Class::Roll, "Get the Roll value of the position")
.def("pitch", &Class::Pitch, "Get the Pitch value of the position")
Expand Down
1 change: 0 additions & 1 deletion src/python_pybind11/src/RotationSpline.cc
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@ void defineMathRotationSpline(py::module &m, const std::string &typestr)
"Adds a control point to the end of the spline.")
.def("point",
&Class::Point,
py::return_value_policy::reference,
"Gets the detail of one of the control points of the spline.")
.def("point_count",
&Class::PointCount,
Expand Down
8 changes: 4 additions & 4 deletions src/python_pybind11/src/Vector3Stats.cc
Original file line number Diff line number Diff line change
Expand Up @@ -52,19 +52,19 @@ void defineMathVector3Stats(py::module &m, const std::string &typestr)
"Forget all previous data.")
.def("x",
py::overload_cast<>(&Class::X),
py::return_value_policy::reference,
py::return_value_policy::reference_internal,
"Get statistics for x component of signal.")
.def("y",
py::overload_cast<>(&Class::Y),
py::return_value_policy::reference,
py::return_value_policy::reference_internal,
"Get statistics for y component of signal.")
.def("z",
py::overload_cast<>(&Class::Z),
py::return_value_policy::reference,
py::return_value_policy::reference_internal,
"Get statistics for z component of signal.")
.def("mag",
py::overload_cast<>(&Class::Mag),
py::return_value_policy::reference,
py::return_value_policy::reference_internal,
"Get statistics for mag component of signal.")
.def("__copy__", [](const Class &self) {
return Class(self);
Expand Down

0 comments on commit 8dc8e93

Please sign in to comment.