Skip to content

Commit

Permalink
Added Quaternion pybind11 interface (#324)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <[email protected]>
  • Loading branch information
ahcorde authored Dec 23, 2021
1 parent b0f3685 commit 9ab392a
Show file tree
Hide file tree
Showing 5 changed files with 238 additions and 19 deletions.
1 change: 0 additions & 1 deletion src/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,6 @@ if (PYTHONLIBS_FOUND)
Plane_TEST
Pose3_TEST
python_TEST
Quaternion_TEST
RotationSpline_TEST
SemanticVersion_TEST
SignalStats_TEST
Expand Down
1 change: 1 addition & 0 deletions src/python_pybind11/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,7 @@ if (${pybind11_FOUND})
Color_TEST
Helpers_TEST
Line2_TEST
Quaternion_TEST
Rand_TEST
RollingMean_TEST
StopWatch_TEST
Expand Down
210 changes: 210 additions & 0 deletions src/python_pybind11/src/Quaternion.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,210 @@
/*
* 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.
*
*/

#ifndef IGNITION_MATH_PYTHON__QUATERNION_HH_
#define IGNITION_MATH_PYTHON__QUATERNION_HH_

#include <string>

#include <pybind11/pybind11.h>
#include <pybind11/operators.h>
#include <pybind11/stl.h>

#include <ignition/math/Quaternion.hh>
#include <ignition/math/Vector3.hh>
#include <ignition/math/Matrix3.hh>

namespace py = pybind11;
using namespace pybind11::literals;

namespace ignition
{
namespace math
{
namespace python
{
/// Define a pybind11 wrapper for an ignition::math::Quaternion
/**
* \param[in] module a pybind11 module to add the definition to
* \param[in] typestr name of the type used by Python
*/
template<typename T>
void defineMathQuaternion(py::module &m, const std::string &typestr)
{
using Class = ignition::math::Quaternion<T>;
auto toString = [](const Class &si) {
std::stringstream stream;
stream << si;
return stream.str();
};
std::string pyclass_name = typestr;
py::class_<Class>(m,
pyclass_name.c_str(),
py::buffer_protocol(),
py::dynamic_attr())
.def(py::init<>())
.def(py::init<T, T, T, T>())
.def(py::init<T, T, T>())
.def(py::init<const ignition::math::Vector3<T>&, T>())
.def(py::init<const ignition::math::Vector3<T>&>())
.def(py::init<const ignition::math::Matrix3<T>&>())
.def(py::init<const Class&>())
.def(py::self + py::self)
.def(py::self += py::self)
.def(-py::self)
.def(py::self - py::self)
.def(py::self -= py::self)
.def(py::self * py::self)
.def(py::self * float())
.def(py::self * ignition::math::Vector3<T>())
.def(py::self *= py::self)
.def(py::self == py::self)
.def(py::self != py::self)
// .def(py::self * py::self)
// .def(py::self *= py::self)
.def("invert",
&Class::Invert,
"Invert the quaternion")
.def("inverse",
&Class::Inverse,
"Get the inverse of this quaternion")
.def("log",
&Class::Log,
"Return the logarithm")
.def("exp",
&Class::Exp,
"Return the exponent")
.def("normalize",
&Class::Normalize,
"Normalize the quaternion")
.def("normalized",
&Class::Normalized,
"Gets a normalized version of this quaternion")
.def("axis",
py::overload_cast<T, T, T, T>(&Class::Axis),
"Set the quaternion from an axis and angle")
.def("axis",
py::overload_cast<const ignition::math::Vector3<T>&, T>(&Class::Axis),
"Set the quaternion from an axis and angle")
.def("set",
&Class::Set,
"Set this quaternion from 4 floating numbers")
.def("euler",
py::overload_cast<const ignition::math::Vector3<T>&>(&Class::Euler),
"Set the quaternion from Euler angles. The order of operations "
"is roll, pitch, yaw around a fixed body frame axis "
"(the original frame of the object before rotation is applied).")
.def("euler",
py::overload_cast<T, T, T>(&Class::Euler),
"Set the quaternion from Euler angles.")
.def("euler",
py::overload_cast<>(&Class::Euler, py::const_),
"Return the rotation in Euler angles")
.def("euler_to_quaternion",
py::overload_cast<const ignition::math::Vector3<T>&>(
&Class::EulerToQuaternion),
"Convert euler angles to quatern.")
.def("euler_to_quaternion",
py::overload_cast<T, T, T>(&Class::EulerToQuaternion),
"Convert euler angles to quatern.")
.def("roll", &Class::Roll, "Get the Euler roll angle in radians")
.def("pitch", &Class::Pitch, "Get the Euler pitch angle in radians")
.def("yaw", &Class::Yaw, "Get the Euler yaw angle in radians")
.def("to_axis",
[](const Class &self) {
ignition::math::Vector3<T> _axis;
T _angle;
self.ToAxis(_axis, _angle);
return std::make_tuple(_axis, _angle);
},
"Return rotation as axis and angle")
.def("matrix",
&Class::Matrix,
"Set from a rotation matrix.")
.def("from_2_axes",
&Class::From2Axes,
"Set this quaternion to represent rotation from "
"vector _v1 to vector _v2, so that")
.def("scale",
&Class::Scale,
"Scale a Quaternion<T>")
.def("equal",
&Class::Equal,
"Equality test with tolerance.")
.def("rotate_vector",
&Class::RotateVector,
"Rotate a vector using the quaternion")
.def("rotate_vector_reverse",
&Class::RotateVectorReverse,
"Do the reverse rotation of a vector by this quaternion")
.def("is_finite",
&Class::IsFinite,
"See if a quaternion is finite (e.g., not nan)")
.def("correct",
&Class::Correct,
"Correct any nan values in this quaternion")
.def("x_axis",
&Class::XAxis,
"Return the X axis")
.def("y_axis",
&Class::YAxis,
"Return the Y axis")
.def("z_axis",
&Class::ZAxis,
"Return the Z axis")
.def("round",
&Class::Round,
"Round all values to _precision decimal places")
.def("dot",
&Class::Dot,
"Dot product")
.def("squad",
&Class::Squad,
"Spherical quadratic interpolation "
"given the ends and an interpolation parameter between 0 and 1")
.def("slerp",
&Class::Slerp,
"Spherical linear interpolation between 2 quaternions, "
" given the ends and an interpolation parameter between 0 and 1")
.def("integrate",
&Class::Integrate,
"Integrate quaternion for constant angular velocity vector "
"along specified interval `_deltaT`.")
.def("x", py::overload_cast<>(&Class::X), "Get the x value.")
.def("y", py::overload_cast<>(&Class::Y), "Get the y value.")
.def("z", py::overload_cast<>(&Class::Z), "Get the z value.")
.def("w", py::overload_cast<>(&Class::W), "Get the w value.")
.def("x", py::overload_cast<T>(&Class::X), "Set the x value.")
.def("y", py::overload_cast<T>(&Class::Y), "Set the y value.")
.def("z", py::overload_cast<T>(&Class::Z), "Set the z value.")
.def("w", py::overload_cast<T>(&Class::W), "Set the w value.")
.def("__copy__", [](const Class &self) {
return Class(self);
})
.def("__deepcopy__", [](const Class &self, py::dict) {
return Class(self);
}, "memo"_a)
.def_readonly_static("IDENTITY", &Class::Identity, "Identity matrix")
.def_readonly_static("ZERO", &Class::Zero, "Zero matrix")
.def("__str__", toString)
.def("__repr__", toString);
}
} // namespace python
} // namespace math
} // namespace ignition

#endif // IGNITION_MATH_PYTHON__QUATERNION_HH_
5 changes: 5 additions & 0 deletions src/python_pybind11/src/_ignition_math_pybind11.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include "Color.hh"
#include "Helpers.hh"
#include "Line2.hh"
#include "Quaternion.hh"
#include "Rand.hh"
#include "RollingMean.hh"
#include "StopWatch.hh"
Expand Down Expand Up @@ -58,4 +59,8 @@ PYBIND11_MODULE(math, m)
ignition::math::python::defineMathLine2<int>(m, "Line2i");
ignition::math::python::defineMathLine2<double>(m, "Line2d");
ignition::math::python::defineMathLine2<float>(m, "Line2f");

ignition::math::python::defineMathQuaternion<int>(m, "Quaternioni");
ignition::math::python::defineMathQuaternion<double>(m, "Quaterniond");
ignition::math::python::defineMathQuaternion<float>(m, "Quaternionf");
}
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,10 @@

