Skip to content

Commit

Permalink
Added Material pybind11 interface (#340)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández <[email protected]>

Co-authored-by: Louise Poubel <[email protected]>
  • Loading branch information
ahcorde and chapulina authored Dec 28, 2021
1 parent bb43b30 commit a0be19f
Show file tree
Hide file tree
Showing 6 changed files with 170 additions and 16 deletions.
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)
GaussMarkovProcess_TEST
Inertial_TEST
MassMatrix3_TEST
Material_TEST
Matrix4_TEST
OrientedBox_TEST
PID_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 @@ -18,6 +18,7 @@ if (${pybind11_FOUND})
src/Color.cc
src/Helpers.cc
src/Kmeans.cc
src/Material.cc
src/Rand.cc
src/RollingMean.cc
src/SemanticVersion.cc
Expand Down Expand Up @@ -82,6 +83,7 @@ if (${pybind11_FOUND})
Kmeans_TEST
Line2_TEST
Line3_TEST
Material_TEST
Matrix3_TEST
MovingWindowFilter_TEST
Pose3_TEST
Expand Down
106 changes: 106 additions & 0 deletions src/python_pybind11/src/Material.cc
Original file line number Diff line number Diff line change
@@ -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.
*
*/
#include <limits>
#include <map>
#include <string>

#include "Material.hh"
#include <ignition/math/Material.hh>
#include <ignition/math/MaterialType.hh>

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

namespace ignition
{
namespace math
{
namespace python
{
void defineMathMaterial(py::module &m, const std::string &typestr)
{

py::bind_map<std::map<
ignition::math::MaterialType, ignition::math::Material>>
(m, "MaterialMap");

using Class = ignition::math::Material;
std::string pyclass_name = typestr;
py::class_<Class> (m,
pyclass_name.c_str(),
py::buffer_protocol(),
py::dynamic_attr())
.def(py::init<>())
.def(py::init<const ignition::math::MaterialType>())
.def(py::init<const std::string&>())
.def(py::init<const double>())
.def(py::init<const Class&>())
.def(py::self != py::self)
.def(py::self == py::self)
.def("predefined",
&Class::Predefined,
"Get all the built-in materials.")
.def("set_to_nearest_density",
&Class::SetToNearestDensity,
py::arg("_value") = 0,
py::arg("_epsilon") = std::numeric_limits<double>::max(),
"Set this Material to the built-in Material with "
"the nearest density value within _epsilon. If a built-in material "
"could not be found, then this Material is not changed.")
.def("type",
&Class::Type,
"Set the material's type. This will only set the type value. "
"Other properties, such as density, will not be changed.")
.def("set_type",
&Class::SetType,
"Set the material's type. This will only set the type value. "
"Other properties, such as density, will not be changed.")
.def("name",
&Class::Name,
"Get the name of the material. This will match the enum type "
"names used in ::MaterialType, but in lowercase, if a built-in "
"material is used.")
.def("set_name",
&Class::SetName,
"Set the name of the material.")
.def("set_density",
&Class::SetDensity,
"Set the name of the material.")
.def("density", &Class::Density,
"Set the density value of the material in kg/m^3.");

py::enum_<ignition::math::MaterialType>(m, "MaterialType")
.value("STYROFOAM", ignition::math::MaterialType::STYROFOAM)
.value("PINE", ignition::math::MaterialType::PINE)
.value("WOOD", ignition::math::MaterialType::WOOD)
.value("OAK", ignition::math::MaterialType::OAK)
.value("PLASTIC", ignition::math::MaterialType::PLASTIC)
.value("CONCRETE", ignition::math::MaterialType::CONCRETE)
.value("ALUMINUM", ignition::math::MaterialType::ALUMINUM)
.value("STEEL_ALLOY", ignition::math::MaterialType::STEEL_ALLOY)
.value("STEEL_STAINLESS", ignition::math::MaterialType::STEEL_STAINLESS)
.value("IRON", ignition::math::MaterialType::IRON)
.value("BRASS", ignition::math::MaterialType::BRASS)
.value("COPPER", ignition::math::MaterialType::COPPER)
.value("TUNGSTEN", ignition::math::MaterialType::TUNGSTEN)
.value("UNKNOWN_MATERIAL",
ignition::math::MaterialType::UNKNOWN_MATERIAL)
.export_values();
}
} // namespace python
} // namespace math
} // namespace ignition
42 changes: 42 additions & 0 deletions src/python_pybind11/src/Material.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
/*
* 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__MATERIAL_HH_
#define IGNITION_MATH_PYTHON__MATERIAL_HH_

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

namespace py = pybind11;

namespace ignition
{
namespace math
{
namespace python
{
/// Define a pybind11 wrapper for an ignition::math::Material
/**
* \param[in] module a pybind11 module to add the definition to
* \param[in] typestr name of the type used by Python
*/
void defineMathMaterial(py::module &m, const std::string &typestr);
} // namespace python
} // namespace math
} // namespace ignition

