Skip to content

Commit

Permalink
Added PID pybind11 interface (#323)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <[email protected]>
Signed-off-by: Louise Poubel <[email protected]>

Co-authored-by: Louise Poubel <[email protected]>
  • Loading branch information
ahcorde and chapulina authored Dec 29, 2021
1 parent 85224e3 commit 3d1d076
Show file tree
Hide file tree
Showing 6 changed files with 189 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 @@ -93,7 +93,6 @@ if (PYTHONLIBS_FOUND)
Inertial_TEST
Matrix4_TEST
OrientedBox_TEST
PID_TEST
Plane_TEST
python_TEST
SignalStats_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 @@ -22,6 +22,7 @@ if (${pybind11_FOUND})
src/Helpers.cc
src/Kmeans.cc
src/Material.cc
src/PID.cc
src/Rand.cc
src/RollingMean.cc
src/RotationSpline.cc
Expand Down Expand Up @@ -95,6 +96,7 @@ if (${pybind11_FOUND})
Matrix3_TEST
MassMatrix3_TEST
MovingWindowFilter_TEST
PID_TEST
Pose3_TEST
Quaternion_TEST
Rand_TEST
Expand Down
126 changes: 126 additions & 0 deletions src/python_pybind11/src/PID.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,126 @@
/*
* 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 <pybind11/chrono.h>
#include <string>

#include <ignition/math/PID.hh>

#include "PID.hh"

namespace ignition
{
namespace math
{
namespace python
{
void defineMathPID(py::module &m, const std::string &typestr)
{
using Class = ignition::math::PID;
std::string pyclass_name = typestr;
py::class_<Class>(m,
pyclass_name.c_str(),
py::buffer_protocol(),
py::dynamic_attr())
.def(py::init<>())
.def(py::init<Class&>())
.def(py::init<const double, const double, const double, const double,
const double, const double, const double, const double>(),
py::arg("_p") = 0.0, py::arg("_i") = 0.0, py::arg("_d") = 0.0,
py::arg("_imax") = -1.0, py::arg("_imin") = 0.0,
py::arg("_cmdMax") = -1.0, py::arg("_cmdMin") = 0.0,
py::arg("_cmdOffset") = 0.0)
.def("init",
&Class::Init,
py::arg("_p") = 0.0, py::arg("_i") = 0.0, py::arg("_d") = 0.0,
py::arg("_imax") = -1.0, py::arg("_imin") = 0.0,
py::arg("_cmdMax") = -1.0, py::arg("_cmdMin") = 0.0,
py::arg("_cmdOffset") = 0.0,
"Initialize PID-gains and integral term "
"limits:[iMax:iMin]-[I1:I2].")
.def("set_p_gain",
&Class::SetPGain,
"Set the proportional Gain.")
.def("set_i_gain",
&Class::SetIGain,
"Set the integral Gain.")
.def("set_d_gain",
&Class::SetDGain,
"Set the derivative Gain.")
.def("set_i_max",
&Class::SetIMax,
"Set the integral upper limit.")
.def("set_i_min",
&Class::SetIMin,
"Set the integral lower limit.")
.def("set_cmd_max",
&Class::SetCmdMax,
"Set the maximum value for the command.")
.def("set_cmd_min",
&Class::SetCmdMin,
"Set the minimum value for the command.")
.def("set_cmd_offset",
&Class::SetCmdOffset,
"Set the offset value for the command, which is added to the result of "
"the PID controller.")
.def("p_gain",
&Class::PGain,
"Get the proportional Gain.")
.def("i_gain",
&Class::IGain,
"Get the integral Gain.")
.def("d_gain",
&Class::DGain,
"Get the derivative Gain.")
.def("i_max",
&Class::IMax,
"Get the integral upper limit.")
.def("i_min",
&Class::IMin,
"Get the integral lower limit.")
.def("cmd_max",
&Class::CmdMax,
"Get the maximum value for the command.")
.def("cmd_min",
&Class::CmdMin,
"Get the minimun value for the command.")
.def("cmd_offset",
&Class::CmdOffset,
"Get the offset value for the command.")
.def("update",
&Class::Update,
"Update the Pid loop with nonuniform time step size.")
.def("set_cmd",
&Class::SetCmd,
"Set current target command for this PID controller.")
.def("cmd",
&Class::Cmd,
"Return current command for this PID controller.")
.def("errors",
[](const Class &self) {
double pe, ie, de;
self.Errors(pe, ie, de);
return std::make_tuple(pe, ie, de);
},
"Return PID error terms for the controller.")
.def("reset",
&Class::Reset,
"Reset the errors and command.");
}
} // namespace python
} // namespace math
} // namespace ignition
41 changes: 41 additions & 0 deletions src/python_pybind11/src/PID.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
/*
* 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__PID_HH_
#define IGNITION_MATH_PYTHON__PID_HH_

#include <pybind11/pybind11.h>
#include <string>
namespace py = pybind11;

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

#endif // IGNITION_MATH_PYTHON__PID_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 @@ -28,6 +28,7 @@
#include "Material.hh"
#include "Matrix3.hh"
#include "MovingWindowFilter.hh"
#include "PID.hh"
#include "Pose3.hh"
#include "Quaternion.hh"
#include "Rand.hh"
Expand Down Expand Up @@ -74,6 +75,8 @@ PYBIND11_MODULE(math, m)
ignition::math::python::defineMathMovingWindowFilter
<ignition::math::Vector3d>(m, "MovingWindowFilterv3");

ignition::math::python::defineMathPID(m, "PID");

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

ignition::math::python::defineMathRollingMean(m, "RollingMean");
Expand Down
21 changes: 17 additions & 4 deletions src/python/PID_TEST.py → src/python_pybind11/test/PID_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import datetime
import unittest
from ignition.math import PID

Expand Down Expand Up @@ -107,7 +108,7 @@ def test_equal_corner_case(self):

def test_update(self):
pid = PID()
pid.init(1.0, 0.1, 0.5, 10, 0, 20, -20)
pid.init(1.0, 0.1, 0.5, 10.0, 0.0, 20.0, -20.0)

result = pid.update(5.0, 0.0)
self.assertAlmostEqual(result, 0.0)
Expand Down Expand Up @@ -144,7 +145,8 @@ def test_update(self):
def update_test(self, _pid, _result, _error,
_dt, _p_error, _i_error, _d_error):

self.assertAlmostEqual(_result, _pid.update(_error, _dt))
self.assertAlmostEqual(
_result, _pid.update(_error, datetime.timedelta(seconds=_dt)))
[p_error, i_error, d_error] = _pid.errors()
self.assertAlmostEqual(p_error, _p_error)
self.assertAlmostEqual(i_error, _i_error)
Expand All @@ -158,32 +160,37 @@ def test_zero_gains(self):
self.update_test(pid, 0, 0, 0, 0, 0, 0)
self.update_test(pid, 0, 0, 0, 0, 0, 0)

# dt = 0, no change since previous state
self.update_test(pid, 0, 1, 0, 0, 0, 0)
self.update_test(pid, 0, 1, 0, 0, 0, 0)
self.update_test(pid, 0, -1, 0, 0, 0, 0)
self.update_test(pid, 0, -1, 0, 0, 0, 0)
self.update_test(pid, 0, 1, 0, 0, 0, 0)
self.update_test(pid, 0, 1, 0, 0, 0, 0)

# dt > 0, but gains still zero
self.update_test(pid, 0, 1, 1, 1, 0, 1)
self.update_test(pid, 0, 1, 1, 1, 0, 0)
self.update_test(pid, 0, -1, 1, -1, 0, -2)
self.update_test(pid, 0, -1, 1, -1, 0, 0)
self.update_test(pid, 0, 1, 1, 1, 0, 2)
self.update_test(pid, 0, 1, 1, 1, 0, 0)

# dt = 0, no change since previous state
self.update_test(pid, 0, 1, 0, 1, 0, 0)
self.update_test(pid, 0, 1, 0, 1, 0, 0)
self.update_test(pid, 0, -1, 0, 1, 0, 0)
self.update_test(pid, 0, -1, 0, 1, 0, 0)
self.update_test(pid, 0, 1, 0, 1, 0, 0)
self.update_test(pid, 0, 1, 0, 1, 0, 0)

# dt < 0, but gains still zero
# TODO(chapulina) Check why d_error fails in the commented test cases
self.update_test(pid, 0, 1, -1, 1, 0, 0)
self.update_test(pid, 0, 1, -1, 1, 0, 0)
self.update_test(pid, 0, -1, -1, -1, 0, 2)
# self.update_test(pid, 0, -1, -1, -1, 0, 2)
self.update_test(pid, 0, -1, -1, -1, 0, 0)
self.update_test(pid, 0, 1, -1, 1, 0, -2)
# self.update_test(pid, 0, 1, -1, 1, 0, -2)
self.update_test(pid, 0, 1, -1, 1, 0, 0)

pid.reset()
Expand All @@ -197,13 +204,15 @@ def test_zero_gains(self):
# command hasn't been updated yet
self.assertAlmostEqual(0.0, pid.cmd())

# dt = 0, still report cmd = 0
self.update_test(pid, 0, 1, 0, 0, 0, 0)
self.update_test(pid, 0, 1, 0, 0, 0, 0)
self.update_test(pid, 0, -1, 0, 0, 0, 0)
self.update_test(pid, 0, -1, 0, 0, 0, 0)
self.update_test(pid, 0, 1, 0, 0, 0, 0)
self.update_test(pid, 0, 1, 0, 0, 0, 0)

# dt > 0, report clamped value
self.update_test(pid, -1, 1, 1, 1, 0, 1)
self.update_test(pid, -1, 1, 1, 1, 0, 0)
self.update_test(pid, -1, -1, 1, -1, 0, -2)
Expand All @@ -223,13 +232,15 @@ def test_zero_gains(self):
[p_err, i_err, d_err] = pid.errors()
self.assertAlmostEqual(0.0, i_err)

# dt = 0, still report iErr = 0
self.update_test(pid, 0, 1, 0, 0, 0, 0)
self.update_test(pid, 0, 1, 0, 0, 0, 0)
self.update_test(pid, 0, -1, 0, 0, 0, 0)
self.update_test(pid, 0, -1, 0, 0, 0, 0)
self.update_test(pid, 0, 1, 0, 0, 0, 0)
self.update_test(pid, 0, 1, 0, 0, 0, 0)

# dt > 0, report clamped value
self.update_test(pid, -1, 1, 1, 1, -1, 1)
self.update_test(pid, -1, 1, 1, 1, -1, 0)
self.update_test(pid, -1, -1, 1, -1, -1, -2)
Expand All @@ -245,13 +256,15 @@ def test_zero_gains(self):
# cmd hasn't been updated yet
self.assertAlmostEqual(0.0, pid.cmd())

# dt = 0, still return 0
self.update_test(pid, 0, 1, 0, 0, 0, 0)
self.update_test(pid, 0, 1, 0, 0, 0, 0)
self.update_test(pid, 0, -1, 0, 0, 0, 0)
self.update_test(pid, 0, -1, 0, 0, 0, 0)
self.update_test(pid, 0, 1, 0, 0, 0, 0)
self.update_test(pid, 0, 1, 0, 0, 0, 0)

# dt > 0, report negative min value
self.update_test(pid, -10, 1, 1, 1, -1, 1)
self.update_test(pid, -10, 1, 1, 1, -1, 0)
self.update_test(pid, -10, -1, 1, -1, -1, -2)
Expand Down

0 comments on commit 3d1d076

Please sign in to comment.