Skip to content

Commit

Permalink
time_until_next_call returns None if timer is canceled.
Browse files Browse the repository at this point in the history
Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
  • Loading branch information
fujitatomoya committed Mar 10, 2022
1 parent 12f3698 commit 53a215e
Show file tree
Hide file tree
Showing 3 changed files with 45 additions and 7 deletions.
8 changes: 6 additions & 2 deletions rclpy/src/rclpy/timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,13 +13,15 @@
// limitations under the License.

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

#include <rcl/context.h>
#include <rcl/error_handling.h>
#include <rcl/rcl.h>
#include <rcl/timer.h>
#include <rcl/types.h>

#include <limits>
#include <memory>
#include <stdexcept>

Expand Down Expand Up @@ -105,11 +107,13 @@ void Timer::change_timer_period(int64_t period_nsec)
}
}

int64_t Timer::time_until_next_call()
std::optional<int64_t> Timer::time_until_next_call()
{
int64_t remaining_time;
rcl_ret_t ret = rcl_timer_get_time_until_next_call(rcl_timer_.get(), &remaining_time);
if (ret != RCL_RET_OK) {
if (ret == RCL_RET_TIMER_CANCELED) {
return std::nullopt;
} else if (ret != RCL_RET_OK) {
throw RCLError("failed to get time until next timer call");
}

Expand Down
5 changes: 3 additions & 2 deletions rclpy/src/rclpy/timer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,9 +87,10 @@ class Timer : public Destroyable, public std::enable_shared_from_this<Timer>
*
* Raises RCLError there is an rcl error
*
* \return the time until next call in nanoseconds
* \return the time until next call in nanoseconds.
* std::nullopt if the timer is canceled.
*/
int64_t time_until_next_call();
std::optional<int64_t> time_until_next_call();

/// Get the time since the timer has been called
/**
Expand Down
39 changes: 36 additions & 3 deletions rclpy/test/test_timer.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

import pytest
import rclpy
from rclpy.constants import S_TO_NS
from rclpy.executors import SingleThreadedExecutor


Expand Down Expand Up @@ -49,7 +50,7 @@ def test_zero_callback(period):
executor = SingleThreadedExecutor(context=context)
try:
executor.add_node(node)
# The first spin_once() takes long enough for 1ms timer tests to fail
# The first spin_once() takes long enough for 1ms timer tests to fail
executor.spin_once(timeout_sec=0)

callbacks = []
Expand Down Expand Up @@ -78,7 +79,7 @@ def test_number_callbacks(period):
executor = SingleThreadedExecutor(context=context)
try:
executor.add_node(node)
# The first spin_once() takes long enough for 1ms timer tests to fail
# The first spin_once() takes long enough for 1ms timer tests to fail
executor.spin_once(timeout_sec=0)

callbacks = []
Expand Down Expand Up @@ -110,7 +111,7 @@ def test_cancel_reset(period):
executor = SingleThreadedExecutor(context=context)
try:
executor.add_node(node)
# The first spin_once() takes long enough for 1ms timer tests to fail
# The first spin_once() takes long enough for 1ms timer tests to fail
executor.spin_once(timeout_sec=0)

callbacks = []
Expand Down Expand Up @@ -148,3 +149,35 @@ def test_cancel_reset(period):
node.destroy_node()
finally:
rclpy.shutdown(context=context)


def test_time_until_next_call():
context = rclpy.context.Context()
rclpy.init(context=context)
try:
node = rclpy.create_node('test_time_until_next_call', context=context)
try:
executor = SingleThreadedExecutor(context=context)
try:
executor.add_node(node)
executor.spin_once(timeout_sec=0)

timer = node.create_timer(1, lambda: None)
try:
assert not timer.is_canceled()
executor.spin_once(0.1)
assert timer.time_until_next_call() <= (1 * S_TO_NS)
timer.reset()
assert not timer.is_canceled()
assert timer.time_until_next_call() <= (1 * S_TO_NS)
timer.cancel()
assert timer.is_canceled()
assert timer.time_until_next_call() is None
finally:
node.destroy_timer(timer)
finally:
executor.shutdown()
finally:
node.destroy_node()
finally:
rclpy.shutdown(context=context)

0 comments on commit 53a215e

Please sign in to comment.