Skip to content

Commit

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

Co-authored-by: Louise Poubel <[email protected]>
  • Loading branch information
ahcorde and chapulina authored Dec 23, 2021
1 parent be461ca commit b0f3685
Show file tree
Hide file tree
Showing 6 changed files with 136 additions and 13 deletions.
1 change: 0 additions & 1 deletion src/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,6 @@ if (PYTHONLIBS_FOUND)
Sphere_TEST
SphericalCoordinates_TEST
Spline_TEST
StopWatch_TEST
Temperature_TEST
Triangle_TEST
Triangle3_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 @@ -19,6 +19,7 @@ if (${pybind11_FOUND})
src/Helpers.cc
src/Rand.cc
src/RollingMean.cc
src/StopWatch.cc
)

target_link_libraries(math PRIVATE
Expand Down Expand Up @@ -77,6 +78,7 @@ if (${pybind11_FOUND})
Line2_TEST
Rand_TEST
RollingMean_TEST
StopWatch_TEST
Vector2_TEST
Vector3_TEST
Vector4_TEST
Expand Down
77 changes: 77 additions & 0 deletions src/python_pybind11/src/StopWatch.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
/*
* 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 <pybind11/operators.h>
#include <string>

#include "StopWatch.hh"

#include <ignition/math/Stopwatch.hh>

namespace ignition
{
namespace math
{
namespace python
{
void defineMathStopwatch(py::module &m, const std::string &typestr)
{
using Class = ignition::math::Stopwatch;
std::string pyclass_name = typestr;
py::class_<Class>(m,
pyclass_name.c_str(),
py::buffer_protocol(),
py::dynamic_attr())
.def(py::init<>())
.def(py::self != py::self)
.def(py::self == py::self)
.def("start",
&Class::Start, py::arg("_reset") = false,
"Start the stopwatch.")
.def("start_time",
&Class::StartTime,
"Get the time when the stopwatch was started.")
.def("stop",
&Class::Stop,
"Stop the stopwatch")
.def("stop_time",
&Class::StopTime,
"Get the time when the stopwatch was last stopped.")
.def("running",
&Class::Running,
"Get whether the stopwatch is running.")
.def("reset",
&Class::Reset,
"Reset the stopwatch. This resets the start time, stop time "
"elapsed duration and elapsed stop duration.")
.def("elapsed_run_time",
&Class::ElapsedRunTime,
"Get the amount of time that the stop watch has been "
"running. This is the total amount of run time, spannning all start "
"and stop calls. The Reset function or passing true to the Start "
"function will reset this value.")
.def("elapsed_stop_time",
&Class::ElapsedStopTime,
"Get the amount of time that the stop watch has been "
"stopped. This is the total amount of stop time, spannning all start "
"and stop calls. The Reset function or passing true to the Start "
"function will reset this value.");
}
} // namespace python
} // namespace math
} // namespace ignition
42 changes: 42 additions & 0 deletions src/python_pybind11/src/StopWatch.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__STOPWATCH_HH_
#define IGNITION_MATH_PYTHON__STOPWATCH_HH_

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

namespace py = pybind11;

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

#endif // IGNITION_MATH_PYTHON__STOPWATCH_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 @@ -20,6 +20,7 @@
#include "Line2.hh"
#include "Rand.hh"
#include "RollingMean.hh"
#include "StopWatch.hh"
#include "Vector2.hh"
#include "Vector3.hh"
#include "Vector4.hh"
Expand All @@ -40,6 +41,8 @@ PYBIND11_MODULE(math, m)

ignition::math::python::defineMathRollingMean(m, "RollingMean");

ignition::math::python::defineMathStopwatch(m, "Stopwatch");

ignition::math::python::defineMathVector2<double>(m, "Vector2d");
ignition::math::python::defineMathVector2<int>(m, "Vector2i");
ignition::math::python::defineMathVector2<float>(m, "Vector2f");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
class TestBox(unittest.TestCase):
# Helper function that runs a few tests
def runTimer(self, _time):
handleSteadyClock = 0
handleSteadyClock = timedelta(0)

# Start the timer
self.assertTrue(_time.start())
Expand All @@ -31,12 +31,12 @@ def runTimer(self, _time):
# The start time should be greater than the stop time.
self.assertGreater(_time.start_time(), _time.stop_time())
# The elapsed stop time should still be zero.
self.assertEqual(0, _time.elapsed_stop_time())
self.assertEqual(timedelta(0), _time.elapsed_stop_time())

# Wait for some time...
time.sleep(1)
# Now the elapsed time should be greater than or equal to the time slept.
self.assertGreaterEqual(_time.elapsed_run_time() + handleSteadyClock, 1000)
self.assertGreaterEqual(_time.elapsed_run_time() + handleSteadyClock, timedelta(seconds=1))

# Stop the timer.
self.assertTrue(_time.stop())
Expand All @@ -45,7 +45,7 @@ def runTimer(self, _time):
# The stop time should be greater than the start time.
self.assertGreater(_time.stop_time(), _time.start_time())
# The elapsed time should still be greater than the time slept.
self.assertGreaterEqual(_time.elapsed_run_time() + handleSteadyClock, 1000)
self.assertGreaterEqual(_time.elapsed_run_time() + handleSteadyClock, timedelta(seconds=1))

# Save the elapsed time.
elapsedTime = _time.elapsed_run_time()
Expand All @@ -54,7 +54,7 @@ def runTimer(self, _time):
time.sleep(1)
# The elapsed stop time should be greater than or equal to the time
# slept.
self.assertGreaterEqual(_time.elapsed_stop_time() + handleSteadyClock, 1000)
self.assertGreaterEqual(_time.elapsed_stop_time() + handleSteadyClock, timedelta(seconds=1))
# The elapsed time should be the same.
self.assertEqual(elapsedTime, _time.elapsed_run_time())

Expand All @@ -72,15 +72,15 @@ def runTimer(self, _time):
self.assertGreater(_time.elapsed_run_time(), elapsedTime)
# The elapsed time should be greater than or equal to the the previous
# two sleep times.
self.assertGreaterEqual(_time.elapsed_run_time() + handleSteadyClock, 2000)
self.assertGreaterEqual(_time.elapsed_run_time() + handleSteadyClock, timedelta(seconds=2))

def test_constructor(self):
watch = Stopwatch()

self.assertFalse(watch.running())
self.assertEqual(watch.stop_time(), watch.start_time())
self.assertEqual(0, watch.elapsed_run_time())
self.assertEqual(0, watch.elapsed_stop_time())
self.assertEqual(timedelta(0), watch.elapsed_run_time())
self.assertEqual(timedelta(0), watch.elapsed_stop_time())

self.runTimer(watch)

Expand Down Expand Up @@ -119,8 +119,8 @@ def test_start_stop_reset(self):

self.assertFalse(watch.running())
self.assertEqual(watch.stop_time(), watch.start_time())
self.assertEqual(0, watch.elapsed_run_time())
self.assertEqual(0, watch.elapsed_stop_time())
self.assertEqual(timedelta(0), watch.elapsed_run_time())
self.assertEqual(timedelta(0), watch.elapsed_stop_time())

self.runTimer(watch)

Expand All @@ -129,8 +129,8 @@ def test_start_stop_reset(self):
watch.start(True)
self.assertTrue(watch.running())
self.assertLess(watch.stop_time(), watch.start_time())
self.assertNotEqual(0, watch.elapsed_run_time())
self.assertEqual(0, watch.elapsed_stop_time())
self.assertNotEqual(timedelta(0), watch.elapsed_run_time())
self.assertEqual(timedelta(0), watch.elapsed_stop_time())

def test_fail_start_stop(self):
watch = Stopwatch()
Expand Down

0 comments on commit b0f3685

Please sign in to comment.