Skip to content

Commit

Permalink
Added MovingWindowFilter pybind11 interface (#321)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <ahcorde@gmail.com>
  • Loading branch information
ahcorde authored Dec 24, 2021
1 parent 8b5f3dc commit 1cac654
Show file tree
Hide file tree
Showing 5 changed files with 73 additions and 1 deletion.
1 change: 0 additions & 1 deletion src/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,6 @@ if (PYTHONLIBS_FOUND)
Material_TEST
Matrix3_TEST
Matrix4_TEST
MovingWindowFilter_TEST
OrientedBox_TEST
PID_TEST
Plane_TEST
Expand Down
1 change: 1 addition & 0 deletions src/python_pybind11/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ if (${pybind11_FOUND})
Helpers_TEST
Line2_TEST
Line3_TEST
MovingWindowFilter_TEST
Quaternion_TEST
Rand_TEST
RollingMean_TEST
Expand Down
64 changes: 64 additions & 0 deletions src/python_pybind11/src/MovingWindowFilter.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
/*
* 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__MOVINGWINDOWFILTER_HH_
#define IGNITION_MATH_PYTHON__MOVINGWINDOWFILTER_HH_

#include <string>

#include <pybind11/pybind11.h>

#include <ignition/math/MovingWindowFilter.hh>

namespace py = pybind11;
using namespace pybind11::literals;

namespace ignition
{
namespace math
{
namespace python
{
/// Define a pybind11 wrapper for an ignition::math::MovingWindowFilter
/**
* \param[in] module a pybind11 module to add the definition to
* \param[in] typestr name of the type used by Python
*/
template<typename T>
void defineMathMovingWindowFilter(py::module &m, const std::string &typestr)
{
using Class = ignition::math::MovingWindowFilter<T>;
std::string pyclass_name = typestr;
py::class_<Class>(m,
pyclass_name.c_str(),
py::buffer_protocol(),
py::dynamic_attr())
.def(py::init<>())
.def("update", &Class::Update, "Update value of filter")
.def("set_window_size", &Class::SetWindowSize, "Set window size")
.def("window_size", &Class::WindowSize, "Get the window size.")
.def("window_filled",
&Class::WindowFilled,
"Get whether the window has been filled.")
.def("value", &Class::Value, "Get filtered result");
}

} // namespace python
} // namespace math
} // namespace ignition

#endif // IGNITION_MATH_PYTHON__MovingWindowFilterD_HH_
8 changes: 8 additions & 0 deletions src/python_pybind11/src/_ignition_math_pybind11.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include "Helpers.hh"
#include "Line2.hh"
#include "Line3.hh"
#include "MovingWindowFilter.hh"
#include "Quaternion.hh"
#include "Rand.hh"
#include "RollingMean.hh"
Expand All @@ -39,6 +40,13 @@ PYBIND11_MODULE(math, m)

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

ignition::math::python::defineMathMovingWindowFilter<int>(
m, "MovingWindowFilteri");
ignition::math::python::defineMathMovingWindowFilter<double>(
m, "MovingWindowFilterd");
ignition::math::python::defineMathMovingWindowFilter
<ignition::math::Vector3d>(m, "MovingWindowFilterv3");

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

ignition::math::python::defineMathRollingMean(m, "RollingMean");
Expand Down
File renamed without changes.

0 comments on commit 1cac654

Please sign in to comment.