Skip to content

Commit

Permalink
Added Inertial pybind11 interface (#349)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández <[email protected]>
  • Loading branch information
ahcorde authored Dec 29, 2021
1 parent 9c28568 commit 5283016
Show file tree
Hide file tree
Showing 5 changed files with 136 additions and 29 deletions.
1 change: 0 additions & 1 deletion src/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,6 @@ if (PYTHONLIBS_FOUND)
Box_TEST
Cylinder_TEST
Frustum_TEST
Inertial_TEST
OrientedBox_TEST
Plane_TEST
python_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 @@ -89,6 +89,7 @@ if (${pybind11_FOUND})
Filter_TEST
GaussMarkovProcess_TEST
Helpers_TEST
Inertial_TEST
Kmeans_TEST
Line2_TEST
Line3_TEST
Expand Down
104 changes: 104 additions & 0 deletions src/python_pybind11/src/Inertial.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,104 @@
/*
* 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__INERTIAL_HH_
#define IGNITION_MATH_PYTHON__INERTIAL_HH_

#include <string>

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

#include <ignition/math/Inertial.hh>

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

namespace ignition
{
namespace math
{
namespace python
{
/// Define a pybind11 wrapper for an ignition::math::Inertial
/**
* \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 defineMathInertial(py::module &m, const std::string &typestr)
{

using Class = ignition::math::Inertial<T>;
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<const ignition::math::MassMatrix3<T>&,
const ignition::math::Pose3<T>&>())
.def(py::init<const Class&>())
.def(py::self == py::self)
.def(py::self != py::self)
.def(py::self += py::self)
.def(py::self + py::self)
.def("set_mass_matrix",
&Class::SetMassMatrix,
py::arg("_m") = ignition::math::MassMatrix3<T>(),
py::arg("_tolerance") = IGN_MASSMATRIX3_DEFAULT_TOLERANCE<T>,
"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,
"Get the moment of inertia matrix computer about the body's "
"center of mass and expressed in this Inertial object’s frame F.")
.def("set_inertial_rotation",
&Class::SetInertialRotation,
"Set the inertial pose rotation without affecting the "
"MOI in the base coordinate frame.")
.def("set_mass_matrix_rotation",
&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) {
return Class(self);
})
.def("__deepcopy__", [](const Class &self, py::dict) {
return Class(self);
}, "memo"_a);
}

} // namespace python
} // namespace math
} // namespace ignition

#endif // IGNITION_MATH_PYTHON__INERTIAL_HH_
3 changes: 3 additions & 0 deletions src/python_pybind11/src/_ignition_math_pybind11.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include "Filter.hh"
#include "GaussMarkovProcess.hh"
#include "Helpers.hh"
#include "Inertial.hh"
#include "Kmeans.hh"
#include "Line2.hh"
#include "Line3.hh"
Expand Down Expand Up @@ -139,6 +140,8 @@ PYBIND11_MODULE(math, m)
ignition::math::python::defineMathMassMatrix3<double>(m, "MassMatrix3d");
ignition::math::python::defineMathMassMatrix3<float>(m, "MassMatrix3f");

ignition::math::python::defineMathInertial<double>(m, "Inertiald");

ignition::math::python::defineMathFilter<int>(m, "Filteri");
ignition::math::python::defineMathFilter<float>(m, "Filterf");
ignition::math::python::defineMathFilter<double>(m, "Filterd");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
import math
import unittest

from ignition.math import IGN_PI, IGN_PI_2, IGN_PI_4, Inertiald, Quaterniond, Pose3d, Matrix3d, MassMatrix3d, Vector3d
from ignition.math import Inertiald, Quaterniond, Pose3d, Matrix3d, MassMatrix3d, Vector3d


class TestInertial(unittest.TestCase):
Expand Down Expand Up @@ -45,7 +45,7 @@ def test_constructor_non_default_values(self):
m = MassMatrix3d(mass, Ixxyyzz, Ixyxzyz)
self.assertTrue(m.is_positive())
self.assertTrue(m.is_valid())
pose = Pose3d(1, 2, 3, IGN_PI/6, 0, 0)
pose = Pose3d(1, 2, 3, math.pi/6, 0, 0)
inertial = Inertiald(m, pose)

# Should not match simple constructor
Expand Down Expand Up @@ -83,7 +83,7 @@ def test_setters(self):
m = MassMatrix3d(mass, Ixxyyzz, Ixyxzyz)
self.assertTrue(m.is_positive())
self.assertTrue(m.is_valid())
pose = Pose3d(1, 2, 3, IGN_PI/6, 0, 0)
pose = Pose3d(1, 2, 3, math.pi/6, 0, 0)
inertial = Inertiald()

# Initially valid
Expand Down Expand Up @@ -114,28 +114,28 @@ def test_moi_diagonal(self):
self.assertEqual(inertial.moi(), m.moi())

# 90 deg rotation about X axis, expect different MOI
pose = Pose3d(0, 0, 0, IGN_PI_2, 0, 0)
pose = Pose3d(0, 0, 0, math.pi/2, 0, 0)
expectedMOI = Matrix3d(2, 0, 0, 0, 4, 0, 0, 0, 3)
inertial = Inertiald(m, pose)
self.assertNotEqual(inertial.moi(), m.moi())
self.assertEqual(inertial.moi(), expectedMOI)

# 90 deg rotation about Y axis, expect different MOI
pose = Pose3d(0, 0, 0, 0, IGN_PI_2, 0)
pose = Pose3d(0, 0, 0, 0, math.pi/2, 0)
expectedMOI = Matrix3d(4, 0, 0, 0, 3, 0, 0, 0, 2)
inertial = Inertiald(m, pose)
self.assertNotEqual(inertial.moi(), m.moi())
self.assertEqual(inertial.moi(), expectedMOI)

# 90 deg rotation about Z axis, expect different MOI
pose = Pose3d(0, 0, 0, 0, 0, IGN_PI_2)
pose = Pose3d(0, 0, 0, 0, 0, math.pi/2)
expectedMOI = Matrix3d(3, 0, 0, 0, 2, 0, 0, 0, 4)
inertial = Inertiald(m, pose)
self.assertNotEqual(inertial.moi(), m.moi())
self.assertEqual(inertial.moi(), expectedMOI)

# 45 deg rotation about Z axis, expect different MOI
pose = Pose3d(0, 0, 0, 0, 0, IGN_PI_4)
pose = Pose3d(0, 0, 0, 0, 0, math.pi/4)
expectedMOI = Matrix3d(2.5, -0.5, 0, -0.5, 2.5, 0, 0, 0, 4)
inertial = Inertiald(m, pose)
self.assertNotEqual(inertial.moi(), m.moi())
Expand All @@ -161,18 +161,18 @@ def SetRotation(self, _mass, _ixxyyzz, _ixyxzyz, _unique=True):

rotations = [
Quaterniond.IDENTITY,
Quaterniond(IGN_PI, 0, 0),
Quaterniond(0, IGN_PI, 0),
Quaterniond(0, 0, IGN_PI),
Quaterniond(IGN_PI_2, 0, 0),
Quaterniond(0, IGN_PI_2, 0),
Quaterniond(0, 0, IGN_PI_2),
Quaterniond(IGN_PI_4, 0, 0),
Quaterniond(0, IGN_PI_4, 0),
Quaterniond(0, 0, IGN_PI_4),
Quaterniond(IGN_PI/6, 0, 0),
Quaterniond(0, IGN_PI/6, 0),
Quaterniond(0, 0, IGN_PI/6),
Quaterniond(math.pi, 0, 0),
Quaterniond(0, math.pi, 0),
Quaterniond(0, 0, math.pi),
Quaterniond(math.pi/2, 0, 0),
Quaterniond(0, math.pi/2, 0),
Quaterniond(0, 0, math.pi/2),
Quaterniond(math.pi/4, 0, 0),
Quaterniond(0, math.pi/4, 0),
Quaterniond(0, 0, math.pi/4),
Quaterniond(math.pi/6, 0, 0),
Quaterniond(0, math.pi/6, 0),
Quaterniond(0, 0, math.pi/6),
Quaterniond(0.1, 0.2, 0.3),
Quaterniond(-0.1, 0.2, -0.3),
Quaterniond(0.4, 0.2, 0.5),
Expand Down Expand Up @@ -323,12 +323,12 @@ def test_addition(self):
size = Vector3d(1, 1, 1)
cubeMM3 = MassMatrix3d()
self.assertTrue(cubeMM3.set_from_box(mass, size))
cube = Inertiald(cubeMM3, Pose3d(0, 0, 0, IGN_PI_4, 0, 0))
cube = Inertiald(cubeMM3, Pose3d(0, 0, 0, math.pi/4, 0, 0))

half = MassMatrix3d()
self.assertTrue(half.set_from_box(0.5*mass, Vector3d(0.5, 1, 1)))
left = Inertiald(half, Pose3d(-0.25, 0, 0, IGN_PI_4, 0, 0))
right = Inertiald(half, Pose3d(0.25, 0, 0, IGN_PI_4, 0, 0))
left = Inertiald(half, Pose3d(-0.25, 0, 0, math.pi/4, 0, 0))
right = Inertiald(half, Pose3d(0.25, 0, 0, math.pi/4, 0, 0))

# objects won't match exactly
# since inertia matrices will all be in base frame
Expand Down Expand Up @@ -367,12 +367,12 @@ def test_addition(self):
self.assertTrue(cubeMM3.set_from_box(mass, size))
addedCube = Inertiald(
Inertiald(cubeMM3, Pose3d(-0.5, -0.5, -0.5, 0, 0, 0)) +
Inertiald(cubeMM3, Pose3d(-0.5, 0.5, -0.5, IGN_PI_2, 0, 0)) +
Inertiald(cubeMM3, Pose3d(0.5, -0.5, -0.5, 0, IGN_PI_2, 0)) +
Inertiald(cubeMM3, Pose3d(0.5, 0.5, -0.5, 0, 0, IGN_PI_2)) +
Inertiald(cubeMM3, Pose3d(-0.5, -0.5, 0.5, IGN_PI, 0, 0)) +
Inertiald(cubeMM3, Pose3d(-0.5, 0.5, 0.5, 0, IGN_PI, 0)) +
Inertiald(cubeMM3, Pose3d(0.5, -0.5, 0.5, 0, 0, IGN_PI)) +
Inertiald(cubeMM3, Pose3d(-0.5, 0.5, -0.5, math.pi/2, 0, 0)) +
Inertiald(cubeMM3, Pose3d(0.5, -0.5, -0.5, 0, math.pi/2, 0)) +
Inertiald(cubeMM3, Pose3d(0.5, 0.5, -0.5, 0, 0, math.pi/2)) +
Inertiald(cubeMM3, Pose3d(-0.5, -0.5, 0.5, math.pi, 0, 0)) +
Inertiald(cubeMM3, Pose3d(-0.5, 0.5, 0.5, 0, math.pi, 0)) +
Inertiald(cubeMM3, Pose3d(0.5, -0.5, 0.5, 0, 0, math.pi)) +
Inertiald(cubeMM3, Pose3d(0.5, 0.5, 0.5, 0, 0, 0)))

trueCubeMM3 = MassMatrix3d()
Expand Down

0 comments on commit 5283016

Please sign in to comment.