Skip to content

Commit

Permalink
Added Kmeans pybind11 interface (#341)
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 76ffa87 commit bb43b30
Show file tree
Hide file tree
Showing 6 changed files with 110 additions and 5 deletions.
1 change: 0 additions & 1 deletion src/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,6 @@ if (PYTHONLIBS_FOUND)
Frustum_TEST
GaussMarkovProcess_TEST
Inertial_TEST
Kmeans_TEST
MassMatrix3_TEST
Material_TEST
Matrix4_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 @@ -17,6 +17,7 @@ if (${pybind11_FOUND})
src/Angle.cc
src/Color.cc
src/Helpers.cc
src/Kmeans.cc
src/Rand.cc
src/RollingMean.cc
src/SemanticVersion.cc
Expand Down Expand Up @@ -78,6 +79,7 @@ if (${pybind11_FOUND})
Color_TEST
Filter_TEST
Helpers_TEST
Kmeans_TEST
Line2_TEST
Line3_TEST
Matrix3_TEST
Expand Down
60 changes: 60 additions & 0 deletions src/python_pybind11/src/Kmeans.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
/*
* 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 <string>
#include <vector>

#include "Kmeans.hh"
#include <ignition/math/Kmeans.hh>
#include <pybind11/stl.h>

namespace ignition
{
namespace math
{
namespace python
{
void defineMathKmeans(py::module &m, const std::string &typestr)
{
using Class = ignition::math::Kmeans;
std::string pyclass_name = typestr;
py::class_<Class>(m,
pyclass_name.c_str(),
py::buffer_protocol(),
py::dynamic_attr())
.def(py::init<const std::vector<ignition::math::Vector3d>&>())
.def("observations",
py::overload_cast<const std::vector<ignition::math::Vector3d>&>
(&Class::Observations),
"Set the observations to cluster.")
.def("observations",
py::overload_cast<>(&Class::Observations, py::const_),
"Get the observations to cluster.")
.def("append_observations",
&Class::AppendObservations,
"Add observations to the cluster.")
.def("cluster",
[](Class &self, int k) {
std::vector<ignition::math::Vector3<double>> centroids;
std::vector<unsigned int> labels;
bool result = self.Cluster(k, centroids, labels);
return std::make_tuple(result, centroids, labels);
},
"Executes the k-means algorithm.");
}
} // namespace python
} // namespace math
} // namespace ignition
42 changes: 42 additions & 0 deletions src/python_pybind11/src/Kmeans.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__KMEANS_HH_
#define IGNITION_MATH_PYTHON__KMEANS_HH_

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

namespace py = pybind11;

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

#endif // IGNITION_MATH_PYTHON__KMEANS_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 @@ -18,6 +18,7 @@
#include "Color.hh"
#include "Filter.hh"
#include "Helpers.hh"
#include "Kmeans.hh"
#include "Line2.hh"
#include "Line3.hh"
#include "Matrix3.hh"
Expand Down Expand Up @@ -47,6 +48,8 @@ PYBIND11_MODULE(math, m)

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

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

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 @@ -15,7 +15,6 @@
import unittest
from ignition.math import Kmeans
from ignition.math import Vector3d
from ignition.math import vector_vector3d


class TestKmeans(unittest.TestCase):
Expand Down Expand Up @@ -128,13 +127,13 @@ def test_kmeans_append(self):

kmeans.append_observations(obs2)

obs_copy = vector_vector3d(kmeans.observations())
obs_copy = kmeans.observations()

for i in range(obs_copy.size()):
for i in range(len(obs_copy)):
self.assertEqual(obs_total[i], obs_copy[i])

# Append an empty vector.
emptyVector = vector_vector3d()
emptyVector = []
self.assertFalse(kmeans.append_observations(emptyVector))


Expand Down

0 comments on commit bb43b30

Please sign in to comment.