Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions rclpy/rclpy/exceptions.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ def __init__(self, name_type: str, name: str, error_msg: str, invalid_index: int


InvalidHandle = _rclpy.InvalidHandle
TimerCancelledError = _rclpy.TimerCancelledError


class InvalidNamespaceException(NameValidationException):
Expand Down
8 changes: 5 additions & 3 deletions rclpy/rclpy/executors.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
from rclpy.clock import Clock
from rclpy.clock_type import ClockType
from rclpy.context import Context
from rclpy.exceptions import InvalidHandle
from rclpy.exceptions import InvalidHandle, TimerCancelledError
from rclpy.guard_condition import GuardCondition
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.service import Service
Expand Down Expand Up @@ -384,8 +384,10 @@ async def _execute():
except InvalidHandle:
# Timer is a Destroyable, which means that on __enter__ it can throw an
# InvalidHandle exception if the entity has already been destroyed. Handle that here
# by just returning an empty argument, which means we will skip doing any real work
# in _execute_timer below
# by just returning an empty argument, which means we will skip doing any real work.
pass
except TimerCancelledError:
# If this exception occurs when calling call_timer(), we will skip doing any real work.
pass

return None
Expand Down
2 changes: 2 additions & 0 deletions rclpy/src/rclpy/_rclpy_pybind11.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,8 @@ PYBIND11_MODULE(_rclpy_pybind11, m) {
m, "NodeNameNonExistentError", rclerror.ptr());
py::register_exception<rclpy::UnsupportedEventTypeError>(
m, "UnsupportedEventTypeError", rclerror.ptr());
py::register_exception<rclpy::TimerCancelledError>(
m, "TimerCancelledError", rclerror.ptr());
py::register_exception<rclpy::NotImplementedError>(
m, "NotImplementedError", PyExc_NotImplementedError);
py::register_exception<rclpy::InvalidHandle>(
Expand Down
5 changes: 5 additions & 0 deletions rclpy/src/rclpy/exceptions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,11 @@ class UnsupportedEventTypeError : public RCLError
using RCLError::RCLError;
};

class TimerCancelledError : public RCLError
{
using RCLError::RCLError;
};

class NotImplementedError : public RCLError
{
using RCLError::RCLError;
Expand Down
6 changes: 5 additions & 1 deletion rclpy/src/rclpy/timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,11 @@ void Timer::call_timer()
{
rcl_ret_t ret = rcl_timer_call(rcl_timer_.get());
if (ret != RCL_RET_OK) {
throw RCLError("failed to call timer");
if (ret == RCL_RET_TIMER_CANCELED) {
throw TimerCancelledError("Timer has been canceled");
} else {
throw RCLError("failed to call timer");
}
}
}

Expand Down