Skip to content

Commit

Permalink
Adding Kmeans and Vector3Stats python interface and tests
Browse files Browse the repository at this point in the history
Signed-off-by: Marcos Wagner <[email protected]>
  • Loading branch information
WagnerMarcos committed Aug 31, 2021
1 parent 3ea6229 commit b4531e2
Show file tree
Hide file tree
Showing 6 changed files with 436 additions and 0 deletions.
2 changes: 2 additions & 0 deletions src/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -70,13 +70,15 @@ if (PYTHONLIBS_FOUND)
set(python_tests
Angle_TEST
GaussMarkovProcess_TEST
Kmeans_TEST
Line2_TEST
Line3_TEST
python_TEST
Rand_TEST
SignalStats_TEST
Vector2_TEST
Vector3_TEST
Vector3Stats_TEST
Vector4_TEST
Temperature_TEST
)
Expand Down
66 changes: 66 additions & 0 deletions src/python/Kmeans.i
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
/*
* 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.
*
*/

%module kmeans
%{
#include <ignition/math/Helpers.hh>
#include <ignition/math/Vector3.hh>
#include <ignition/math/Kmeans.hh>
%}

%include "std_vector.i"
%template(vector_vector3d) std::vector<ignition::math::Vector3<double>>;
%template(vector_uint) std::vector<unsigned int>;

%inline %{
struct ClusterOutput {
bool result;
std::vector<ignition::math::Vector3<double>> centroids;
std::vector<unsigned int> labels;
};
%}

namespace ignition
{
namespace math
{
class Kmeans
{
%rename("%(undercase)s", %$isfunction, %$ismember, %$not %$isconstructor) "";
public: explicit Kmeans(const std::vector<Vector3<double>> &_obs);
public: virtual ~Kmeans();
public: std::vector<Vector3<double>> Observations() const;
public: bool Observations(const std::vector<Vector3<double>> &_obs);
public: bool AppendObservations(const std::vector<Vector3<double>> &_obs);

%pythoncode %{
def cluster(self, _k):
cluster_output = self._cluster(_k)
return [cluster_output.result,
vector_vector3d(cluster_output.centroids),
vector_uint(cluster_output.labels)]
%}
};
%extend Kmeans{
inline ClusterOutput _cluster(int _k) {
ClusterOutput output;
output.result = (*$self).Cluster(_k, output.centroids, output.labels);
return output;
}
}
}
}
173 changes: 173 additions & 0 deletions src/python/Kmeans_TEST.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,173 @@
# 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 ignition.math import Kmeans
from ignition.math import Vector3d
from ignition.math import vector_vector3d


class TestKmeans(unittest.TestCase):

def test_kmeans_constructor(self):
# Create some observations.
obs = list([])
obs.append(Vector3d(1.0, 1.0, 0.0))
obs.append(Vector3d(1.1, 1.0, 0.0))
obs.append(Vector3d(1.2, 1.0, 0.0))
obs.append(Vector3d(1.3, 1.0, 0.0))
obs.append(Vector3d(1.4, 1.0, 0.0))
obs.append(Vector3d(5.0, 1.0, 0.0))
obs.append(Vector3d(5.1, 1.0, 0.0))
obs.append(Vector3d(5.2, 1.0, 0.0))
obs.append(Vector3d(5.3, 1.0, 0.0))
obs.append(Vector3d(5.4, 1.0, 0.0))

# Initialize Kmeans with two partitions.
kmeans = Kmeans(obs)

# ::GetObservations()
obs_copy = list(kmeans.observations()).copy()
for i in range(len(obs_copy)):
self.assertEqual(obs_copy[i], obs[i])

for idx, a in enumerate(obs_copy):
obs_copy[idx] = a + Vector3d(0.1, 0.2, 0.0)

self.assertTrue(kmeans.observations(obs_copy))

obs_copy = list(kmeans.observations()).copy()
for i in range(len(obs_copy)):
self.assertEqual(obs_copy[i], obs[i] + Vector3d(0.1, 0.2, 0.0))
self.assertTrue(kmeans.observations(obs))

# ::Cluster()
result, centroids, labels = kmeans.cluster(2)
self.assertTrue(result)

# Check that there are two centroids.
self.assertEqual(len(centroids), 2)

# Check that the observations are clustered properly.
self.assertEqual(labels[0], labels[1])
self.assertEqual(labels[1], labels[2])
self.assertEqual(labels[2], labels[3])
self.assertEqual(labels[3], labels[4])

self.assertNotEqual(labels[4], labels[5])

