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
104 changes: 45 additions & 59 deletions rclpy/rclpy/clock.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,10 @@
# limitations under the License.

from types import TracebackType
from typing import Callable, Literal, Optional, overload, Type, TYPE_CHECKING, TypedDict
from typing import Callable, Optional, Type, TypedDict

from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from typing_extensions import TypeAlias
from typing_extensions import deprecated, TypeAlias

from .clock_type import ClockType
from .context import Context
Expand Down Expand Up @@ -87,7 +87,7 @@ class TimeJumpDictionary(TypedDict):

class JumpHandle:

def __init__(self, *, clock: 'Clock', threshold: JumpThreshold,
def __init__(self, *, clock: 'BaseClock', threshold: JumpThreshold,
pre_callback: Optional[JumpHandlePreCallbackType],
post_callback: Optional[Callable[[TimeJumpDictionary], None]]) -> None:
"""
Expand All @@ -106,7 +106,7 @@ def __init__(self, *, clock: 'Clock', threshold: JumpThreshold,
raise ValueError('pre_callback must be callable if given')
if post_callback is not None and not callable(post_callback):
raise ValueError('post_callback must be callable if given')
self._clock: Optional[Clock] = clock
self._clock: Optional[BaseClock] = clock
self._pre_callback = pre_callback
self._post_callback = post_callback

Expand Down Expand Up @@ -137,37 +137,13 @@ def __exit__(self, t: Optional[Type[BaseException]],
self.unregister()


class Clock:
class BaseClock:

if TYPE_CHECKING:
__clock: _rclpy.Clock
_clock_type: ClockType

@overload
def __new__(
cls,
*,
clock_type: Literal[ClockType.ROS_TIME]
) -> 'ROSClock': ...

@overload
def __new__(
cls,
*,
clock_type: ClockType = ClockType.SYSTEM_TIME
) -> 'Clock': ...

def __new__(cls, *,
clock_type: ClockType = ClockType.SYSTEM_TIME) -> 'Clock':
def __init__(self, *, clock_type: ClockType = ClockType.SYSTEM_TIME) -> None:
if not isinstance(clock_type, ClockType):
raise TypeError('Clock type must be a ClockType enum')
if clock_type is ClockType.ROS_TIME:
self: 'Clock' = super().__new__(ROSClock)
else:
self = super().__new__(cls)
self.__clock = _rclpy.Clock(clock_type.value)
self._clock_type = clock_type
return self

@property
def clock_type(self) -> ClockType:
Expand All @@ -183,7 +159,7 @@ def handle(self) -> _rclpy.Clock:
return self.__clock

def __repr__(self) -> str:
return 'Clock(clock_type={0})'.format(self.clock_type.name)
return f'{type(self).__name__}(clock_type={self.clock_type.name})'

def now(self) -> Time:
"""Return the current time of this clock."""
Expand Down Expand Up @@ -225,11 +201,41 @@ def callback_shim(jump_dict: TimeJumpDictionary) -> None:
clock=self, threshold=threshold, pre_callback=pre_callback,
post_callback=post_callback_time_jump_dictionary)

@property
def ros_time_is_active(self) -> bool:
"""
Return ``True`` if ROS time is currently active.

:raises RCLError: if the clock is not of type ``ROS_TIME``.
"""
with self.handle:
return self.handle.get_ros_time_override_is_enabled()

def _set_ros_time_is_active(self, enabled: bool) -> None:
# This is not public because it is only to be called by a TimeSource managing the Clock
with self.handle:
self.handle.set_ros_time_override_is_enabled(enabled)

def set_ros_time_override(self, time: Time) -> None:
"""
Set the next time the ROS clock will report when ROS time is active.

:raises RCLError: if the clock is not of type ``ROS_TIME``.
"""
if not isinstance(time, Time):
raise TypeError(
'Time must be specified as rclpy.time.Time. Received type: {0}'.format(type(time)))
with self.handle:
self.handle.set_ros_time_override(time._time_handle)


class Clock(BaseClock):

def sleep_until(self, until: Time, context: Optional[Context] = None) -> bool:
"""
Sleep until a specific time on this Clock is reached.

When using a ``ROSClock``, this may sleep forever if the ``TimeSource`` is misconfigured
When using ``ROS_TIME``, this may sleep forever if the ``TimeSource`` is misconfigured
and the context is never shut down.
ROS time being activated or deactivated causes this function to cease sleeping and return
``False``.
Expand Down Expand Up @@ -276,11 +282,11 @@ def on_time_jump(time_jump: TimeJump) -> None:
on_clock_change=True)
with self.create_jump_callback(threshold, post_callback=on_time_jump):
if ClockType.SYSTEM_TIME == self._clock_type:
event.wait_until_system(self.__clock, until._time_handle)
event.wait_until_system(self.handle, until._time_handle)
elif ClockType.STEADY_TIME == self._clock_type:
event.wait_until_steady(self.__clock, until._time_handle)
event.wait_until_steady(self.handle, until._time_handle)
elif ClockType.ROS_TIME == self._clock_type:
event.wait_until_ros(self.__clock, until._time_handle)
event.wait_until_ros(self.handle, until._time_handle)

if not context.ok() or time_source_changed:
return False
Expand All @@ -298,7 +304,7 @@ def sleep_for(self, rel_time: Duration, context: Optional[Context] = None) -> bo
clock.sleep_until(clock.now() + rel_time, context)


