Skip to content

Commit 6354da5

Browse files
Do not execute the timer if call_timer() fails (#1487)
* Do not execute the timer if call_timer() fails Signed-off-by: Barry Xu <[email protected]> * Add a new exception to handle timer cancelled error Signed-off-by: Barry Xu <[email protected]> --------- Signed-off-by: Barry Xu <[email protected]>
1 parent b763ada commit 6354da5

File tree

5 files changed

+18
-4
lines changed

5 files changed

+18
-4
lines changed

rclpy/rclpy/exceptions.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@ def __init__(self, name_type: str, name: str, error_msg: str, invalid_index: int
4646

4747

4848
InvalidHandle = _rclpy.InvalidHandle
49+
TimerCancelledError = _rclpy.TimerCancelledError
4950

5051

5152
class InvalidNamespaceException(NameValidationException):

rclpy/rclpy/executors.py

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@
4141
from rclpy.clock import Clock
4242
from rclpy.clock_type import ClockType
4343
from rclpy.context import Context
44-
from rclpy.exceptions import InvalidHandle
44+
from rclpy.exceptions import InvalidHandle, TimerCancelledError
4545
from rclpy.guard_condition import GuardCondition
4646
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
4747
from rclpy.service import Service
@@ -384,8 +384,10 @@ async def _execute():
384384
except InvalidHandle:
385385
# Timer is a Destroyable, which means that on __enter__ it can throw an
386386
# InvalidHandle exception if the entity has already been destroyed. Handle that here
387-
# by just returning an empty argument, which means we will skip doing any real work
388-
# in _execute_timer below
387+
# by just returning an empty argument, which means we will skip doing any real work.
388+
pass
389+
except TimerCancelledError:
390+
# If this exception occurs when calling call_timer(), we will skip doing any real work.
389391
pass
390392

391393
return None

rclpy/src/rclpy/_rclpy_pybind11.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -118,6 +118,8 @@ PYBIND11_MODULE(_rclpy_pybind11, m) {
118118
m, "NodeNameNonExistentError", rclerror.ptr());
119119
py::register_exception<rclpy::UnsupportedEventTypeError>(
120120
m, "UnsupportedEventTypeError", rclerror.ptr());
121+
py::register_exception<rclpy::TimerCancelledError>(
122+
m, "TimerCancelledError", rclerror.ptr());
121123
py::register_exception<rclpy::NotImplementedError>(
122124
m, "NotImplementedError", PyExc_NotImplementedError);
123125
py::register_exception<rclpy::InvalidHandle>(

rclpy/src/rclpy/exceptions.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -70,6 +70,11 @@ class UnsupportedEventTypeError : public RCLError
7070
using RCLError::RCLError;
7171
};
7272

73+
class TimerCancelledError : public RCLError
74+
{
75+
using RCLError::RCLError;
76+
};
77+
7378
class NotImplementedError : public RCLError
7479
{
7580
using RCLError::RCLError;

rclpy/src/rclpy/timer.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -90,7 +90,11 @@ void Timer::call_timer()
9090
{
9191
rcl_ret_t ret = rcl_timer_call(rcl_timer_.get());
9292
if (ret != RCL_RET_OK) {
93-
throw RCLError("failed to call timer");
93+
if (ret == RCL_RET_TIMER_CANCELED) {
94+
throw TimerCancelledError("Timer has been canceled");
95+
} else {
96+
throw RCLError("failed to call timer");
97+
}
9498
}
9599
}
96100

0 commit comments

Comments
 (0)