Skip to content

Commit

Permalink
Merge branch 'ign-math6' into ahcorde/pybind11/cylinder
Browse files Browse the repository at this point in the history
  • Loading branch information
ahcorde authored Dec 29, 2021
2 parents 34c5bd5 + 5d2f924 commit c3fba38
Show file tree
Hide file tree
Showing 5 changed files with 136 additions and 3 deletions.
1 change: 0 additions & 1 deletion src/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,6 @@ if (PYTHONLIBS_FOUND)
set(python_tests
Box_TEST
Frustum_TEST
OrientedBox_TEST
Plane_TEST
python_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 @@ -99,6 +99,7 @@ if (${pybind11_FOUND})
Matrix4_TEST
MassMatrix3_TEST
MovingWindowFilter_TEST
OrientedBox_TEST
PID_TEST
Pose3_TEST
Quaternion_TEST
Expand Down
129 changes: 129 additions & 0 deletions src/python_pybind11/src/OrientedBox.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,129 @@
/*
* 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__ORIENTEDBOX_HH_
#define IGNITION_MATH_PYTHON__ORIENTEDBOX_HH_

#include <string>

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

#include <ignition/math/OrientedBox.hh>

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

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

using Class = ignition::math::OrientedBox<T>;
std::string pyclass_name = typestr;
auto toString = [](const Class &si) {
std::stringstream stream;
stream << si;
return stream.str();
};
py::class_<Class>(m,
pyclass_name.c_str(),
py::buffer_protocol(),
py::dynamic_attr())
.def(py::init<>())
.def(py::init<const ignition::math::Vector3<T>&,
const ignition::math::Pose3<T>&>())
.def(py::init<const ignition::math::Vector3<T>&,
const ignition::math::Pose3<T>&,
const ignition::math::Material&>())
.def(py::init<const ignition::math::Vector3<T>&>())
.def(py::init<const Class&>())
.def(py::init<const ignition::math::Vector3<T>&,
const ignition::math::Material&>())
.def(py::self != py::self)
.def(py::self == py::self)
.def("pose",
py::overload_cast<ignition::math::Pose3<T>&>(&Class::Pose),
"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_),
"Get the size of the OrientedBox.")
.def("size",
py::overload_cast<ignition::math::Vector3<T>&>
(&Class::Size),
"Set the size of the OrientedBox.")
.def("x_length",
&Class::XLength,
"Get the length along the x dimension")
.def("y_length",
&Class::YLength,
"Get the length along the y dimension")
.def("z_length",
&Class::ZLength,
"Get the length along the z dimension")
.def("material",
&Class::Material,
"Get the material associated with this OrientedBox.")
.def("set_material",
&Class::SetMaterial,
"Set the material associated with this OrientedBox.")
.def("volume",
&Class::Volume,
"Get the volume of the OrientedBox in m^3.")
.def("contains",
&Class::Contains,
"Check if a point lies inside the box.")
.def("density_from_mass",
&Class::DensityFromMass,
"Compute the OrientedBox's density given a mass value.")
.def("set_density_from_mass",
&Class::SetDensityFromMass,
"Set the density of this OrientedBox based on a mass value.")
.def("mass_matrix",
&Class::MassMatrix,
"Get the mass matrix for this OrientedBox. This function "
"is only meaningful if the OrientedBox's size and material "
"have been set.")
.def("__copy__", [](const Class &self) {
return Class(self);
})
.def("__deepcopy__", [](const Class &self, py::dict) {
return Class(self);
}, "memo"_a)
.def("__str__", toString)
.def("__repr__", toString);
}

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

#endif // IGNITION_MATH_PYTHON__ORIENTEDBOX_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 @@ -31,6 +31,7 @@
#include "Matrix3.hh"
#include "Matrix4.hh"
#include "MovingWindowFilter.hh"
#include "OrientedBox.hh"
#include "PID.hh"
#include "Pose3.hh"
#include "Quaternion.hh"
Expand Down Expand Up @@ -134,6 +135,8 @@ PYBIND11_MODULE(math, m)
ignition::math::python::defineMathQuaternion<double>(m, "Quaterniond");
ignition::math::python::defineMathQuaternion<float>(m, "Quaternionf");

ignition::math::python::defineMathOrientedBox<double>(m, "OrientedBoxd");

ignition::math::python::defineMathPose3<int>(m, "Pose3i");
ignition::math::python::defineMathPose3<double>(m, "Pose3d");
ignition::math::python::defineMathPose3<float>(m, "Pose3f");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,10 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import math
import unittest

from ignition.math import IGN_PI, OrientedBoxd, MassMatrix3d, Material, Pose3d, Vector3d
from ignition.math import OrientedBoxd, MassMatrix3d, Material, Pose3d, Vector3d

g_tolerance = 1e-6

Expand Down Expand Up @@ -205,7 +206,7 @@ def test_contains_oriented_position(self):

def test_contains_oriented_rotation(self):
# Rotate PI/2 about +x: swap Z and Y
box = OrientedBoxd(Vector3d(1, 2, 3), Pose3d(0, 0, 0, IGN_PI*0.5, 0, 0))
box = OrientedBoxd(Vector3d(1, 2, 3), Pose3d(0, 0, 0, math.pi*0.5, 0, 0))

# Doesn't contain non-rotated vertices
self.assertFalse(box.contains(Vector3d(-0.5, -1.0, -1.5)))
Expand Down

0 comments on commit c3fba38

Please sign in to comment.