When using a ``ROSClock``, this may sleep forever if the ``TimeSource`` is misconfigured
When using a ``ROS_TIME``, this may sleep forever if the ``TimeSource`` is misconfigured
and the context is never shut down.
ROS time being activated or deactivated causes this function to cease sleeping and return
False.
Expand All @@ -313,28 +319,8 @@ def sleep_for(self, rel_time: Duration, context: Optional[Context] = None) -> bo
return self.sleep_until(self.now() + rel_time, context)


@deprecated('Use Clock(clock_type=ClockType.ROS_TIME) instead')
class ROSClock(Clock):

def __new__(cls) -> 'ROSClock':
self = super().__new__(Clock, clock_type=ClockType.ROS_TIME)
assert isinstance(self, ROSClock)
return self

@property
def ros_time_is_active(self) -> bool:
"""Return ``True`` if ROS time is currently active."""
with self.handle:
return self.handle.get_ros_time_override_is_enabled()

def _set_ros_time_is_active(self, enabled: bool) -> None:
# This is not public because it is only to be called by a TimeSource managing the Clock
with self.handle:
self.handle.set_ros_time_override_is_enabled(enabled)

def set_ros_time_override(self, time: Time) -> None:
"""Set the next time the ROS clock will report when ROS time is active."""
if not isinstance(time, Time):
raise TypeError(
'Time must be specified as rclpy.time.Time. Received type: {0}'.format(type(time)))
with self.handle:
self.handle.set_ros_time_override(time._time_handle)
def __init__(self) -> None:
super().__init__(clock_type=ClockType.ROS_TIME)
12 changes: 6 additions & 6 deletions rclpy/rclpy/impl/rcutils_logger.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
from typing import TypedDict
from typing import Union

from rclpy.clock import Clock
from rclpy.clock import BaseClock
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.impl.logging_severity import LoggingSeverity
from typing_extensions import Unpack
Expand Down Expand Up @@ -103,7 +103,7 @@ class OnceContext(RcutilsLoggerContext):

class ThrottleContext(RcutilsLoggerContext):
throttle_duration_sec: float
throttle_time_source_type: Clock
throttle_time_source_type: BaseClock
throttle_last_logged: int


Expand All @@ -114,14 +114,14 @@ class SkipFirstContext(RcutilsLoggerContext):
class LoggingFilterArgs(TypedDict, total=False):
once: bool
throttle_duration_sec: float
throttle_time_source_type: Clock
throttle_time_source_type: BaseClock
skip_first: bool


class LoggingFilterParams(TypedDict, total=False):
once: Optional[bool]
throttle_duration_sec: Optional[float]
throttle_time_source_type: Clock
throttle_time_source_type: BaseClock
skip_first: Optional[bool]


Expand Down Expand Up @@ -192,7 +192,7 @@ class Throttle(LoggingFilter):

params: ClassVar[LoggingFilterParams] = {
'throttle_duration_sec': None,
'throttle_time_source_type': Clock(),
'throttle_time_source_type': BaseClock(),
}

@classmethod
Expand All @@ -201,7 +201,7 @@ def initialize_context(cls, context: RcutilsLoggerContext,
context = cast(ThrottleContext, context)
super(Throttle, cls).initialize_context(context, **kwargs)
context['throttle_last_logged'] = 0
if not isinstance(context['throttle_time_source_type'], Clock):
if not isinstance(context['throttle_time_source_type'], BaseClock):
raise ValueError(
'Received throttle_time_source_type of "{0}" '
'is not a clock instance'
Expand Down
4 changes: 2 additions & 2 deletions rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.client import Client
from rclpy.clock import Clock
from rclpy.clock import ROSClock
from rclpy.clock_type import ClockType
from rclpy.constants import S_TO_NS
from rclpy.context import Context
from rclpy.endpoint_info import ServiceEndpointInfo, TopicEndpointInfo
Expand Down Expand Up @@ -253,7 +253,7 @@ def __init__(
self._parameter_overrides.update({p.name: p for p in parameter_overrides})

# Clock that has support for ROS time.
self._clock = ROSClock()
self._clock = Clock(clock_type=ClockType.ROS_TIME)

if automatically_declare_parameters_from_overrides:
self.declare_parameters(
Expand Down
8 changes: 4 additions & 4 deletions rclpy/rclpy/time_source.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
import weakref

from rcl_interfaces.msg import SetParametersResult
from rclpy.clock import ROSClock
from rclpy.clock import BaseClock
from rclpy.clock_type import ClockType
from rclpy.parameter import Parameter
from rclpy.qos import QoSProfile
Expand All @@ -37,7 +37,7 @@ class TimeSource:
def __init__(self, *, node: Optional['Node'] = None):
self._clock_sub: Optional['Subscription[rosgraph_msgs.msg.Clock]'] = None
self._node_weak_ref: Optional[weakref.ReferenceType['Node']] = None
self._associated_clocks: Set[ROSClock] = set()
self._associated_clocks: Set[BaseClock] = set()
# Zero time is a special value that means time is uninitialized
self._last_time_set = Time(clock_type=ClockType.ROS_TIME)
self._ros_time_is_active = False
Expand Down Expand Up @@ -112,8 +112,8 @@ def detach_node(self) -> None:
self._clock_sub = None
self._node_weak_ref = None

def attach_clock(self, clock: ROSClock) -> None:
if not isinstance(clock, ROSClock):
def attach_clock(self, clock: BaseClock) -> None:
if clock.clock_type != ClockType.ROS_TIME:
raise ValueError('Only clocks with type ROS_TIME can be attached.')

clock.set_ros_time_override(self._last_time_set)
Expand Down
Loading