Skip to content

Commit

Permalink
Merge branch 'ign-math6' into fixes_for_testi386
Browse files Browse the repository at this point in the history
  • Loading branch information
chapulina authored Mar 25, 2022
2 parents cea52b5 + 3b3e7ab commit 908fcc1
Show file tree
Hide file tree
Showing 18 changed files with 338 additions and 27 deletions.
9 changes: 9 additions & 0 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -24,3 +24,12 @@ jobs:
- name: Compile and test
id: ci
uses: ignition-tooling/action-ignition-ci@focal
jammy-ci:
runs-on: ubuntu-latest
name: Ubuntu Jammy CI
steps:
- name: Checkout
uses: actions/checkout@v2
- name: Compile and test
id: ci
uses: ignition-tooling/action-ignition-ci@jammy
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,7 @@ else()
message (STATUS "Searching for Python - found version ${PYTHONLIBS_VERSION_STRING}.")

set(PYBIND11_PYTHON_VERSION 3)
find_package(Python3 QUIET COMPONENTS Interpreter Development)
find_package(pybind11 2.2 QUIET)

if (${pybind11_FOUND})
Expand Down
7 changes: 7 additions & 0 deletions src/python_pybind11/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,14 @@ pybind11_add_module(math SHARED
src/Kmeans.cc
src/Line2.cc
src/Line3.cc
src/MassMatrix3.cc
src/Material.cc
src/Matrix3.cc
src/Matrix4.cc
src/MovingWindowFilter.cc
src/PID.cc
src/Pose3.cc
src/Quaternion.cc
src/Rand.cc
src/RollingMean.cc
src/RotationSpline.cc
Expand All @@ -32,6 +37,8 @@ pybind11_add_module(math SHARED
src/Spline.cc
src/StopWatch.cc
src/Temperature.cc
src/Triangle.cc
src/Triangle3.cc
src/Vector2.cc
src/Vector3.cc
src/Vector4.cc
Expand Down
36 changes: 36 additions & 0 deletions src/python_pybind11/src/MassMatrix3.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
/*
* Copyright (C) 2022 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.
*
*/

#include <string>

#include "MassMatrix3.hh"

namespace ignition
{
namespace math
{
namespace python
{
void defineMathMassMatrix3(py::module &m, const std::string &typestr)
{
helpDefineMathMassMatrix3<double>(m, typestr + "d");
helpDefineMathMassMatrix3<float>(m, typestr + "f");
}

} // namespace python
} // namespace gazebo
} // namespace ignition
9 changes: 8 additions & 1 deletion src/python_pybind11/src/MassMatrix3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -34,12 +34,19 @@ namespace math
namespace python
{
/// Define a pybind11 wrapper for an ignition::math::MassMatrix3
/**
* \param[in] module a pybind11 module to add the definition to
* \param[in] typestr name of the type used by Python
*/
void defineMathMassMatrix3(py::module &m, const std::string &typestr);

/// Help define a pybind11 wrapper for an ignition::math::MassMatrix3
/**
* \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 defineMathMassMatrix3(py::module &m, const std::string &typestr)
void helpDefineMathMassMatrix3(py::module &m, const std::string &typestr)
{
using Class = ignition::math::MassMatrix3<T>;
std::string pyclass_name = typestr;
Expand Down
37 changes: 37 additions & 0 deletions src/python_pybind11/src/Matrix3.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
/*
* Copyright (C) 2022 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.
*
*/

#include <string>

#include "Matrix3.hh"

namespace ignition
{
namespace math
{
namespace python
{
void defineMathMatrix3(py::module &m, const std::string &typestr)
{
helpDefineMathMatrix3<double>(m, typestr + "d");
helpDefineMathMatrix3<float>(m, typestr + "f");
helpDefineMathMatrix3<int>(m, typestr + "i");
}

} // namespace python
} // namespace gazebo
} // namespace ignition
9 changes: 8 additions & 1 deletion src/python_pybind11/src/Matrix3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,19 @@ namespace math
namespace python
{
/// Define a pybind11 wrapper for an ignition::math::Matrix3
/**
* \param[in] module a pybind11 module to add the definition to
* \param[in] typestr name of the type used by Python
*/
void defineMathMatrix3(py::module &m, const std::string &typestr);

/// Help define a pybind11 wrapper for an ignition::math::Matrix3
/**
* \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 defineMathMatrix3(py::module &m, const std::string &typestr)
void helpDefineMathMatrix3(py::module &m, const std::string &typestr)
{
using Class = ignition::math::Matrix3<T>;
auto toString = [](const Class &si) {
Expand Down
37 changes: 37 additions & 0 deletions src/python_pybind11/src/Matrix4.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
/*
* Copyright (C) 2022 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.
*
*/

#include <string>

#include "Matrix4.hh"

namespace ignition
{
namespace math
{
namespace python
{
void defineMathMatrix4(py::module &m, const std::string &typestr)
{
helpDefineMathMatrix4<double>(m, typestr + "d");
helpDefineMathMatrix4<float>(m, typestr + "f");
helpDefineMathMatrix4<int>(m, typestr + "i");
}

} // namespace python
} // namespace gazebo
} // namespace ignition
9 changes: 8 additions & 1 deletion src/python_pybind11/src/Matrix4.hh
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,20 @@ namespace math
{
namespace python
{
/// Define a pybind11 wrapper for an ignition::math::Matrix4
/**
* \param[in] module a pybind11 module to add the definition to
* \param[in] typestr name of the type used by Python
*/
void defineMathMatrix4(py::module &m, const std::string &typestr);

/// Define a pybind11 wrapper for an ignition::math::Matrix4
/**
* \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 defineMathMatrix4(py::module &m, const std::string &typestr)
void helpDefineMathMatrix4(py::module &m, const std::string &typestr)
{
using Class = ignition::math::Matrix4<T>;
auto toString = [](const Class &si) {
Expand Down
37 changes: 37 additions & 0 deletions src/python_pybind11/src/Pose3.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
/*
* Copyright (C) 2022 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.
*
*/

#include <string>

#include "Pose3.hh"

namespace ignition
{
namespace math
{
namespace python
{
void defineMathPose3(py::module &m, const std::string &typestr)
{
helpDefineMathPose3<double>(m, typestr + "d");
helpDefineMathPose3<float>(m, typestr + "f");
helpDefineMathPose3<int>(m, typestr + "i");
}

} // namespace python
} // namespace gazebo
} // namespace ignition
9 changes: 8 additions & 1 deletion src/python_pybind11/src/Pose3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,19 @@ namespace math
namespace python
{
/// Define a pybind11 wrapper for an ignition::math::Pose3
/**
* \param[in] module a pybind11 module to add the definition to
* \param[in] typestr name of the type used by Python
*/
void defineMathPose3(py::module &m, const std::string &typestr);

/// Help define a pybind11 wrapper for an ignition::math::Pose3
/**
* \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 defineMathPose3(py::module &m, const std::string &typestr)
void helpDefineMathPose3(py::module &m, const std::string &typestr)
{
using Class = ignition::math::Pose3<T>;
auto toString = [](const Class &si) {
Expand Down
37 changes: 37 additions & 0 deletions src/python_pybind11/src/Quaternion.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
/*
* Copyright (C) 2022 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.
*
*/

#include <string>

#include "Quaternion.hh"

namespace ignition
{
namespace math
{
namespace python
{
void defineMathQuaternion(py::module &m, const std::string &typestr)
{
helpDefineMathQuaternion<double>(m, typestr + "d");
helpDefineMathQuaternion<float>(m, typestr + "f");
helpDefineMathQuaternion<int>(m, typestr + "i");
}

} // namespace python
} // namespace gazebo
} // namespace ignition
9 changes: 8 additions & 1 deletion src/python_pybind11/src/Quaternion.hh
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,19 @@ 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
*/
void defineMathQuaternion(py::module &m, const std::string &typestr);

/// Help 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)
void helpDefineMathQuaternion(py::module &m, const std::string &typestr)
{
using Class = ignition::math::Quaternion<T>;
auto toString = [](const Class &si) {
Expand Down
37 changes: 37 additions & 0 deletions src/python_pybind11/src/Triangle.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
/*
* Copyright (C) 2022 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.
*
*/

#include <string>

#include "Triangle.hh"

namespace ignition
{
namespace math
{
namespace python
{
void defineMathTriangle(py::module &m, const std::string &typestr)
{
helpDefineMathTriangle<double>(m, typestr + "d");
helpDefineMathTriangle<float>(m, typestr + "f");
helpDefineMathTriangle<int>(m, typestr + "i");
}

} // namespace python
} // namespace gazebo
} // namespace ignition
9 changes: 8 additions & 1 deletion src/python_pybind11/src/Triangle.hh
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,19 @@ namespace math
namespace python
{
/// Define a pybind11 wrapper for an ignition::math::Triangle
/**
* \param[in] module a pybind11 module to add the definition to
* \param[in] typestr name of the type used by Python
*/
void defineMathTriangle(py::module &m, const std::string &typestr);

/// Help define a pybind11 wrapper for an ignition::math::Triangle
/**
* \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 defineMathTriangle(py::module &m, const std::string &typestr)
void helpDefineMathTriangle(py::module &m, const std::string &typestr)
{
using Class = ignition::math::Triangle<T>;
py::class_<Class>(m,
Expand Down
Loading

0 comments on commit 908fcc1

Please sign in to comment.