Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Helpers pybind11 interface #313

Merged
merged 4 commits into from
Dec 23, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion src/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,6 @@ if (PYTHONLIBS_FOUND)
Filter_TEST
Frustum_TEST
GaussMarkovProcess_TEST
Helpers_TEST
Inertial_TEST
Kmeans_TEST
Line2_TEST
Expand Down
2 changes: 2 additions & 0 deletions src/python_pybind11/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ if (${pybind11_FOUND})
pybind11_add_module(math SHARED
src/_ignition_math_pybind11.cc
src/Angle.cc
src/Helpers.cc
src/Rand.cc
)

Expand Down Expand Up @@ -69,6 +70,7 @@ if (${pybind11_FOUND})
# Add the Python tests
set(python_tests
Angle_TEST
Helpers_TEST
Rand_TEST
Vector2_TEST
Vector3_TEST
Expand Down
231 changes: 231 additions & 0 deletions src/python_pybind11/src/Helpers.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,231 @@
/*
* 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.
*
*/
#include <tuple>

#include <pybind11/stl.h>

#include "Helpers.hh"
#include <ignition/math/Helpers.hh>
#include <ignition/math/Vector3.hh>

namespace ignition
{
namespace math
{
namespace python
{
class Helpers
{
};

/// \brief Compute sphere volume
/// \param[in] _radius Sphere radius
/// \return sphere volume
float SphereVolume(const float _radius)
{
return IGN_SPHERE_VOLUME(_radius);
}

/// \brief Compute cylinder volume
/// \param[in] _r Cylinder base radius
/// \param[in] _l Cylinder length
/// \return cylinder volume
float CylinderVolume(const float _r, const float _l)
{
return IGN_CYLINDER_VOLUME(_r, _l);
}

/// \brief Compute box volume
/// \param[in] _x X length
/// \param[in] _y Y length
/// \param[in] _z Z length
/// \return box volume
float BoxVolume(const float _x, const float _y, const float _z)
{
return IGN_BOX_VOLUME(_x, _y, _z);
}

/// \brief Compute box volume from a vector
/// \param[in] _v Vector3d that contains the box's dimensions.
/// \return box volume from a vector
float BoxVolumeV(const ignition::math::Vector3d &_v)
{
return IGN_BOX_VOLUME_V(_v);
}
Comment on lines +35 to +68
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I intend on replacing these macros with constexpr functions in main, just a thought when we are forward porting.


/// \brief Sort two numbers, such that _a <= _b
/// \param[out] _a the first number
/// \param[out] _b the second number
/// \return a tuple with the numbers sorted
std::tuple<float, float> Sort2(float _a, float _b)
{
sort2(_a, _b);
return std::make_tuple(_a, _b);
}

/// \brief Sort three numbers, such that _a <= _b <= _c
/// \param[out] _a the first number
/// \param[out] _b the second number
/// \param[out] _c the third number
/// \return a tuple with the numbers sorted
std::tuple<float, float, float> Sort3(float _a, float _b, float _c)
{
sort3(_a, _b, _c);
return std::make_tuple(_a, _b, _c);
}

void defineMathHelpers(py::module &m)
{
using Class = Helpers;

m.def("clamp", &ignition::math::clamp<float>, "Simple clamping function")
.def("clamp", &ignition::math::clamp<int>, "Simple clamping function")
.def("isnan",
py::overload_cast<float>(&ignition::math::isnan),
"Check if a float is NaN")
.def("fixnan",
py::overload_cast<float>(&ignition::math::fixnan),
"Fix a nan value.")
.def("is_even",
py::overload_cast<int>(&ignition::math::isEven),
"Check if parameter is even.")
.def("is_odd",
py::overload_cast<int>(&ignition::math::isOdd),
"Check if parameter is odd.")
.def("sgn",
&ignition::math::sgn<float>,
"Returns 0 for zero values, -1 for negative values and +1 for positive"
" values.")
.def("signum",
&ignition::math::signum<float>,
"Returns 0 for zero values, -1 for negative values and "
"+1 for positive values.")
.def("mean", &ignition::math::mean<float>, "Get mean of vector of values")
.def("variance",
&ignition::math::variance<float>,
"Get variance of vector of values")
.def("max",
&ignition::math::max<float>,
"Get the maximum value of vector of values")
.def("max",
&ignition::math::max<int>,
"Get the maximum value of vector of values")
.def("min",
&ignition::math::min<float>,
"Get the minimum value of vector of values")
.def("min",
&ignition::math::min<int>,
"Get the minimum value of vector of values")
.def("equal",
&ignition::math::equal<float>,
"check if two values are equal, within a tolerance")
.def("less_or_near_equal",
&ignition::math::lessOrNearEqual<float>,
"Inequality test, within a tolerance")
.def("greater_or_near_equal",
&ignition::math::greaterOrNearEqual<float>,
"Inequality test, within a tolerance")
.def("precision",
&ignition::math::precision<float>,
"Get value at a specified precision")
.def("sort2",
&Sort2,
"Sort two numbers, such that _a <= _b")
.def("sort3",
&Sort3,
"Sort three numbers, such that _a <= _b <= _c")
.def("is_power_of_two",
&ignition::math::isPowerOfTwo,
"Is this a power of 2?")
.def("round_up_power_of_two",
&ignition::math::roundUpPowerOfTwo,
"Get the smallest power of two that is greater or equal to a given "
"value")
.def("round_up_multiple",
&ignition::math::roundUpMultiple,
"Round a number up to the nearest multiple")
.def("parse_int",
&ignition::math::parseInt,
"parse string into an integer")
.def("parse_float",
&ignition::math::parseFloat,
"parse string into an float")
.def("ign_sphere_volume",
&SphereVolume,
"Compute sphere volume")
.def("ign_cylinder_volume",
&CylinderVolume,
"Compute cylinder volume")
.def("ign_box_volume",
&BoxVolume,
"Compute box volume")
.def("ign_box_volume_v",
&BoxVolumeV,
"Compute box volume from vector");
py::class_<Class>(m,
"Helpers",
py::buffer_protocol(),
py::dynamic_attr())
.def_readonly_static("IGNZEROSIZET", &IGN_ZERO_SIZE_T, "IGN_PI")
.def_readonly_static("IGN_ONE_SIZE_T", &IGN_ONE_SIZE_T)
.def_readonly_static("IGN_TWO_SIZE_T", &IGN_TWO_SIZE_T)
.def_readonly_static("IGN_THREE_SIZE_T", &IGN_THREE_SIZE_T)
.def_readonly_static("IGN_FOUR_SIZE_T", &IGN_FOUR_SIZE_T)
.def_readonly_static("IGN_FIVE_SIZE_T", &IGN_FIVE_SIZE_T)
.def_readonly_static("IGN_SIX_SIZE_T", &IGN_SIX_SIZE_T)
.def_readonly_static("IGN_SEVEN_SIZE_T", &IGN_SEVEN_SIZE_T)
.def_readonly_static("IGN_EIGHT_SIZE_T", &IGN_EIGHT_SIZE_T)
.def_readonly_static("IGN_NINE_SIZE_T", &IGN_NINE_SIZE_T)
.def_readonly_static("MAX_D", &MAX_D)
.def_readonly_static("MIN_D", &MIN_D)
.def_readonly_static("LOW_D", &LOW_D)
.def_readonly_static("INF_D", &INF_D)
.def_readonly_static("NAN_D", &NAN_D)
.def_readonly_static("MAX_F", &MAX_F)
.def_readonly_static("MIN_F", &MIN_F)
.def_readonly_static("LOW_F", &LOW_F)
.def_readonly_static("INF_F", &INF_F)
.def_readonly_static("NAN_F", &NAN_F)
.def_readonly_static("MAX_UI16", &MAX_UI16)
.def_readonly_static("MIN_UI16", &MIN_UI16)
.def_readonly_static("LOW_UI16", &LOW_UI16)
.def_readonly_static("INF_UI16", &INF_UI16)
.def_readonly_static("MAX_I16", &MAX_I16)
.def_readonly_static("MIN_I16", &MIN_I16)
.def_readonly_static("LOW_I16", &LOW_I16)
.def_readonly_static("INF_I16", &INF_I16)
.def_readonly_static("MAX_UI32", &MAX_UI32)
.def_readonly_static("MIN_UI32", &MIN_UI32)
.def_readonly_static("LOW_UI32", &LOW_UI32)
.def_readonly_static("INF_UI32", &INF_UI32)
.def_readonly_static("MAX_I32", &MAX_I32)
.def_readonly_static("MIN_I32", &MIN_I32)
.def_readonly_static("LOW_I32", &LOW_I32)
.def_readonly_static("INF_I32", &INF_I32)
.def_readonly_static("MAX_UI64", &MAX_UI64)
.def_readonly_static("MIN_UI64", &MIN_UI64)
.def_readonly_static("LOW_UI64", &LOW_UI64)
.def_readonly_static("INF_UI64", &INF_UI64)
.def_readonly_static("MAX_I64", &MAX_I64)
.def_readonly_static("MIN_I64", &MIN_I64)
.def_readonly_static("LOW_I64", &LOW_I64)
.def_readonly_static("INF_I64", &INF_I64)
.def_readonly_static("NAN_I", &NAN_I);
}
} // namespace python
} // namespace gazebo
} // namespace ignition
40 changes: 40 additions & 0 deletions src/python_pybind11/src/Helpers.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
/*
* 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__HELPERS_HH_
#define IGNITION_MATH_PYTHON__HELPERS_HH_

#include <pybind11/pybind11.h>

namespace py = pybind11;

namespace ignition
{
namespace math
{
namespace python
{
/// Define a py::bind11 wrapper for an ignition::math::Helpers
/**
* \param[in] module a py::bind11 module to add the definition to
*/
void defineMathHelpers(py::module &m);
} // namespace python
} // namespace gazebo
} // namespace ignition