#endif // IGNITION_MATH_PYTHON__MATERIAL_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 @@ -21,6 +21,7 @@
#include "Kmeans.hh"
#include "Line2.hh"
#include "Line3.hh"
#include "Material.hh"
#include "Matrix3.hh"
#include "MovingWindowFilter.hh"
#include "Pose3.hh"
Expand Down Expand Up @@ -50,6 +51,8 @@ PYBIND11_MODULE(math, m)

ignition::math::python::defineMathKmeans(m, "Kmeans");

ignition::math::python::defineMathMaterial(m, "Material");

ignition::math::python::defineMathMovingWindowFilter<int>(
m, "MovingWindowFilteri");
ignition::math::python::defineMathMovingWindowFilter<double>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,32 +26,34 @@ def test_init(self):

# Make sure that the number of elements in the MaterialType enum matches
# the number of elements in the MaterialDensity::materials map.
self.assertEqual(ignition.math.MaterialType_UNKNOWN_MATERIAL, len(mats))
self.assertEqual(ignition.math.MaterialType.UNKNOWN_MATERIAL,
ignition.math.MaterialType(len(mats)))

# Iterate over each element in the enum. Check the that enum value
# matches the type value in the mats map.
for i in range(ignition.math.MaterialType_UNKNOWN_MATERIAL):
for i in range(ignition.math.MaterialType.UNKNOWN_MATERIAL):
# Get the type of the material for MaterialType i.
self.assertEqual(i, next(iter(mats.find(i)))[1].type())
self.assertEqual(ignition.math.MaterialType(i),
mats[ignition.math.MaterialType(i)].type())

# The name should not be empty
self.assertTrue(next(iter(mats.find(i)))[1].name())
self.assertTrue(mats[ignition.math.MaterialType(i)].name())

# The density should be less than the max double value and greater than
# zero.
self.assertLess(next(iter(mats.find(i)))[1].density(), sys.float_info.max)
self.assertGreater(next(iter(mats.find(i)))[1].density(), 0.0)
self.assertLess(mats[ignition.math.MaterialType(i)].density(), sys.float_info.max)
self.assertGreater(mats[ignition.math.MaterialType(i)].density(), 0.0)

malicious = ignition.math.Material(42)
malicious = ignition.math.Material(ignition.math.MaterialType(42))
self.assertEqual(-1.0, malicious.density())
self.assertEqual('', malicious.name())

byDensity = ignition.math.Material(42.2)
self.assertEqual(42.2, byDensity.density())
self.assertEqual(ignition.math.MaterialType_UNKNOWN_MATERIAL, byDensity.type())
self.assertEqual(ignition.math.MaterialType.UNKNOWN_MATERIAL, byDensity.type())

def test_comparison(self):
aluminum = ignition.math.Material(ignition.math.MaterialType_ALUMINUM)
aluminum = ignition.math.Material(ignition.math.MaterialType.ALUMINUM)

modified = ignition.math.Material(aluminum)
self.assertEqual(modified, aluminum)
Expand All @@ -62,14 +64,14 @@ def test_comparison(self):
modified = ignition.math.Material(aluminum)
self.assertEqual(modified, aluminum)

modified.set_type(ignition.math.MaterialType_PINE)
modified.set_type(ignition.math.MaterialType.PINE)
self.assertNotEqual(modified, aluminum)

def test_accessors(self):

mat = ignition.math.Material("Aluminum")
mat1 = ignition.math.Material("aluminum")
mat2 = ignition.math.Material(ignition.math.MaterialType_ALUMINUM)
mat2 = ignition.math.Material(ignition.math.MaterialType.ALUMINUM)
mat3 = ignition.math.Material(mat2)

self.assertAlmostEqual(2700.0, mat.density())
Expand All @@ -86,23 +88,23 @@ def test_accessors(self):

mat = ignition.math.Material("Notfoundium")
self.assertGreater(0.0, mat.density())
self.assertEqual(ignition.math.MaterialType_UNKNOWN_MATERIAL,
self.assertEqual(ignition.math.MaterialType.UNKNOWN_MATERIAL,
mat.type())
self.assertFalse(mat.name())

material = ignition.math.Material()
material.set_to_nearest_density(19300.0)
self.assertEqual(ignition.math.MaterialType_TUNGSTEN, material.type())
self.assertEqual(ignition.math.MaterialType.TUNGSTEN, material.type())
self.assertAlmostEqual(19300.0, material.density())

material = ignition.math.Material()
material.set_to_nearest_density(1001001.001, 1e-3)
self.assertEqual(ignition.math.MaterialType_UNKNOWN_MATERIAL,
self.assertEqual(ignition.math.MaterialType.UNKNOWN_MATERIAL,
material.type())
self.assertGreater(0.0, material.density())
material = ignition.math.Material()
material.set_to_nearest_density(1001001.001)
self.assertEqual(ignition.math.MaterialType_TUNGSTEN, material.type())
self.assertEqual(ignition.math.MaterialType.TUNGSTEN, material.type())
self.assertAlmostEqual(19300, material.density())


Expand Down

0 comments on commit a0be19f

Please sign in to comment.