Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added MecanumDriveOdometry Python wrapper #549

Merged
merged 10 commits into from
Feb 13, 2024
2 changes: 2 additions & 0 deletions src/python_pybind11/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ pybind11_add_module(math SHARED
src/Matrix3.cc
src/Matrix4.cc
src/Matrix6.cc
src/MecanumDriveOdometry.cc
src/MovingWindowFilter.cc
src/PID.cc
src/Polynomial3.cc
Expand Down Expand Up @@ -124,6 +125,7 @@ if (BUILD_TESTING)
Matrix3_TEST
Matrix4_TEST
Matrix6_TEST
MecanumDriveOdometry_TEST
MovingWindowFilter_TEST
OrientedBox_TEST
PID_TEST
Expand Down
74 changes: 74 additions & 0 deletions src/python_pybind11/src/MecanumDriveOdometry.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
/*
* Copyright (C) 2023 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 <gz/math/MecanumDriveOdometry.hh>

#include "MecanumDriveOdometry.hh"

namespace ignition
{
namespace math
{
namespace python
{
void defineMathMecanumDriveOdometry(py::module &m, const std::string &typestr)
{
using Class = gz::math::MecanumDriveOdometry;
std::string pyclass_name = typestr;
py::class_<Class>(m,
pyclass_name.c_str(),
py::buffer_protocol())
.def(py::init<size_t>(), py::arg("_windowSize") = 10)
.def("init", &Class::Init, "Initialize the odometry")
.def("initialized", &Class::Initialized, "Get whether Init has been called.")
.def("update",
&Class::Update,
"Updates the odometry class with latest wheels and "
"steerings position")
.def("heading", &Class::Heading, "Get the heading.")
.def("x", &Class::X, "Get the X position.")
.def("y", &Class::Y, "Get the Y position.")
.def("linear_velocity",
&Class::LinearVelocity,
"Get the linear velocity.")
.def("angular_velocity",
&Class::AngularVelocity,
"Get the angular velocity.")
.def("lateral_velocity",
&Class::LateralVelocity,
"Get the lateral velocity.")
.def("set_wheel_params",
&Class::SetWheelParams,
"Set the wheel parameters including the radius and separation.")
.def("set_velocity_rolling_window_size",
&Class::SetVelocityRollingWindowSize,
"Set the velocity rolling window size.")
.def("wheel_separation", &Class::WheelSeparation, "Get the wheel separation")
.def("wheel_base", &Class::WheelBase, "Get the wheel base")
.def("left_wheel_radius",
&Class::LeftWheelRadius,
"Get the left wheel radius")
.def("right_wheel_radius",
&Class::RightWheelRadius,
"Get the rightwheel radius");

}
} // namespace python
} // namespace math
} // namespace ignition
44 changes: 44 additions & 0 deletions src/python_pybind11/src/MecanumDriveOdometry.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
/*
* Copyright (C) 2023 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__MECANUMDRIVEODOMETRY_HH_
#define GZ_MATH_PYTHON__MECANUMDRIVEODOMETRY_HH_

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

#include <string>
namespace py = pybind11;

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

#endif // GZ_MATH_PYTHON__MECANUMDRIVEODOMETRY_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 @@ -36,6 +36,7 @@
#include "Matrix3.hh"
#include "Matrix4.hh"
#include "Matrix6.hh"
#include "MecanumDriveOdometry.hh"
#include "MovingWindowFilter.hh"
#include "OrientedBox.hh"
#include "PID.hh"
Expand Down Expand Up @@ -151,6 +152,8 @@ PYBIND11_MODULE(math, m)

gz::math::python::defineMathMatrix6(m, "Matrix6");

gz::math::python::defineMathMecanumDriveOdometry(m, "MecanumDriveOdometry");

gz::math::python::defineMathTriangle(m, "Triangle");

gz::math::python::defineMathTriangle3(m, "Triangle3");
Expand Down
5 changes: 3 additions & 2 deletions src/python_pybind11/test/DiffDriveOdometry_TEST.py
azeey marked this conversation as resolved.
Show resolved Hide resolved
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

import datetime
import math
import time
import unittest

from ignition.math import Angle, DiffDriveOdometry
Expand All @@ -38,7 +39,7 @@ def test_diff_drive_odometry(self):

# Setup the wheel parameters, and initialize
odom.set_wheel_params(wheelSeparation, wheelRadius, wheelRadius)
startTime = datetime.datetime.now()
startTime = datetime.timedelta(time.monotonic())
odom.init(datetime.timedelta())
azeey marked this conversation as resolved.
Show resolved Hide resolved

# Sleep for a little while, then update the odometry with the new wheel
Expand Down Expand Up @@ -71,7 +72,7 @@ def test_diff_drive_odometry(self):
self.assertAlmostEqual(0.0, odom.angular_velocity().radian(), delta=1e-3)

# Initialize again, and odom values should be reset.
startTime = datetime.datetime.now()
startTime = datetime.timedelta(time.monotonic())
odom.init(datetime.timedelta())
azeey marked this conversation as resolved.
Show resolved Hide resolved
self.assertEqual(0.0, odom.heading().radian())
self.assertEqual(0.0, odom.x())
Expand Down
123 changes: 123 additions & 0 deletions src/python_pybind11/test/MecanumDriveOdometry_TEST.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,123 @@
# Copyright (C) 2023 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 datetime
import math
import time
import unittest

from ignition.math import MecanumDriveOdometry, Angle


class TestMecanumDriveOdometry(unittest.TestCase):

def test_constructor(self):
odom = MecanumDriveOdometry()
self.assertAlmostEqual(0.0, odom.heading().radian())
self.assertAlmostEqual(0.0, odom.x())
self.assertAlmostEqual(0.0, odom.y())
self.assertAlmostEqual(0.0, odom.linear_velocity())
self.assertAlmostEqual(0.0, odom.lateral_velocity())
self.assertAlmostEqual(0.0, odom.angular_velocity().radian())

wheelSeparation = 2.0
wheelRadius = 0.5
wheelCircumference = 2 * math.pi * wheelRadius

# This is the linear distance traveled per degree of wheel rotation.
distPerDegree = wheelCircumference / 360.0

# Setup the wheel parameters, and initialize
odom.set_wheel_params(wheelSeparation, wheelRadius, wheelRadius,wheelRadius)
startTime = datetime.timedelta(time.monotonic())
odom.init(startTime)

# Sleep for a little while, then update the odometry with the new wheel
# position.
time1 = startTime + datetime.timedelta(milliseconds=100)
odom.update(Angle(math.radians(1.0)),
Angle(math.radians(1.0)),
Angle(math.radians(1.0)),
Angle(math.radians(1.0)),
time1)
self.assertAlmostEqual(0.0, odom.heading().radian())
self.assertAlmostEqual(distPerDegree, odom.x())
self.assertAlmostEqual(0.0, odom.y())
# Linear velocity should be dist_traveled / time_elapsed.
self.assertAlmostEqual(distPerDegree / 0.1, odom.linear_velocity(), delta=1e-3)
# Angular velocity should be zero since the "robot" is traveling in a
# straight line.
self.assertAlmostEqual(0.0, odom.angular_velocity().radian(), delta=1e-3)

# Sleep again, then update the odometry with the new wheel position.
time2 = time1 + datetime.timedelta(milliseconds=100)
odom.update(Angle(math.radians(2.0)),
Angle(math.radians(2.0)),
Angle(math.radians(2.0)),
Angle(math.radians(2.0)),
time2)
self.assertAlmostEqual(0.0, odom.heading().radian())
self.assertAlmostEqual(distPerDegree * 2.0, odom.x(), delta=3e-6)
self.assertAlmostEqual(0.0, odom.y())
# Linear velocity should be dist_traveled / time_elapsed.
self.assertAlmostEqual(distPerDegree / 0.1, odom.linear_velocity(), delta=1e-3)
# Angular velocity should be zero since the "robot" is traveling in a
# straight line.
self.assertAlmostEqual(0.0, odom.angular_velocity().radian(), delta=1e-3)

# Initialize again, and odom values should be reset.
startTime = datetime.timedelta(time.monotonic())
odom.init(startTime)
self.assertAlmostEqual(0.0, odom.heading().radian())
self.assertAlmostEqual(0.0, odom.x())
self.assertAlmostEqual(0.0, odom.y())
self.assertAlmostEqual(0.0, odom.linear_velocity())
self.assertAlmostEqual(0.0, odom.angular_velocity().radian())

# Sleep again, this time move 2 degrees in 100ms.
time1 = startTime + datetime.timedelta(milliseconds=100)
odom.update(Angle(math.radians(2.0)),
Angle(math.radians(2.0)),
Angle(math.radians(2.0)),
Angle(math.radians(2.0)),
time1)
self.assertAlmostEqual(0.0, odom.heading().radian())
self.assertAlmostEqual(distPerDegree * 2.0, odom.x(), delta=3e-6)
self.assertAlmostEqual(0.0, odom.y())
# Linear velocity should be dist_traveled / time_elapsed.
self.assertAlmostEqual(distPerDegree * 2 / 0.1, odom.linear_velocity(), delta=1e-3)
# Angular velocity should be zero since the "robot" is traveling in a
# straight line.
self.assertAlmostEqual(0.0, odom.angular_velocity().radian(), delta=1e-3)

# Sleep again, this time move 2 degrees in 100ms.
odom.init(startTime)
time1 = startTime + datetime.timedelta(milliseconds=100)
odom.update(Angle(math.radians(-2.0)),
Angle(math.radians(2.0)),
Angle(math.radians(2.0)),
Angle(math.radians(-2.0)),
time1)
self.assertAlmostEqual(0.0, odom.heading().radian())
self.assertAlmostEqual(distPerDegree * 2.0, odom.y(), delta=3e-6)
# self.assertAlmostEqual(0.0, odom.y())
# Linear velocity should be dist_traveled / time_elapsed.
self.assertAlmostEqual(distPerDegree * 2 / 0.1, odom.lateral_velocity(), delta=1e-3)
# Angular velocity should be zero since the "robot" is traveling in a
# straight line.
self.assertAlmostEqual(0.0, odom.angular_velocity().radian(), delta=1e-3)


if __name__ == '__main__':
unittest.main()