From 20ef6b800258a937c6343d514ac484cbf9cc3b8d Mon Sep 17 00:00:00 2001 From: gokulp01 Date: Mon, 6 Jan 2025 23:05:30 -0600 Subject: [PATCH 1/6] Update CMakeLists for VolumetricGridLookupField Python bindings Signed-off-by: gokulp01 --- src/python_pybind11/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/python_pybind11/CMakeLists.txt b/src/python_pybind11/CMakeLists.txt index 4e7d5a40..efd7d9d4 100644 --- a/src/python_pybind11/CMakeLists.txt +++ b/src/python_pybind11/CMakeLists.txt @@ -39,6 +39,7 @@ pybind11_add_module(${BINDINGS_MODULE_NAME} MODULE src/Frustum.cc src/GaussMarkovProcess.cc src/Helpers.cc + src/InterpolationPoint.cc src/Interval.cc src/Kmeans.cc src/Line2.cc @@ -70,6 +71,7 @@ pybind11_add_module(${BINDINGS_MODULE_NAME} MODULE src/Vector3.cc src/Vector4.cc src/Vector3Stats.cc + src/VolumetricGridLookupField.cc ) target_link_libraries(${BINDINGS_MODULE_NAME} PRIVATE From b3dbeb81ee8677a515e864b09bb110c0306072d2 Mon Sep 17 00:00:00 2001 From: gokulp01 Date: Mon, 6 Jan 2025 23:05:35 -0600 Subject: [PATCH 2/6] Add pybindings for InterpolationPoint Signed-off-by: gokulp01 --- src/python_pybind11/src/InterpolationPoint.cc | 32 ++++++++ src/python_pybind11/src/InterpolationPoint.hh | 80 +++++++++++++++++++ 2 files changed, 112 insertions(+) create mode 100644 src/python_pybind11/src/InterpolationPoint.cc create mode 100644 src/python_pybind11/src/InterpolationPoint.hh diff --git a/src/python_pybind11/src/InterpolationPoint.cc b/src/python_pybind11/src/InterpolationPoint.cc new file mode 100644 index 00000000..3edd966f --- /dev/null +++ b/src/python_pybind11/src/InterpolationPoint.cc @@ -0,0 +1,32 @@ +/* + * Copyright (C) 2025 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 "InterpolationPoint.hh" +#include + +namespace gz { +namespace math { +namespace python { + +void defineMathInterpolationPoint3D(py::module &m, const std::string &typestr) { + helpDefineMathInterpolationPoint3D(m, typestr + "d"); + helpDefineMathInterpolationPoint3D(m, typestr + "f"); +} + +} // namespace python +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/InterpolationPoint.hh b/src/python_pybind11/src/InterpolationPoint.hh new file mode 100644 index 00000000..b2f7912a --- /dev/null +++ b/src/python_pybind11/src/InterpolationPoint.hh @@ -0,0 +1,80 @@ +/* + * Copyright (C) 2025 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 GZ_MATH_PYTHON__INTERPOLATION_POINT_HH_ +#define GZ_MATH_PYTHON__INTERPOLATION_POINT_HH_ + +#include +#include + +#include +#include +#include + +#include +#include + +namespace py = pybind11; +using namespace pybind11::literals; + +namespace gz { +namespace math { +namespace python { +/// define a pybind11 wrapper for gz::math::InterpolationPoint3D +/** + * \param[in] module a pybind11 module to add the definition to + */ +template +void helpDefineMathInterpolationPoint3D(py::module &m, + const std::string &typestr) { + using Class = gz::math::InterpolationPoint3D; + using Vector3Type = gz::math::Vector3; + + auto toString = [](const Class &si) { + std::stringstream stream; + stream << "InterpolationPoint3D(position=" << si.position; + if (si.index.has_value()) { + stream << ", index=" << si.index.value(); + } else { + stream << ", index=None"; + } + stream << ")"; + return stream.str(); + }; + + std::string pyclass_name = typestr; + py::class_(m, pyclass_name.c_str(), py::dynamic_attr()) + .def(py::init<>()) + .def(py::init>(), + py::arg("position"), py::arg("index") = std::nullopt) + .def_readwrite("position", &Class::position) + .def_readwrite("index", &Class::index) + .def("__str__", toString) + .def("__repr__", toString); +} + +/// define a pybind11 wrapper for gz::math::InterpolationPoint3D +/** + * \param[in] module a pybind11 module to add the definition to + */ +void defineMathInterpolationPoint3D(py::module &m, const std::string &typestr); + +} // namespace python +} // namespace math +} // namespace gz + +#endif // GZ_MATH_PYTHON__INTERPOLATION_POINT_HH_ From e5e45cc2e41e57d69dacceb68b69ab445e145b00 Mon Sep 17 00:00:00 2001 From: gokulp01 Date: Mon, 6 Jan 2025 23:05:41 -0600 Subject: [PATCH 3/6] Add pybindings for VolumetricGridLookupField Signed-off-by: gokulp01 --- .../src/VolumetricGridLookupField.cc | 35 +++++++ .../src/VolumetricGridLookupField.hh | 93 +++++++++++++++++++ src/python_pybind11/src/_gz_math_pybind11.cc | 37 ++++---- 3 files changed, 145 insertions(+), 20 deletions(-) create mode 100644 src/python_pybind11/src/VolumetricGridLookupField.cc create mode 100644 src/python_pybind11/src/VolumetricGridLookupField.hh diff --git a/src/python_pybind11/src/VolumetricGridLookupField.cc b/src/python_pybind11/src/VolumetricGridLookupField.cc new file mode 100644 index 00000000..687382e1 --- /dev/null +++ b/src/python_pybind11/src/VolumetricGridLookupField.cc @@ -0,0 +1,35 @@ +/* + * Copyright (C) 2025 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 "VolumetricGridLookupField.hh" +#include + +namespace gz { +namespace math { +namespace python { + +void defineMathVolumetricGridLookupField(py::module &m, + const std::string &typestr) { + // Define for double type + helpDefineMathVolumetricGridLookupField(m, typestr + "d"); + // Define for float type + helpDefineMathVolumetricGridLookupField(m, typestr + "f"); +} + +} // namespace python +} // namespace math +} // namespace gz diff --git a/src/python_pybind11/src/VolumetricGridLookupField.hh b/src/python_pybind11/src/VolumetricGridLookupField.hh new file mode 100644 index 00000000..9ab71ae6 --- /dev/null +++ b/src/python_pybind11/src/VolumetricGridLookupField.hh @@ -0,0 +1,93 @@ +/* + * Copyright (C) 2025 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 GZ_MATH_PYTHON__VOLUMETRIC_GRID_LOOKUP_FIELD_HH_ +#define GZ_MATH_PYTHON__VOLUMETRIC_GRID_LOOKUP_FIELD_HH_ + +#include +#include +#include + +#include +#include +#include + +#include +#include +#include + +namespace py = pybind11; +using namespace pybind11::literals; + +namespace gz { +namespace math { +namespace python { +/// define a pybind11 wrapper for a gz::math::VolumetricGridLookupField +/** + * \param[in] module a pybind11 module to add the definition to + */ +template +void helpDefineMathVolumetricGridLookupField(py::module &m, + const std::string &typestr) { + using Class = gz::math::VolumetricGridLookupField; + using Vector3Type = gz::math::Vector3; + + auto toString = [](const Class &si) { + std::stringstream stream; + stream << "VolumetricGridLookupField"; + 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 &, const std::vector &>()) + .def( + "get_interpolators", + [](const Class &self, const Vector3Type &pt, double xTol, double yTol, + double zTol) { + return self.GetInterpolators(pt, xTol, yTol, zTol); + }, + "Get interpolators for a given point", py::arg("point"), + py::arg("x_tol") = 1e-6, py::arg("y_tol") = 1e-6, + py::arg("z_tol") = 1e-6) + .def( + "estimate_value_using_trilinear", + [](const Class &self, const Vector3Type &pt, + const std::vector &values, double defaultVal = 0.0) { + return self.EstimateValueUsingTrilinear(pt, values, defaultVal); + }, + "Estimate value using trilinear interpolation", py::arg("point"), + py::arg("values"), py::arg("default") = 0.0) + .def("bounds", &Class::Bounds, "Get the bounds of the grid field") + .def("__str__", toString) + .def("__repr__", toString); +} + +/// Define a pybind11 wrapper for a gz::math::VolumetricGridLookupField +/** + * \param[in] module a pybind11 module to add the definition to + */ +void defineMathVolumetricGridLookupField(py::module &m, + const std::string &typestr); + +} // namespace python +} // namespace math +} // namespace gz + +#endif // GZ_MATH_PYTHON__VOLUMETRIC_GRID_LOOKUP_FIELD_HH_ diff --git a/src/python_pybind11/src/_gz_math_pybind11.cc b/src/python_pybind11/src/_gz_math_pybind11.cc index 51f4f627..7fb0309d 100644 --- a/src/python_pybind11/src/_gz_math_pybind11.cc +++ b/src/python_pybind11/src/_gz_math_pybind11.cc @@ -64,10 +64,11 @@ #include "Vector3Stats.hh" #include "Vector4.hh" +#include "InterpolationPoint.hh" +#include "VolumetricGridLookupField.hh" namespace py = pybind11; -PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) -{ +PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) { m.doc() = "Gazebo Math Python Library."; gz::math::python::defineMathAngle(m, "Angle"); @@ -78,14 +79,11 @@ PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) gz::math::python::defineMathColor(m, "Color"); - gz::math::python::defineMathDiffDriveOdometry( - m, "DiffDriveOdometry"); + gz::math::python::defineMathDiffDriveOdometry(m, "DiffDriveOdometry"); - gz::math::python::defineMathEllipsoid( - m, "Ellipsoid"); + gz::math::python::defineMathEllipsoid(m, "Ellipsoid"); - gz::math::python::defineMathGaussMarkovProcess( - m, "GaussMarkovProcess"); + gz::math::python::defineMathGaussMarkovProcess(m, "GaussMarkovProcess"); gz::math::python::defineMathHelpers(m); @@ -106,10 +104,9 @@ PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) gz::math::python::defineMathSignalVariance(m, "SignalVariance"); gz::math::python::defineMathSignalMaximum(m, "SignalMaximum"); gz::math::python::defineMathSignalMinimum(m, "SignalMinimum"); - gz::math::python::defineMathSignalMaxAbsoluteValue( - m, "SignalMaxAbsoluteValue"); - gz::math::python::defineMathSignalRootMeanSquare( - m, "SignalRootMeanSquare"); + gz::math::python::defineMathSignalMaxAbsoluteValue(m, + "SignalMaxAbsoluteValue"); + gz::math::python::defineMathSignalRootMeanSquare(m, "SignalRootMeanSquare"); gz::math::python::defineMathSignalMean(m, "SignalMean"); gz::math::python::defineMathRotationSpline(m, "RotationSpline"); @@ -118,8 +115,7 @@ PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) gz::math::python::defineMathSemanticVersion(m, "SemanticVersion"); - gz::math::python::defineMathSphericalCoordinates( - m, "SphericalCoordinates"); + gz::math::python::defineMathSphericalCoordinates(m, "SphericalCoordinates"); gz::math::python::defineMathSpline(m, "Spline"); @@ -182,15 +178,16 @@ PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) gz::math::python::defineMathBiQuad(m, "BiQuad"); - gz::math::python::defineMathBiQuadVector3( - m, "BiQuadVector3"); + gz::math::python::defineMathBiQuadVector3(m, "BiQuadVector3"); gz::math::python::defineMathOnePole(m, "OnePole"); - gz::math::python::defineMathOnePoleQuaternion( - m, "OnePoleQuaternion"); - gz::math::python::defineMathOnePoleVector3( - m, "OnePoleVector3"); + gz::math::python::defineMathOnePoleQuaternion(m, "OnePoleQuaternion"); + gz::math::python::defineMathOnePoleVector3(m, "OnePoleVector3"); gz::math::python::defineMathCoordinateVector3(m, "CoordinateVector3"); + + gz::math::python::defineMathVolumetricGridLookupField( + m, "VolumetricGridLookupField"); + gz::math::python::defineMathInterpolationPoint3D(m, "InterpolationPoint3D"); } From 2a6cf3761eeaca1ef2438cfd06cae3b961cd550f Mon Sep 17 00:00:00 2001 From: gokulp01 Date: Mon, 6 Jan 2025 23:05:51 -0600 Subject: [PATCH 4/6] Add test for VolumetricGridLookupField pybindings Signed-off-by: gokulp01 --- .../test/VolumetricGridLookupField_TEST.py | 98 +++++++++++++++++++ 1 file changed, 98 insertions(+) create mode 100644 src/python_pybind11/test/VolumetricGridLookupField_TEST.py diff --git a/src/python_pybind11/test/VolumetricGridLookupField_TEST.py b/src/python_pybind11/test/VolumetricGridLookupField_TEST.py new file mode 100644 index 00000000..f9972100 --- /dev/null +++ b/src/python_pybind11/test/VolumetricGridLookupField_TEST.py @@ -0,0 +1,98 @@ +# 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. + +import unittest + +from gz.math8 import Vector3d, VolumetricGridLookupFieldd + + +class TestVolumetricGridLookupField(unittest.TestCase): + def test_interpolation_box_eight_points(self): + # Create cloud points as in the C++ test + cloud = [ + Vector3d(0, 0, 0), + Vector3d(0, 0, 1), + Vector3d(0, 1, 0), + Vector3d(0, 1, 1), + Vector3d(1, 0, 0), + Vector3d(1, 0, 1), + Vector3d(1, 1, 0), + Vector3d(1, 1, 1), + ] + + # Create lookup field + field = VolumetricGridLookupFieldd(cloud) + + # Test inside point (should return 8 interpolators??) + pos = Vector3d(0.5, 0.5, 0.5) + interpolators = field.get_interpolators(pos) + self.assertEqual(len(interpolators), 8) + + # Test outside point (should return 0 interpolators) + pos = Vector3d(-0.5, -0.5, -0.5) + interpolators = field.get_interpolators(pos) + self.assertEqual(len(interpolators), 0) + + # Test point on plane (should return 4 interpolators) + pos = Vector3d(0.5, 0.5, 0) + interpolators = field.get_interpolators(pos) + self.assertEqual(len(interpolators), 4) + + # Test point on edge (should return 2 interpolators) + pos = Vector3d(0.5, 0, 0) + interpolators = field.get_interpolators(pos) + self.assertEqual(len(interpolators), 2) + + def test_trilinear_interpolation(self): + # Create cloud points + cloud = [ + Vector3d(0, 0, 0), + Vector3d(0, 0, 1), + Vector3d(0, 1, 0), + Vector3d(0, 1, 1), + Vector3d(1, 0, 0), + Vector3d(1, 0, 1), + Vector3d(1, 1, 0), + Vector3d(1, 1, 1), + ] + + values = [0, 0, 0, 0, 1, 1, 1, 1] + field = VolumetricGridLookupFieldd(cloud) + + # Test inside point + pos = Vector3d(0.5, 0.5, 0.5) + value = field.estimate_value_using_trilinear(pos, values) + self.assertIsNotNone(value) + self.assertAlmostEqual(value, 0.5, places=3) + + # Test outside point + pos = Vector3d(-0.5, -0.5, -0.5) + value = field.estimate_value_using_trilinear(pos, values) + self.assertIsNone(value) + + # Test point on plane + pos = Vector3d(0, 0.5, 0.5) + value = field.estimate_value_using_trilinear(pos, values) + self.assertIsNotNone(value) + self.assertAlmostEqual(value, 0.0, places=3) + + # Test point on vertex + pos = Vector3d(0, 0, 0) + value = field.estimate_value_using_trilinear(pos, values) + self.assertIsNotNone(value) + self.assertAlmostEqual(value, 0.0, places=3) + + +if __name__ == "__main__": + unittest.main() From 4f993ce11e3d6d28fdc6662ee5225848e439cce2 Mon Sep 17 00:00:00 2001 From: gokulp01 Date: Tue, 14 Jan 2025 18:47:44 -0600 Subject: [PATCH 5/6] Address review suggestions Signed-off-by: gokulp01 --- src/python_pybind11/src/InterpolationPoint.hh | 1 + src/python_pybind11/src/_gz_math_pybind11.cc | 36 ++++++++++++------- .../test/VolumetricGridLookupField_TEST.py | 2 +- 3 files changed, 25 insertions(+), 14 deletions(-) diff --git a/src/python_pybind11/src/InterpolationPoint.hh b/src/python_pybind11/src/InterpolationPoint.hh index b2f7912a..97e0b413 100644 --- a/src/python_pybind11/src/InterpolationPoint.hh +++ b/src/python_pybind11/src/InterpolationPoint.hh @@ -27,6 +27,7 @@ #include #include +#include namespace py = pybind11; using namespace pybind11::literals; diff --git a/src/python_pybind11/src/_gz_math_pybind11.cc b/src/python_pybind11/src/_gz_math_pybind11.cc index 7fb0309d..79de6308 100644 --- a/src/python_pybind11/src/_gz_math_pybind11.cc +++ b/src/python_pybind11/src/_gz_math_pybind11.cc @@ -28,6 +28,7 @@ #include "Frustum.hh" #include "GaussMarkovProcess.hh" #include "Helpers.hh" +#include "InterpolationPoint.hh" #include "Inertial.hh" #include "Interval.hh" #include "Kmeans.hh" @@ -63,12 +64,12 @@ #include "Vector3.hh" #include "Vector3Stats.hh" #include "Vector4.hh" - -#include "InterpolationPoint.hh" #include "VolumetricGridLookupField.hh" + namespace py = pybind11; -PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) { +PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) +{ m.doc() = "Gazebo Math Python Library."; gz::math::python::defineMathAngle(m, "Angle"); @@ -79,11 +80,14 @@ PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) { gz::math::python::defineMathColor(m, "Color"); - gz::math::python::defineMathDiffDriveOdometry(m, "DiffDriveOdometry"); + gz::math::python::defineMathDiffDriveOdometry( + m, "DiffDriveOdometry"); - gz::math::python::defineMathEllipsoid(m, "Ellipsoid"); + gz::math::python::defineMathEllipsoid( + m, "Ellipsoid"); - gz::math::python::defineMathGaussMarkovProcess(m, "GaussMarkovProcess"); + gz::math::python::defineMathGaussMarkovProcess( + m, "GaussMarkovProcess"); gz::math::python::defineMathHelpers(m); @@ -104,9 +108,10 @@ PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) { gz::math::python::defineMathSignalVariance(m, "SignalVariance"); gz::math::python::defineMathSignalMaximum(m, "SignalMaximum"); gz::math::python::defineMathSignalMinimum(m, "SignalMinimum"); - gz::math::python::defineMathSignalMaxAbsoluteValue(m, - "SignalMaxAbsoluteValue"); - gz::math::python::defineMathSignalRootMeanSquare(m, "SignalRootMeanSquare"); + gz::math::python::defineMathSignalMaxAbsoluteValue( + m, "SignalMaxAbsoluteValue"); + gz::math::python::defineMathSignalRootMeanSquare( + m, "SignalRootMeanSquare"); gz::math::python::defineMathSignalMean(m, "SignalMean"); gz::math::python::defineMathRotationSpline(m, "RotationSpline"); @@ -115,7 +120,8 @@ PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) { gz::math::python::defineMathSemanticVersion(m, "SemanticVersion"); - gz::math::python::defineMathSphericalCoordinates(m, "SphericalCoordinates"); + gz::math::python::defineMathSphericalCoordinates( + m, "SphericalCoordinates"); gz::math::python::defineMathSpline(m, "Spline"); @@ -178,16 +184,20 @@ PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) { gz::math::python::defineMathBiQuad(m, "BiQuad"); - gz::math::python::defineMathBiQuadVector3(m, "BiQuadVector3"); + gz::math::python::defineMathBiQuadVector3( + m, "BiQuadVector3"); gz::math::python::defineMathOnePole(m, "OnePole"); - gz::math::python::defineMathOnePoleQuaternion(m, "OnePoleQuaternion"); - gz::math::python::defineMathOnePoleVector3(m, "OnePoleVector3"); + gz::math::python::defineMathOnePoleQuaternion( + m, "OnePoleQuaternion"); + gz::math::python::defineMathOnePoleVector3( + m, "OnePoleVector3"); gz::math::python::defineMathCoordinateVector3(m, "CoordinateVector3"); gz::math::python::defineMathVolumetricGridLookupField( m, "VolumetricGridLookupField"); + gz::math::python::defineMathInterpolationPoint3D(m, "InterpolationPoint3D"); } diff --git a/src/python_pybind11/test/VolumetricGridLookupField_TEST.py b/src/python_pybind11/test/VolumetricGridLookupField_TEST.py index f9972100..33b5f113 100644 --- a/src/python_pybind11/test/VolumetricGridLookupField_TEST.py +++ b/src/python_pybind11/test/VolumetricGridLookupField_TEST.py @@ -1,4 +1,4 @@ -# Copyright (C) 2021 Open Source Robotics Foundation +# Copyright (C) 2025 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. From 43fcfe02c154f7312b3e4c411f5e27c40bea8398 Mon Sep 17 00:00:00 2001 From: Gokul <43350089+gokulp01@users.noreply.github.com> Date: Wed, 15 Jan 2025 09:01:37 -0600 Subject: [PATCH 6/6] Update src/python_pybind11/src/VolumetricGridLookupField.hh MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Gokul <43350089+gokulp01@users.noreply.github.com> --- src/python_pybind11/src/VolumetricGridLookupField.hh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/python_pybind11/src/VolumetricGridLookupField.hh b/src/python_pybind11/src/VolumetricGridLookupField.hh index 9ab71ae6..b3dc377f 100644 --- a/src/python_pybind11/src/VolumetricGridLookupField.hh +++ b/src/python_pybind11/src/VolumetricGridLookupField.hh @@ -48,7 +48,7 @@ void helpDefineMathVolumetricGridLookupField(py::module &m, auto toString = [](const Class &si) { std::stringstream stream; - stream << "VolumetricGridLookupField"; + stream << si; return stream.str(); };