self.assertEqual(labels[5], labels[6])
self.assertEqual(labels[6], labels[7])
self.assertEqual(labels[7], labels[8])
self.assertEqual(labels[8], labels[9])

# Check that there are two centroids.
self.assertEqual(centroids.size(), 2)
# Check that the observations are clustered properly.
self.assertEqual(labels[0], labels[1])
self.assertEqual(labels[1], labels[2])
self.assertEqual(labels[2], labels[3])
self.assertEqual(labels[3], labels[4])

self.assertNotEqual(labels[4], labels[5])

self.assertEqual(labels[5], labels[6])
self.assertEqual(labels[6], labels[7])
self.assertEqual(labels[7], labels[8])
self.assertEqual(labels[8], labels[9])

# Check that there are two centroids.
self.assertEqual(centroids.size(), 2)

# Check that the observations are clustered properly.
self.assertEqual(labels[0], labels[1])
self.assertEqual(labels[1], labels[2])
self.assertEqual(labels[2], labels[3])
self.assertEqual(labels[3], labels[4])

self.assertNotEqual(labels[4], labels[5])

self.assertEqual(labels[5], labels[6])
self.assertEqual(labels[6], labels[7])
self.assertEqual(labels[7], labels[8])
self.assertEqual(labels[8], labels[9])

# Check the centroids.
expected_centroid1 = Vector3d(1.2, 1.0, 0.0)
expected_centroid2 = Vector3d(5.2, 1.0, 0.0)
if (centroids[0] == expected_centroid1):
self.assertEqual(centroids[1], expected_centroid2)
elif (centroids[0] == expected_centroid2):
self.assertEqual(centroids[1], expected_centroid1)
else:
self.fail()

# Try to use an empty observation vector.
obs_copy.clear()
self.assertFalse(kmeans.observations(obs_copy))

# Try to call 'Cluster()' with an empty vector.
kmeansEmpty = Kmeans(obs_copy)
result, centroids, labels = kmeansEmpty.cluster(2)
self.assertFalse(result)

# Try to use a non positive k.
result, centroids, labels = kmeans.cluster(0)
self.assertFalse(result)

# Try to use a k > num_observations.
result, centroids, labels = kmeans.cluster(len(obs) + 1)
self.assertFalse(result)

def test_kmeans_append(self):
# Create some observations.
obs = list([])
obs2 = list([])
obs_total = list([])

obs.append(Vector3d(1.0, 1.0, 0.0))
obs.append(Vector3d(1.1, 1.0, 0.0))
obs.append(Vector3d(1.2, 1.0, 0.0))
obs.append(Vector3d(1.3, 1.0, 0.0))
obs.append(Vector3d(1.4, 1.0, 0.0))

obs2.append(Vector3d(5.0, 1.0, 0.0))
obs2.append(Vector3d(5.1, 1.0, 0.0))
obs2.append(Vector3d(5.2, 1.0, 0.0))
obs2.append(Vector3d(5.3, 1.0, 0.0))
obs2.append(Vector3d(5.4, 1.0, 0.0))

for elem in obs:
obs_total.append(elem)

for elem in obs2:
obs_total.append(elem)

# Initialize Kmeans with two partitions.
kmeans = Kmeans(obs)

kmeans.append_observations(obs2)

obs_copy = vector_vector3d(kmeans.observations())

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

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


if __name__ == '__main__':
unittest.main()
51 changes: 51 additions & 0 deletions src/python/Vector3Stats.i
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
/*
* 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.
*
*/

%module vector3stats
%{
#include <ignition/math/Helpers.hh>
#include <ignition/math/SignalStats.hh>
#include <ignition/math/Vector3.hh>
#include <ignition/math/Vector3Stats.hh>
%}

%include "std_string.i"

namespace ignition
{
namespace math
{
class Vector3Stats
{
%rename("%(undercase)s", %$isfunction, %$ismember, %$not %$isconstructor) "";
public: Vector3Stats();
public: ~Vector3Stats();
public: void InsertData(const Vector3<double> &_data);
public: bool InsertStatistic(const std::string &_name);
public: bool InsertStatistics(const std::string &_names);
public: void Reset();
public: const SignalStats &X() const;
public: const SignalStats &Y() const;
public: const SignalStats &Z() const;
public: const SignalStats &Mag() const;
public: SignalStats &X();
public: SignalStats &Y();
public: SignalStats &Z();
public: SignalStats &Mag();
};
}
}
Loading

0 comments on commit b4531e2

Please sign in to comment.