diff --git a/.github/ci/packages.apt b/.github/ci/packages.apt index ac2ae40d2..9c1b95126 100644 --- a/.github/ci/packages.apt +++ b/.github/ci/packages.apt @@ -2,3 +2,4 @@ libeigen3-dev libignition-cmake2-dev ruby-dev swig +python3-pybind11 diff --git a/CMakeLists.txt b/CMakeLists.txt index 9080bc26f..838a29aae 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -15,6 +15,7 @@ find_package(ignition-cmake2 2.8.0 REQUIRED) # Configure the project #============================================================================ set (c++standard 17) +set (CMAKE_CXX_STANDARD 17) ign_configure_project(VERSION_SUFFIX) #============================================================================ diff --git a/include/ignition/math/Vector2.hh b/include/ignition/math/Vector2.hh index beb3fa6f6..6bf68b1d0 100644 --- a/include/ignition/math/Vector2.hh +++ b/include/ignition/math/Vector2.hh @@ -129,8 +129,8 @@ namespace ignition /// \return the result public: Vector2 Round() { - this->data[0] = std::nearbyint(this->data[0]); - this->data[1] = std::nearbyint(this->data[1]); + this->data[0] = static_cast(std::nearbyint(this->data[0])); + this->data[1] = static_cast(std::nearbyint(this->data[1])); return *this; } diff --git a/include/ignition/math/Vector3.hh b/include/ignition/math/Vector3.hh index 3efe4f9bd..85952e13a 100644 --- a/include/ignition/math/Vector3.hh +++ b/include/ignition/math/Vector3.hh @@ -163,9 +163,9 @@ namespace ignition /// \return the result public: Vector3 Round() { - this->data[0] = std::nearbyint(this->data[0]); - this->data[1] = std::nearbyint(this->data[1]); - this->data[2] = std::nearbyint(this->data[2]); + this->data[0] = static_cast(std::nearbyint(this->data[0])); + this->data[1] = static_cast(std::nearbyint(this->data[1])); + this->data[2] = static_cast(std::nearbyint(this->data[2])); return *this; } diff --git a/include/ignition/math/Vector4.hh b/include/ignition/math/Vector4.hh index 4459c3899..9d81d1d85 100644 --- a/include/ignition/math/Vector4.hh +++ b/include/ignition/math/Vector4.hh @@ -122,10 +122,10 @@ namespace ignition /// \brief Round to near whole number. public: void Round() { - this->data[0] = std::nearbyint(this->data[0]); - this->data[1] = std::nearbyint(this->data[1]); - this->data[2] = std::nearbyint(this->data[2]); - this->data[3] = std::nearbyint(this->data[3]); + this->data[0] = static_cast(std::nearbyint(this->data[0])); + this->data[1] = static_cast(std::nearbyint(this->data[1])); + this->data[2] = static_cast(std::nearbyint(this->data[2])); + this->data[3] = static_cast(std::nearbyint(this->data[3])); } /// \brief Get a rounded version of this vector diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index f9e15f386..6c3a024b6 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -14,4 +14,5 @@ add_subdirectory(graph) # Bindings subdirectories add_subdirectory(python) +add_subdirectory(python_pybind11) add_subdirectory(ruby) diff --git a/src/python/CMakeLists.txt b/src/python/CMakeLists.txt index 126d8b90e..01284951e 100644 --- a/src/python/CMakeLists.txt +++ b/src/python/CMakeLists.txt @@ -26,7 +26,7 @@ if (PYTHONLIBS_FOUND) set(SWIG_PY_LIB pymath) set(SWIG_PY_LIB_OUTPUT math) - set(CMAKE_SWIG_OUTDIR "${CMAKE_BINARY_DIR}/lib/python") + set(CMAKE_SWIG_OUTDIR "${CMAKE_BINARY_DIR}/lib/python/swig") if(CMAKE_VERSION VERSION_GREATER 3.8.0) SWIG_ADD_LIBRARY(${SWIG_PY_LIB} LANGUAGE python SOURCES python.i) else() @@ -77,12 +77,12 @@ if (PYTHONLIBS_FOUND) endif() else() # If not a system installation, respect local paths - set(IGN_PYTHON_INSTALL_PATH ${IGN_LIB_INSTALL_DIR}/python) + set(IGN_PYTHON_INSTALL_PATH ${IGN_LIB_INSTALL_DIR}/python/swig) endif() set(IGN_PYTHON_INSTALL_PATH "${IGN_PYTHON_INSTALL_PATH}/ignition") install(TARGETS ${SWIG_PY_LIB} DESTINATION ${IGN_PYTHON_INSTALL_PATH}) - install(FILES ${CMAKE_BINARY_DIR}/lib/python/math.py DESTINATION ${IGN_PYTHON_INSTALL_PATH}) + install(FILES ${CMAKE_BINARY_DIR}/lib/python/swig/math.py DESTINATION ${IGN_PYTHON_INSTALL_PATH}) if (BUILD_TESTING) # Add the Python tests @@ -124,10 +124,7 @@ if (PYTHONLIBS_FOUND) Temperature_TEST Triangle_TEST Triangle3_TEST - Vector2_TEST - Vector3_TEST Vector3Stats_TEST - Vector4_TEST ) foreach (test ${python_tests}) @@ -135,7 +132,7 @@ if (PYTHONLIBS_FOUND) "${PYTHON_EXECUTABLE}" "${CMAKE_SOURCE_DIR}/src/python/${test}.py") set(_env_vars) - list(APPEND _env_vars "PYTHONPATH=${FAKE_INSTALL_PREFIX}/lib/python/") + list(APPEND _env_vars "PYTHONPATH=${FAKE_INSTALL_PREFIX}/lib/python/swig") list(APPEND _env_vars "LD_LIBRARY_PATH=${FAKE_INSTALL_PREFIX}/lib:$ENV{LD_LIBRARY_PATH}") set_tests_properties(${test}.py PROPERTIES ENVIRONMENT "${_env_vars}") diff --git a/src/python_pybind11/CMakeLists.txt b/src/python_pybind11/CMakeLists.txt new file mode 100644 index 000000000..368492352 --- /dev/null +++ b/src/python_pybind11/CMakeLists.txt @@ -0,0 +1,82 @@ +if(WIN32 AND CMAKE_BUILD_TYPE STREQUAL "Debug") + # pybind11 logic for setting up a debug build when both a debug and release + # python interpreter are present in the system seems to be pretty much broken. + # This works around the issue. + set(PYTHON_LIBRARIES "${PYTHON_DEBUG_LIBRARIES}") +endif() + +set(PYBIND11_PYTHON_VERSION 3) + +find_package(pybind11 2.2 QUIET) + +if (${pybind11_FOUND}) + message(STATUS "Building pybind11 interfaces") + # Split from main extension and converted to pybind11 + pybind11_add_module(math SHARED + src/_ignition_math_pybind11.cc + ) + + if(USE_SYSTEM_PATHS_FOR_PYTHON_INSTALLATION) + if(${CMAKE_VERSION} VERSION_LESS "3.12.0") + execute_process( + COMMAND "${PYTHON_EXECUTABLE}" -c "if True: + from distutils import sysconfig as sc + print(sc.get_python_lib(plat_specific=True))" + OUTPUT_VARIABLE Python3_SITEARCH + OUTPUT_STRIP_TRAILING_WHITESPACE) + else() + # Get install variable from Python3 module + # Python3_SITEARCH is available from 3.12 on, workaround if needed: + find_package(Python3 COMPONENTS Interpreter) + endif() + + if(USE_DIST_PACKAGES_FOR_PYTHON) + string(REPLACE "site-packages" "dist-packages" IGN_PYTHON_INSTALL_PATH ${Python3_SITEARCH}) + else() + # custom cmake command is returning dist-packages + string(REPLACE "dist-packages" "site-packages" IGN_PYTHON_INSTALL_PATH ${Python3_SITEARCH}) + endif() + else() + # If not a system installation, respect local paths + set(IGN_PYTHON_INSTALL_PATH ${IGN_LIB_INSTALL_DIR}/python) + endif() + + set(IGN_PYTHON_INSTALL_PATH "${IGN_PYTHON_INSTALL_PATH}/ignition") + + # Set the build location and install location for a CPython extension + function(configure_build_install_location _library_name) + # Install into test folder in build space for unit tests to import + set_target_properties(${_library_name} PROPERTIES + # Use generator expression to avoid prepending a build type specific directory on Windows + LIBRARY_OUTPUT_DIRECTORY $<1:${CMAKE_CURRENT_BINARY_DIR}/test> + RUNTIME_OUTPUT_DIRECTORY $<1:${CMAKE_CURRENT_BINARY_DIR}/test>) + + # Install library for actual use + install(TARGETS ${_library_name} + DESTINATION "${IGN_PYTHON_INSTALL_PATH}/" + ) + endfunction() + + configure_build_install_location(math) + + if (BUILD_TESTING) + # Add the Python tests + set(python_tests + Vector2_TEST + Vector3_TEST + Vector4_TEST + ) + + foreach (test ${python_tests}) + add_test(NAME ${test}.py COMMAND + "${PYTHON_EXECUTABLE}" "${CMAKE_SOURCE_DIR}/src/python_pybind11/test/${test}.py") + + set(_env_vars) + list(APPEND _env_vars "PYTHONPATH=${FAKE_INSTALL_PREFIX}/lib/python/") + list(APPEND _env_vars "LD_LIBRARY_PATH=${FAKE_INSTALL_PREFIX}/lib:$ENV{LD_LIBRARY_PATH}") + set_tests_properties(${test}.py PROPERTIES + ENVIRONMENT "${_env_vars}") + endforeach() + + endif() +endif() diff --git a/src/python_pybind11/src/Vector2.hh b/src/python_pybind11/src/Vector2.hh new file mode 100644 index 000000000..98ce5a9a3 --- /dev/null +++ b/src/python_pybind11/src/Vector2.hh @@ -0,0 +1,143 @@ +/* + * 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__VECTOR2D_HH_ +#define IGNITION_MATH_PYTHON__VECTOR2D_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::Vector2 +/** + * \param[in] module a pybind11 module to add the definition to + */ +template +void defineMathVector2(py::module &m, const std::string &typestr) +{ + using Class = ignition::math::Vector2; + auto toString = [](const Class &si) { + std::stringstream stream; + stream << si; + return stream.str(); + }; + std::string pyclass_name = typestr; + py::class_(m, + pyclass_name.c_str(), + py::buffer_protocol(), + py::dynamic_attr()) + .def(py::init<>()) + .def(py::init()) + .def(py::init()) + .def("sum", &Class::Sum, "Return the sum of the values") + .def("distance", &Class::Distance, "Calc distance to the given point") + .def("length", + &Class::Length, + "Returns the length (magnitude) of the vector") + .def("squared_length", + &Class::SquaredLength, + "Return the square of the length (magnitude) of the vector") + .def("normalize", &Class::Normalize, "Normalize the vector length") + .def("normalized", &Class::Normalized, "Return a normalized vector") + .def("round", + &Class::Round, + "Round to near whole number, return the result.") + .def("rounded", &Class::Rounded, "Get a rounded version of this vector") + .def("set", &Class::Set, "Set the contents of the vector") + .def("dot", + &Class::Dot, + "Return the dot product of this vector and another vector") + .def("abs_dot", &Class::AbsDot, + "Return the absolute dot product of this vector and " + "another vector. This is similar to the Dot function, except the " + "absolute value of each component of the vector is used.") + .def("abs", + &Class::Abs, + "Get the absolute value of the vector") + .def("max", + py::overload_cast(&Class::Max), + "Set this vector's components to the maximum of itself and the " + "passed in vector") + .def("max", py::overload_cast<>(&Class::Max, py::const_), + "Get the maximum value in the vector") + .def("min", py::overload_cast(&Class::Min), + "Set this vector's components to the minimum of itself and the " + "passed in vector") + .def("min", py::overload_cast<>(&Class::Min, py::const_), + "Get the minimum value in the vector") + .def(py::self + py::self) + .def(py::self += py::self) + .def(py::self + T()) + .def(py::self += T()) + .def(py::self * py::self) + .def(py::self *= py::self) + .def(py::self * T()) + .def(py::self *= T()) + .def(py::self - py::self) + .def(py::self -= py::self) + .def(py::self - T()) + .def(py::self -= T()) + .def(py::self / py::self) + .def(py::self /= py::self) + .def(py::self / T()) + .def(py::self /= T()) + .def(py::self != py::self) + .def(py::self == py::self) + .def(-py::self) + .def("equal", &Class::Equal, "Equal to operator") + .def("is_finite", + &Class::IsFinite, + "See if a point is finite (e.g., not nan)") + .def("correct", &Class::Correct, "Corrects any nan values") + .def("x", py::overload_cast<>(&Class::X), "Get the x value.") + .def("y", py::overload_cast<>(&Class::Y), "Get the y value.") + .def("x", py::overload_cast(&Class::X), "Set the x value.") + .def("y", py::overload_cast(&Class::Y), "Set the y value.") + .def_readonly_static("ZERO", &Class::Zero, "math::Vector2(0, 0)") + .def_readonly_static("ONE", &Class::One, "math::Vector2(1, 1)") + .def_readonly_static("NAN", &Class::NaN, "math::Vector3(NaN, NaN)") + .def("__copy__", [](const Class &self) { + return Class(self); + }) + .def("__deepcopy__", [](const Class &self, py::dict) { + return Class(self); + }, "memo"_a) + .def("__getitem__", + py::overload_cast(&Class::operator[], py::const_)) + .def("__setitem__", + [](Class* vec, unsigned index, T val) { (*vec)[index] = val; }) + .def("__str__", toString) + .def("__repr__", toString); +} + +} // namespace python +} // namespace gazebo +} // namespace ignition + +#endif // IGNITION_MATH_PYTHON__VECTOR2D_HH_ diff --git a/src/python_pybind11/src/Vector3.hh b/src/python_pybind11/src/Vector3.hh new file mode 100644 index 000000000..991e26371 --- /dev/null +++ b/src/python_pybind11/src/Vector3.hh @@ -0,0 +1,166 @@ +/* + * 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__VECTOR3D_HH_ +#define IGNITION_MATH_PYTHON__VECTOR3D_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::Vector3 +/** + * \param[in] module a pybind11 module to add the definition to + */ +template +void defineMathVector3(py::module &m, const std::string &typestr) +{ + using Class = ignition::math::Vector3; + auto toString = [](const Class &si) { + std::stringstream stream; + stream << si; + return stream.str(); + }; + std::string pyclass_name = typestr; + py::class_(m, + pyclass_name.c_str(), + py::buffer_protocol(), + py::dynamic_attr()) + .def(py::init<>()) + .def(py::init()) + .def(py::init()) + .def("sum", &Class::Sum, "Return the sum of the values") + .def("distance", + py::overload_cast(&Class::Distance, py::const_), + "Calc distance to the given point") + .def("distance", + py::overload_cast(&Class::Distance, py::const_), + "Calc distance to the given point") + .def("length", + &Class::Length, + "Returns the length (magnitude) of the vector") + .def("squared_length", + &Class::SquaredLength, + "Return the square of the length (magnitude) of the vector") + .def("normalize", &Class::Normalize, "Normalize the vector length") + .def("normalized", &Class::Normalized, "Return a normalized vector") + .def("round", + py::overload_cast<>(&Class::Round), + "Round to near whole number, return the result.") + .def("round", py::overload_cast(&Class::Round)) + .def("rounded", &Class::Rounded, "Get a rounded version of this vector") + .def("set", &Class::Set, "Set the contents of the vector") + .def("cross", + &Class::Cross, + "Return the cross product of this vector with another vector.") + .def("dot", + &Class::Dot, + "Return the dot product of this vector and another vector") + .def("abs_dot", &Class::AbsDot, + "Return the absolute dot product of this vector and " + "another vector. This is similar to the Dot function, except the " + "absolute value of each component of the vector is used.") + .def("abs", &Class::Abs, "Get the absolute value of the vector") + .def("perpendicular", + &Class::Perpendicular, + "Return a vector that is perpendicular to this one.") + .def("normal", &Class::Normal, "Get a normal vector to a triangle") + .def("dist_to_line", + &Class::DistToLine, + "Get distance to an infinite line defined by 2 points.") + .def("max", + py::overload_cast(&Class::Max), + "Set this vector's components to the maximum of itself and the " + "passed in vector") + .def("max", py::overload_cast<>(&Class::Max, py::const_), + "Get the maximum value in the vector") + .def("min", py::overload_cast(&Class::Min), + "Set this vector's components to the minimum of itself and the " + "passed in vector") + .def("min", py::overload_cast<>(&Class::Min, py::const_), + "Get the minimum value in the vector") + .def(py::self + py::self) + .def(py::self += py::self) + .def(py::self + T()) + .def(py::self += T()) + .def(py::self * py::self) + .def(py::self *= py::self) + .def(py::self * T()) + .def(py::self *= T()) + .def(py::self - py::self) + .def(py::self -= py::self) + .def(py::self - T()) + .def(py::self -= T()) + .def(py::self / py::self) + .def(py::self /= py::self) + .def(py::self / T()) + .def(py::self /= T()) + .def(py::self != py::self) + .def(py::self == py::self) + .def(-py::self) + .def("equal", + py::overload_cast(&Class::Equal, py::const_), + "Equality test with tolerance.") + .def("equal", + py::overload_cast(&Class::Equal, py::const_), + "Equal to operator") + .def("is_finite", + &Class::IsFinite, + "See if a point is finite (e.g., not nan)") + .def("correct", &Class::Correct, "Corrects any nan values") + .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("x", py::overload_cast(&Class::X), "Set the x value.") + .def("y", py::overload_cast(&Class::Y), "Set the y value.") + .def("z", py::overload_cast(&Class::Z), "Set the z value.") + .def_readonly_static("ZERO", &Class::Zero, "math::Vector3(0, 0, 0)") + .def_readonly_static("ONE", &Class::One, "math::Vector3(1, 1, 1)") + .def_readonly_static("UNIT_X", &Class::UnitX, "math::Vector3(1, 0, 0)") + .def_readonly_static("UNIT_Y", &Class::UnitY, "math::Vector3(0, 1, 0)") + .def_readonly_static("UNIT_Z", &Class::UnitZ, "math::Vector3(0, 0, 1)") + .def_readonly_static("NAN", &Class::NaN, "math::Vector3(NaN, NaN, NaN)") + .def("__copy__", [](const Class &self) { + return Class(self); + }) + .def("__deepcopy__", [](const Class &self, py::dict) { + return Class(self); + }, "memo"_a) + .def("__getitem__", + py::overload_cast(&Class::operator[], py::const_)) + .def("__setitem__", + [](Class* vec, unsigned index, T val) { (*vec)[index] = val; }) + .def("__str__", toString) + .def("__repr__", toString); +} +} // namespace python +} // namespace gazebo +} // namespace ignition + +#endif // IGNITION_MATH_PYTHON__VECTOR3D_HH_ diff --git a/src/python_pybind11/src/Vector4.hh b/src/python_pybind11/src/Vector4.hh new file mode 100644 index 000000000..5bf3b6fd7 --- /dev/null +++ b/src/python_pybind11/src/Vector4.hh @@ -0,0 +1,152 @@ +/* + * 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__VECTOR4D_HH_ +#define IGNITION_MATH_PYTHON__VECTOR4D_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::Vector4 +/** + * \param[in] module a pybind11 module to add the definition to + */ +template +void defineMathVector4(py::module &m, const std::string &typestr) +{ + using Class = ignition::math::Vector4; + auto toString = [](const Class &si) { + std::stringstream stream; + stream << si; + return stream.str(); + }; + std::string pyclass_name = typestr; + py::class_(m, + pyclass_name.c_str(), + py::buffer_protocol(), + py::dynamic_attr()) + .def(py::init<>()) + .def(py::init()) + .def(py::init()) + .def("sum", &Class::Sum, "Return the sum of the values") + .def("distance", + py::overload_cast(&Class::Distance, py::const_), + "Calc distance to the given point") + .def("distance", + py::overload_cast(&Class::Distance, py::const_), + "Calc distance to the given point") + .def("length", + &Class::Length, + "Returns the length (magnitude) of the vector") + .def("squared_length", + &Class::SquaredLength, + "Return the square of the length (magnitude) of the vector") + .def("normalize", &Class::Normalize, "Normalize the vector length") + .def("normalized", &Class::Normalized, "Return a normalized vector") + .def("round", + &Class::Round, + "Round to near whole number, return the result.") + .def("rounded", &Class::Rounded, "Get a rounded version of this vector") + .def("set", &Class::Set, "Set the contents of the vector") + .def("dot", + &Class::Dot, + "Return the dot product of this vector and another vector") + .def("abs_dot", &Class::AbsDot, + "Return the absolute dot product of this vector and " + "another vector. This is similar to the Dot function, except the " + "absolute value of each component of the vector is used.") + .def("abs", &Class::Abs, " Get the absolute value of the vector") + .def("max", + py::overload_cast(&Class::Max), + "Set this vector's components to the maximum of itself and the " + "passed in vector") + .def("max", py::overload_cast<>(&Class::Max, py::const_), + "Get the maximum value in the vector") + .def("min", py::overload_cast(&Class::Min), + "Set this vector's components to the minimum of itself and the " + "passed in vector") + .def("min", py::overload_cast<>(&Class::Min, py::const_), + "Get the minimum value in the vector") + .def(py::self + py::self) + .def(py::self += py::self) + .def(py::self + T()) + .def(py::self += T()) + .def(py::self * py::self) + .def(py::self *= py::self) + .def(py::self * T()) + .def(py::self *= T()) + .def(py::self - py::self) + .def(py::self -= py::self) + .def(py::self - T()) + .def(py::self -= T()) + .def(py::self / py::self) + .def(py::self /= py::self) + .def(py::self / T()) + .def(py::self /= T()) + .def(py::self != py::self) + .def(py::self == py::self) + .def(-py::self) + .def("equal", &Class::Equal, "Equal to operator") + .def("is_finite", + &Class::IsFinite, + "See if a point is finite (e.g., not nan)") + .def("correct", &Class::Correct, "Corrects any nan values") + .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(&Class::X), "Set the x value.") + .def("y", py::overload_cast(&Class::Y), "Set the y value.") + .def("z", py::overload_cast(&Class::Z), "Set the z value.") + .def("w", py::overload_cast(&Class::W), "Set the w value.") + .def_readonly_static("ZERO", &Class::Zero, "math::Vector4(0, 0, 0, 0)") + .def_readonly_static("ONE", &Class::One, "math::Vector4(1, 1, 1, 1)") + .def_readonly_static("NAN", + &Class::NaN, + "math::Vector4(NaN, NaN, NaN, NaN)") + .def("__copy__", [](const Class &self) { + return Class(self); + }) + .def("__deepcopy__", [](const Class &self, py::dict) { + return Class(self); + }, "memo"_a) + .def("__getitem__", + py::overload_cast(&Class::operator[], py::const_)) + .def("__setitem__", + [](Class* vec, unsigned index, T val) { (*vec)[index] = val; }) + .def("__str__", toString) + .def("__repr__", toString); +} + +} // namespace python +} // namespace gazebo +} // namespace ignition + +#endif // IGNITION_MATH_PYTHON__VECTOR4D_HH_ diff --git a/src/python_pybind11/src/_ignition_math_pybind11.cc b/src/python_pybind11/src/_ignition_math_pybind11.cc new file mode 100644 index 000000000..da0029102 --- /dev/null +++ b/src/python_pybind11/src/_ignition_math_pybind11.cc @@ -0,0 +1,41 @@ +// Copyright 2021 Open Source Robotics Foundation, Inc. +// +// 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. + +#include + +#include "Vector2.hh" +#include "Vector3.hh" +#include "Vector4.hh" + +namespace py = pybind11; + +PYBIND11_MODULE(math, m) +{ + m.doc() = "Ignition Math Python Library."; + + + + + ignition::math::python::defineMathVector2(m, "Vector2d"); + ignition::math::python::defineMathVector2(m, "Vector2i"); + ignition::math::python::defineMathVector2(m, "Vector2f"); + + ignition::math::python::defineMathVector3(m, "Vector3d"); + ignition::math::python::defineMathVector3(m, "Vector3i"); + ignition::math::python::defineMathVector3(m, "Vector3f"); + + ignition::math::python::defineMathVector4(m, "Vector4d"); + ignition::math::python::defineMathVector4(m, "Vector4i"); + ignition::math::python::defineMathVector4(m, "Vector4f"); +} diff --git a/src/python/Vector2_TEST.py b/src/python_pybind11/test/Vector2_TEST.py similarity index 99% rename from src/python/Vector2_TEST.py rename to src/python_pybind11/test/Vector2_TEST.py index 6043f0f0c..597bb35b6 100644 --- a/src/python/Vector2_TEST.py +++ b/src/python_pybind11/test/Vector2_TEST.py @@ -12,8 +12,10 @@ # See the License for the specific language governing permissions and # limitations under the License. -import unittest +import copy import math +import unittest + from ignition.math import Vector2d from ignition.math import Vector2f @@ -184,7 +186,7 @@ def test_add(self): vec1 = Vector2d(0.1, 0.2) vec2 = Vector2d(1.1, 2.2) - vec3 = vec1 + vec3 = copy.deepcopy(vec1) vec3 += vec2 self.assertAlmostEqual(vec1 + vec2, Vector2d(1.2, 2.4)) @@ -216,7 +218,7 @@ def test_sub(self): vec1 = Vector2d(0.1, 0.2) vec2 = Vector2d(1.1, 2.2) - vec3 = vec2 + vec3 = copy.deepcopy(vec2) vec3 -= vec1 self.assertAlmostEqual(vec2 - vec1, Vector2d(1.0, 2.0)) diff --git a/src/python/Vector3_TEST.py b/src/python_pybind11/test/Vector3_TEST.py similarity index 99% rename from src/python/Vector3_TEST.py rename to src/python_pybind11/test/Vector3_TEST.py index 0c3b7e610..4b0e1a6ee 100644 --- a/src/python/Vector3_TEST.py +++ b/src/python_pybind11/test/Vector3_TEST.py @@ -12,8 +12,10 @@ # See the License for the specific language governing permissions and # limitations under the License. -import unittest +import copy import math +import unittest + from ignition.math import Vector3d from ignition.math import Vector3f @@ -225,7 +227,7 @@ def test_add(self): vec1 = Vector3d(0.1, 0.2, 0.4) vec2 = Vector3d(1.1, 2.2, 3.4) - vec3 = vec1 + vec3 = copy.deepcopy(vec1) vec3 += vec2 self.assertEqual(vec1 + vec2, Vector3d(1.2, 2.4, 3.8)) @@ -257,7 +259,7 @@ def test_sub(self): vec1 = Vector3d(0.1, 0.2, 0.4) vec2 = Vector3d(1.1, 2.2, 3.4) - vec3 = vec2 + vec3 = copy.deepcopy(vec2) vec3 -= vec1 self.assertEqual(vec2 - vec1, Vector3d(1.0, 2.0, 3.0)) diff --git a/src/python/Vector4_TEST.py b/src/python_pybind11/test/Vector4_TEST.py similarity index 99% rename from src/python/Vector4_TEST.py rename to src/python_pybind11/test/Vector4_TEST.py index 854050277..e8f57f7da 100644 --- a/src/python/Vector4_TEST.py +++ b/src/python_pybind11/test/Vector4_TEST.py @@ -12,9 +12,10 @@ # See the License for the specific language governing permissions and # limitations under the License. - -import unittest +import copy import math +import unittest + from ignition.math import Vector4d from ignition.math import Vector4f @@ -132,7 +133,7 @@ def test_add(self): vec1 = Vector4d(0.1, 0.2, 0.4, 0.8) vec2 = Vector4d(1.1, 2.2, 3.4, 4.3) - vec3 = vec1 + vec3 = copy.deepcopy(vec1) vec3 += vec2 self.assertEqual(vec1 + vec2, Vector4d(1.2, 2.4, 3.8, 5.1)) @@ -164,7 +165,7 @@ def test_sub(self): vec1 = Vector4d(0.1, 0.2, 0.4, 0.8) vec2 = Vector4d(1.1, 2.2, 3.4, 4.3) - vec3 = vec2 + vec3 = copy.deepcopy(vec2) vec3 -= vec1 self.assertEqual(vec2 - vec1, Vector4d(1.0, 2.0, 3.0, 3.5))