Skip to content

Commit

Permalink
Creates Enum wrapper for ClockType and ClockChange (#1235)
Browse files Browse the repository at this point in the history
* Testing out Enum wrapper for ClockType

* convert to rcl_clock_type_t

* Update create_time_point

Signed-off-by: Michael Carlstrom <[email protected]>
  • Loading branch information
InvincibleRMC authored Mar 8, 2024
1 parent bd892a7 commit eaee1d2
Show file tree
Hide file tree
Showing 13 changed files with 60 additions and 23 deletions.
17 changes: 11 additions & 6 deletions rclpy/rclpy/clock.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,19 +12,24 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from enum import IntEnum
from typing import Optional

from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy

from .clock_type import ClockType
from .context import Context
from .duration import Duration
from .exceptions import NotInitializedException
from .time import Time
from .utilities import get_default_context


ClockType = _rclpy.ClockType
ClockChange = _rclpy.ClockChange
class ClockChange(IntEnum):
ROS_TIME_NO_CHANGE = _rclpy.ClockChange.ROS_TIME_NO_CHANGE
ROS_TIME_ACTIVATED = _rclpy.ClockChange.ROS_TIME_ACTIVATED
ROS_TIME_DEACTIVATED = _rclpy.ClockChange.ROS_TIME_DEACTIVATED
SYSTEM_TIME_NO_CHANGE = _rclpy.ClockChange.SYSTEM_TIME_NO_CHANGE


class JumpThreshold:
Expand Down Expand Up @@ -59,8 +64,8 @@ def __init__(self, *, min_forward: Duration, min_backward: Duration, on_clock_ch

class TimeJump:

def __init__(self, clock_change, delta):
if not isinstance(clock_change, ClockChange):
def __init__(self, clock_change: ClockChange, delta):
if not isinstance(clock_change, (ClockChange, _rclpy.ClockChange)):
raise TypeError('clock_change must be an instance of rclpy.clock.ClockChange')
self._clock_change = clock_change
self._delta = delta
Expand Down Expand Up @@ -124,8 +129,8 @@ def __exit__(self, t, v, tb):

class Clock:

def __new__(cls, *, clock_type=ClockType.SYSTEM_TIME):
if not isinstance(clock_type, ClockType):
def __new__(cls, *, clock_type: ClockType = ClockType.SYSTEM_TIME):
if not isinstance(clock_type, (ClockType, _rclpy.ClockType)):
raise TypeError('Clock type must be a ClockType enum')
if clock_type is ClockType.ROS_TIME:
self = super().__new__(ROSClock)
Expand Down
30 changes: 30 additions & 0 deletions rclpy/rclpy/clock_type.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
# Copyright 2024 Open Source Robotics Foundation, Inc.
#
# 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.

from enum import IntEnum

from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy


class ClockType(IntEnum):
"""
Enum for clock type.
This enum must match the one defined in rclpy/_rclpy_pybind11.cpp.
"""

UNINITIALIZED = _rclpy.ClockType.UNINITIALIZED
ROS_TIME = _rclpy.ClockType.ROS_TIME
SYSTEM_TIME = _rclpy.ClockType.SYSTEM_TIME
STEADY_TIME = _rclpy.ClockType.STEADY_TIME
2 changes: 1 addition & 1 deletion rclpy/rclpy/executors.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@

from rclpy.client import Client
from rclpy.clock import Clock
from rclpy.clock import ClockType
from rclpy.clock_type import ClockType
from rclpy.context import Context
from rclpy.exceptions import InvalidHandle
from rclpy.guard_condition import GuardCondition
Expand Down
9 changes: 5 additions & 4 deletions rclpy/rclpy/time.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
from rclpy.duration import Duration
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy

from .clock_type import ClockType

CONVERSION_CONSTANT = 10 ** 9

Expand All @@ -35,8 +36,8 @@ class Time:
def __init__(
self, *,
seconds=0, nanoseconds=0,
clock_type: _rclpy.ClockType = _rclpy.ClockType.SYSTEM_TIME):
if not isinstance(clock_type, _rclpy.ClockType):
clock_type: ClockType = ClockType.SYSTEM_TIME):
if not isinstance(clock_type, (ClockType, _rclpy.ClockType)):
raise TypeError('Clock type must be a ClockType enum')
if seconds < 0:
raise ValueError('Seconds value must not be negative')
Expand Down Expand Up @@ -65,7 +66,7 @@ def seconds_nanoseconds(self) -> Tuple[int, int]:
return (nanoseconds // CONVERSION_CONSTANT, nanoseconds % CONVERSION_CONSTANT)

@property
def clock_type(self) -> _rclpy.ClockType:
def clock_type(self) -> ClockType:
""":return: the type of clock that produced this instance."""
return self._time_handle.clock_type

Expand Down Expand Up @@ -157,7 +158,7 @@ def to_msg(self) -> builtin_interfaces.msg.Time:
@classmethod
def from_msg(
cls, msg: builtin_interfaces.msg.Time,
clock_type: _rclpy.ClockType = _rclpy.ClockType.ROS_TIME
clock_type: ClockType = ClockType.ROS_TIME
) -> 'Time':
"""
Create a ``Time`` instance from a ROS message.
Expand Down
2 changes: 1 addition & 1 deletion rclpy/rclpy/time_source.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
import weakref

from rcl_interfaces.msg import SetParametersResult
from rclpy.clock import ClockType
from rclpy.clock import ROSClock
from rclpy.clock_type import ClockType
from rclpy.parameter import Parameter
from rclpy.qos import QoSProfile
from rclpy.qos import ReliabilityPolicy
Expand Down
7 changes: 4 additions & 3 deletions rclpy/src/rclpy/clock.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ using pybind11::literals::operator""_a;

namespace rclpy
{
Clock::Clock(rcl_clock_type_t clock_type)
Clock::Clock(int clock_type)
{
// Create a client
rcl_clock_ = std::shared_ptr<rcl_clock_t>(
Expand All @@ -46,8 +46,9 @@ Clock::Clock(rcl_clock_type_t clock_type)
delete clock;
});

rcl_clock_type_t rcl_clock_type = rcl_clock_type_t(clock_type);
rcl_allocator_t allocator = rcl_get_default_allocator();
rcl_ret_t ret = rcl_clock_init(clock_type, rcl_clock_.get(), &allocator);
rcl_ret_t ret = rcl_clock_init(rcl_clock_type, rcl_clock_.get(), &allocator);
if (ret != RCL_RET_OK) {
throw RCLError("failed to initialize clock");
}
Expand Down Expand Up @@ -175,7 +176,7 @@ void Clock::remove_clock_callback(py::object pyjump_handle)
void define_clock(py::object module)
{
py::class_<Clock, Destroyable, std::shared_ptr<Clock>>(module, "Clock")
.def(py::init<rcl_clock_type_t>())
.def(py::init<int>())
.def_property_readonly(
"pointer", [](const Clock & clock) {
return reinterpret_cast<size_t>(clock.rcl_ptr());
Expand Down
2 changes: 1 addition & 1 deletion rclpy/src/rclpy/clock.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class Clock : public Destroyable, public std::enable_shared_from_this<Clock>
* \param[in] clock_type enum of type ClockType
* This constructor creates a Clock object
*/
explicit Clock(rcl_clock_type_t clock_type);
explicit Clock(int clock_type);

/// Returns the current value of the clock
/**
Expand Down
4 changes: 2 additions & 2 deletions rclpy/src/rclpy/time_point.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,11 +22,11 @@ namespace rclpy
{
/// Create a time point
rcl_time_point_t
create_time_point(int64_t nanoseconds, rcl_clock_type_t clock_type)
create_time_point(int64_t nanoseconds, int clock_type)
{
rcl_time_point_t time_point;
time_point.nanoseconds = nanoseconds;
time_point.clock_type = clock_type;
time_point.clock_type = rcl_clock_type_t(clock_type);
return time_point;
}

Expand Down
2 changes: 1 addition & 1 deletion rclpy/test/test_clock.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,10 @@
import pytest
import rclpy
from rclpy.clock import Clock
from rclpy.clock import ClockType
from rclpy.clock import JumpHandle
from rclpy.clock import JumpThreshold
from rclpy.clock import ROSClock
from rclpy.clock_type import ClockType
from rclpy.context import Context
from rclpy.duration import Duration
from rclpy.exceptions import NotInitializedException
Expand Down
2 changes: 1 addition & 1 deletion rclpy/test/test_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
from rcl_interfaces.msg import SetParametersResult
from rcl_interfaces.srv import GetParameters
import rclpy
from rclpy.clock import ClockType
from rclpy.clock_type import ClockType
from rclpy.duration import Duration
from rclpy.exceptions import InvalidParameterException
from rclpy.exceptions import InvalidParameterTypeException
Expand Down
2 changes: 1 addition & 1 deletion rclpy/test/test_time.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

import unittest

from rclpy.clock import ClockType
from rclpy.clock_type import ClockType
from rclpy.duration import Duration
from rclpy.duration import Infinite
from rclpy.time import Time
Expand Down
2 changes: 1 addition & 1 deletion rclpy/test/test_time_source.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,9 @@
import rclpy
from rclpy.clock import Clock
from rclpy.clock import ClockChange
from rclpy.clock import ClockType
from rclpy.clock import JumpThreshold
from rclpy.clock import ROSClock
from rclpy.clock_type import ClockType
from rclpy.duration import Duration
from rclpy.parameter import Parameter
from rclpy.time import Time
Expand Down
2 changes: 1 addition & 1 deletion rclpy/test/test_waitable.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
import rclpy
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup, ReentrantCallbackGroup
from rclpy.clock import Clock
from rclpy.clock import ClockType
from rclpy.clock_type import ClockType
from rclpy.executors import SingleThreadedExecutor
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.qos import QoSProfile
Expand Down

0 comments on commit eaee1d2

Please sign in to comment.