diff --git a/src/python/CMakeLists.txt b/src/python/CMakeLists.txt index cc85cf23d..9494e7f7c 100644 --- a/src/python/CMakeLists.txt +++ b/src/python/CMakeLists.txt @@ -107,7 +107,6 @@ if (PYTHONLIBS_FOUND) Sphere_TEST SphericalCoordinates_TEST Temperature_TEST - Triangle3_TEST Vector3Stats_TEST ) diff --git a/src/python_pybind11/CMakeLists.txt b/src/python_pybind11/CMakeLists.txt index ffaa46299..90bb10030 100644 --- a/src/python_pybind11/CMakeLists.txt +++ b/src/python_pybind11/CMakeLists.txt @@ -90,6 +90,7 @@ if (${pybind11_FOUND}) Spline_TEST StopWatch_TEST Triangle_TEST + Triangle3_TEST Vector2_TEST Vector3_TEST Vector4_TEST diff --git a/src/python_pybind11/src/Triangle3.hh b/src/python_pybind11/src/Triangle3.hh new file mode 100644 index 000000000..871ce2ccc --- /dev/null +++ b/src/python_pybind11/src/Triangle3.hh @@ -0,0 +1,106 @@ +/* + * 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__TRIANGLE3_HH_ +#define IGNITION_MATH_PYTHON__TRIANGLE3_HH_ + +#include + +#include +#include + +#include + +namespace py = pybind11; +using namespace pybind11::literals; + +namespace ignition +{ +namespace math +{ +namespace python +{ +/// Define a pybind11 wrapper for an ignition::math::Triangle3 +/** + * \param[in] module a pybind11 module to add the definition to + * \param[in] typestr name of the type used by Python + */ +template +void defineMathTriangle3(py::module &m, const std::string &typestr) +{ + using Class = ignition::math::Triangle3; + py::class_(m, + typestr.c_str(), + py::buffer_protocol(), + py::dynamic_attr()) + .def(py::init<>()) + .def(py::init &, + const math::Vector3 &, + const math::Vector3 &>()) + .def(py::init()) + .def("set", + py::overload_cast &> + (&Class::Set), + "Set one vertex of the triangle.") + .def("set", + py::overload_cast &, + const math::Vector3 &, + const math::Vector3 &> + (&Class::Set), + "Set all vertices of the triangle.") + .def("valid", + &Class::Valid, + "Get whether this triangle is valid, based on triangle " + "inequality: the sum of the lengths of any two sides must be greater " + "than the length of the remaining side.") + .def("side", + &Class::Side, + "Get a line segment for one side of the triangle.") + .def("contains", + py::overload_cast&>(&Class::Contains, py::const_), + "Check if this triangle completely contains the given line " + "segment.") + .def("contains", + py::overload_cast&>(&Class::Contains, py::const_), + "Get whether this triangle contains the given point") + .def("intersects", + &Class::Intersects, + "Get whether the given line intersects this triangle.") + .def("perimeter", + &Class::Perimeter, + "Get the length of the triangle's perimeter.") + .def("area", &Class::Area, "Get the area of this triangle.") + .def("normal", &Class::Normal, "Get the triangle's normal vector.") + .def("__copy__", [](const Class &self) { + return Class(self); + }) + .def("__deepcopy__", [](const Class &self, py::dict) { + return Class(self); + }, "memo"_a) + .def("__getitem__", + (&Class::operator[])) + .def("__getitem__", + py::overload_cast(&Class::operator[], py::const_)) + .def("__setitem__", + [](Class* vec, unsigned index, T val) { (*vec)[index] = val; }); +} + +} // namespace python +} // namespace gazebo +} // namespace ignition + +#endif // IGNITION_MATH_PYTHON__TRIANGLE3_HH_ diff --git a/src/python_pybind11/src/_ignition_math_pybind11.cc b/src/python_pybind11/src/_ignition_math_pybind11.cc index b7169b1ad..f95bacefb 100644 --- a/src/python_pybind11/src/_ignition_math_pybind11.cc +++ b/src/python_pybind11/src/_ignition_math_pybind11.cc @@ -30,6 +30,7 @@ #include "Spline.hh" #include "StopWatch.hh" #include "Triangle.hh" +#include "Triangle3.hh" #include "Vector2.hh" #include "Vector3.hh" #include "Vector4.hh" @@ -91,6 +92,10 @@ PYBIND11_MODULE(math, m) ignition::math::python::defineMathTriangle(m, "Triangled"); ignition::math::python::defineMathTriangle(m, "Trianglef"); + ignition::math::python::defineMathTriangle3(m, "Triangle3i"); + ignition::math::python::defineMathTriangle3(m, "Triangle3d"); + ignition::math::python::defineMathTriangle3(m, "Triangle3f"); + ignition::math::python::defineMathQuaternion(m, "Quaternioni"); ignition::math::python::defineMathQuaternion(m, "Quaterniond"); ignition::math::python::defineMathQuaternion(m, "Quaternionf"); diff --git a/src/python/Triangle3_TEST.py b/src/python_pybind11/test/Triangle3_TEST.py similarity index 100% rename from src/python/Triangle3_TEST.py rename to src/python_pybind11/test/Triangle3_TEST.py