#endif // IGNITION_MATH_PYTHON__HELPERS_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 @@ -15,6 +15,7 @@
#include <pybind11/pybind11.h>

#include "Angle.hh"
#include "Helpers.hh"
#include "Rand.hh"
#include "Vector2.hh"
#include "Vector3.hh"
Expand All @@ -28,6 +29,8 @@ PYBIND11_MODULE(math, m)

ignition::math::python::defineMathAngle(m, "Angle");

ignition::math::python::defineMathHelpers(m);

ignition::math::python::defineMathRand(m, "Rand");

ignition::math::python::defineMathVector2<double>(m, "Vector2d");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,13 @@
import math
import unittest

from ignition.math import (ign_box_volume, ign_box_volume_v, ign_cylinder_volume,
IGN_PI, ign_sphere_volume, NAN_I, Vector3d, equal, fixnan,
from ignition.math import (Helpers, ign_box_volume, ign_box_volume_v, ign_cylinder_volume,
ign_sphere_volume, Vector3d, equal, fixnan,
greater_or_near_equal, is_even, is_odd, is_power_of_two, isnan,
less_or_near_equal, max, mean, min,
parse_float, parse_int, precision, round_up_multiple,
round_up_power_of_two, signum, sort2, sort3, variance)


class TestHelpers(unittest.TestCase):

def test_helpers(self):
Expand All @@ -32,9 +31,9 @@ def test_helpers(self):
self.assertEqual(0, parse_int(' '))
self.assertEqual(23, parse_int('23ab67'))

self.assertEqual(NAN_I, parse_int(''))
self.assertEqual(NAN_I, parse_int('?'))
self.assertEqual(NAN_I, parse_int('ab23ab67'))
self.assertEqual(Helpers.NAN_I, parse_int(''))
self.assertEqual(Helpers.NAN_I, parse_int('?'))
self.assertEqual(Helpers.NAN_I, parse_int('ab23ab67'))

self.assertEqual(12.345, parse_float('12.345'))
self.assertEqual(-12.345, parse_float('-12.345'))
Expand Down Expand Up @@ -243,16 +242,33 @@ def test_sort(self):
self.assertLess(b, c)

def test_volume(self):
self.assertEqual(ign_sphere_volume(1.0), 4.0*IGN_PI*math.pow(1, 3)/3.0)
self.assertEqual(ign_sphere_volume(0.1), 4.0*IGN_PI*math.pow(.1, 3)/3.0)
self.assertEqual(ign_sphere_volume(-1.1), 4.0*IGN_PI*math.pow(-1.1, 3)/3.0)

self.assertEqual(ign_cylinder_volume(0.5, 2.0), 2 * IGN_PI * math.pow(.5, 2))
self.assertEqual(ign_cylinder_volume(1, -1), -1 * IGN_PI * math.pow(1, 2))
self.assertAlmostEqual(
ign_sphere_volume(1.0),
4.0*math.pi*math.pow(1, 3)/3.0,
6)
self.assertAlmostEqual(
ign_sphere_volume(0.1),
4.0*math.pi*math.pow(.1, 3)/3.0,
6)
self.assertAlmostEqual(
ign_sphere_volume(-1.1),
4.0*math.pi*math.pow(-1.1, 3)/3.0,
6)

self.assertAlmostEqual(
ign_cylinder_volume(0.5, 2.0),
2 * math.pi * math.pow(.5, 2),
6)
self.assertAlmostEqual(
ign_cylinder_volume(1, -1),
-1 * math.pi * math.pow(1, 2),
6)

self.assertEqual(ign_box_volume(1, 2, 3), 1 * 2 * 3)
self.assertEqual(ign_box_volume(.1, .2, .3),
ign_box_volume_v(Vector3d(0.1, 0.2, 0.3)))
self.assertAlmostEqual(
ign_box_volume(.1, .2, .3),
ign_box_volume_v(Vector3d(0.1, 0.2, 0.3)),
6)

def test_round_up_multiple(self):
self.assertEqual(0, round_up_multiple(0, 0))
Expand Down