import math
import unittest
from ignition.math import Matrix3d
from ignition.math import Matrix4d
# TODO(ahcorde): Enable the corresponding tests when these classes
# are ported
# from ignition.math import Matrix3d
# from ignition.math import Matrix4d
from ignition.math import Quaterniond
from ignition.math import Quaternionf
from ignition.math import Quaternioni
Expand Down Expand Up @@ -342,22 +344,24 @@ def test_math(self):
self.assertTrue(-q == Quaterniond(-0.891007, -0.121334,
-0.242668, -0.364002))

self.assertTrue(Matrix3d(q) == Matrix3d(
0.617229, -0.589769, 0.52077,
0.707544, 0.705561, -0.0395554,
-0.344106, 0.392882, 0.85278))

matFromQ = Matrix3d(q)
self.assertTrue(matFromQ == Matrix3d(
0.617229, -0.589769, 0.52077,
0.707544, 0.705561, -0.0395554,
-0.344106, 0.392882, 0.85278))

self.assertTrue(Matrix4d(q) == Matrix4d(
0.617229, -0.589769, 0.52077, 0,
0.707544, 0.705561, -0.0395554, 0,
-0.344106, 0.392882, 0.85278, 0,
0, 0, 0, 1))
# TODO(ahcorde): Enable the corresponding tests when these classes
# are ported
# self.assertTrue(Matrix3d(q) == Matrix3d(
# 0.617229, -0.589769, 0.52077,
# 0.707544, 0.705561, -0.0395554,
# -0.344106, 0.392882, 0.85278))
#
# matFromQ = Matrix3d(q)
# self.assertTrue(matFromQ == Matrix3d(
# 0.617229, -0.589769, 0.52077,
# 0.707544, 0.705561, -0.0395554,
# -0.344106, 0.392882, 0.85278))
#
# self.assertTrue(Matrix4d(q) == Matrix4d(
# 0.617229, -0.589769, 0.52077, 0,
# 0.707544, 0.705561, -0.0395554, 0,
# -0.344106, 0.392882, 0.85278, 0,
# 0, 0, 0, 1))

def test_stream_out(self):
q = Quaterniond(0.1, 1.2, 2.3)
Expand Down

0 comments on commit 9ab392a

Please sign in to comment.