From 3942ac4d7e9956e32e04953e371a018a1f30cc8c Mon Sep 17 00:00:00 2001 From: dhood Date: Thu, 19 Jul 2018 14:27:34 -0700 Subject: [PATCH 01/16] Add first version of TimeSource --- rclpy/rclpy/clock.py | 19 +++++- rclpy/rclpy/time_source.py | 78 ++++++++++++++++++++++++ rclpy/src/rclpy/_rclpy.c | 105 +++++++++++++++++++++++++++++++++ rclpy/test/test_clock.py | 4 +- rclpy/test/test_time_source.py | 68 +++++++++++++++++++++ 5 files changed, 270 insertions(+), 4 deletions(-) create mode 100644 rclpy/rclpy/time_source.py create mode 100644 rclpy/test/test_time_source.py diff --git a/rclpy/rclpy/clock.py b/rclpy/rclpy/clock.py index e5f2d0d6d..b0cc5d2da 100644 --- a/rclpy/rclpy/clock.py +++ b/rclpy/rclpy/clock.py @@ -34,8 +34,6 @@ class Clock: def __init__(self, *, clock_type=ClockType.SYSTEM_TIME): if not isinstance(clock_type, ClockType): raise TypeError('Clock type must be a ClockType enum') - if clock_type is ClockType.ROS_TIME: - raise NotImplementedError self._clock_handle = _rclpy.rclpy_create_clock(clock_type) self._clock_type = clock_type @@ -43,6 +41,13 @@ def __init__(self, *, clock_type=ClockType.SYSTEM_TIME): def clock_type(self): return self._clock_type + @property + def ros_time_is_active(self): + # TODO(dhood): Move to ROS_TIME-specific subclass? + if self.clock_type != ClockType.ROS_TIME: + raise RuntimeError('Only valid for clocks using ROS_TIME') + return _rclpy.rclpy_clock_get_ros_time_override_is_enabled(self._clock_handle) + def __repr__(self): return 'Clock(clock_type={0})'.format(self.clock_type.name) @@ -53,3 +58,13 @@ def now(self): return Time( nanoseconds=_rclpy.rclpy_time_point_get_nanoseconds(time_handle), clock_type=self.clock_type) + + def set_ros_time_override(self, time): + # TODO(dhood): Move to ROS_TIME-specific subclass? + from rclpy.time import Time + if self.clock_type != ClockType.ROS_TIME: + raise RuntimeError('Only valid for clocks using ROS_TIME') + if not isinstance(time, Time): + TypeError( + 'Time must be specified as rclpy.time.Time. Received type: {0}'.format(type(time))) + _rclpy.rclpy_clock_set_ros_time_override(self._clock_handle, time._time_handle) diff --git a/rclpy/rclpy/time_source.py b/rclpy/rclpy/time_source.py new file mode 100644 index 000000000..557d36a9c --- /dev/null +++ b/rclpy/rclpy/time_source.py @@ -0,0 +1,78 @@ +# Copyright 2018 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. + +import builtin_interfaces.msg +from rclpy.clock import Clock +from rclpy.clock import ClockType +from rclpy.node import Node +from rclpy.time import Time + +CLOCK_TOPIC = '/clock' + + +class TimeSource: + + def __init__(self, *, node=None): + self._clock_sub = None + self._node = None + self._associated_clocks = [] + self._last_time_set = None + if node is not None: + self.attach_node(node) + + def attach_node(self, node): + if not isinstance(node, Node): + raise TypeError('Node must be of type rclpy.node.Node') + # Remove an existing node. + if self._node is not None: + self.detach_node() + + # Create a subscription to the clock topic using the node. + self._clock_sub = node.create_subscription( + builtin_interfaces.msg.Time, + CLOCK_TOPIC, + self.clock_callback + ) + self._node = node + + def detach_node(self): + # Remove the subscription to the clock topic. + if self._clock_sub is not None: + if self._node is None: + print('Unable to destroy previously created clock subscription') + else: + self._node.destroy_subscription(self._clock_sub) + self._clock_sub = None + self._node = None + + def attach_clock(self, clock): + if not isinstance(clock, Clock): + raise TypeError('Clock must be of type rclpy.clock.Clock') + if not clock.clock_type == ClockType.ROS_TIME: + raise ValueError('Only clocks with type ROS_TIME can be attached.') + if self._last_time_set is not None: + self._set_clock(self._last_time_set, clock) + self._associated_clocks.append(clock) + + def clock_callback(self, msg): + # Cache the last message in case a new clock is attached. + time_from_msg = Time.from_msg(msg) + self._last_time_set = time_from_msg + for clock in self._associated_clocks: + self._set_clock(time_from_msg, clock) + + def _set_clock(self, time, clock): + # TODO(dhood): clock jump notifications + # if clock.ros_time_is_active: + clock.set_ros_time_override(time) diff --git a/rclpy/src/rclpy/_rclpy.c b/rclpy/src/rclpy/_rclpy.c index 61c4dacfe..0f4f99ce9 100644 --- a/rclpy/src/rclpy/_rclpy.c +++ b/rclpy/src/rclpy/_rclpy.c @@ -3246,6 +3246,101 @@ rclpy_clock_get_now(PyObject * Py_UNUSED(self), PyObject * args) return PyCapsule_New(time_point, "rcl_time_point_t", _rclpy_destroy_time_point); } +/// Returns if a clock using ROS time has the ROS time override enabled. +/** + * On failure, an exception is raised and NULL is returned if: + * + * Raises ValueError if pyclock is not a clock capsule + * Raises RuntimeError if the clock's ROS time override state cannot be retrieved + * + * \param[in] pyclock Capsule pointing to the clock + * \return NULL on failure + * True if enabled + * False if not enabled + */ +static PyObject * +rclpy_clock_get_ros_time_override_is_enabled(PyObject * Py_UNUSED(self), PyObject * args) +{ + PyObject * pyclock; + if (!PyArg_ParseTuple(args, "O", &pyclock)) { + return NULL; + } + + rcl_clock_t * clock = (rcl_clock_t *)PyCapsule_GetPointer( + pyclock, "rcl_clock_t"); + if (!clock) { + return NULL; + } + + bool is_enabled; + rcl_ret_t ret = rcl_is_enabled_ros_time_override(clock, &is_enabled); + if (ret != RCL_RET_OK) { + PyErr_Format(PyExc_RuntimeError, + "Failed to get if ROS time override is enabled for clock: %s", rcl_get_error_string_safe()); + rcl_reset_error(); + return NULL; + } + + if (is_enabled) { + Py_RETURN_TRUE; + } else { + Py_RETURN_FALSE; + } +} + +/// Set the ROS time override for a clock using ROS time. +/** + * On failure, an exception is raised and NULL is returned if: + * + * Raises ValueError if pyclock is not a clock capsule, or + * pytime_point is not a time point capsule + * Raises RuntimeError if the clock's ROS time override cannot be set + * + * \param[in] pyclock Capsule pointing to the clock to set + * \param[in] pytime_point Capsule pointing to the time point + * \return NULL on failure + * None on success + */ +static PyObject * +rclpy_clock_set_ros_time_override(PyObject * Py_UNUSED(self), PyObject * args) +{ + PyObject * pyclock; + PyObject * pytime_point; + if (!PyArg_ParseTuple(args, "OO", &pyclock, &pytime_point)) { + return NULL; + } + + rcl_clock_t * clock = (rcl_clock_t *)PyCapsule_GetPointer( + pyclock, "rcl_clock_t"); + if (!clock) { + return NULL; + } + + rcl_time_point_t * time_point = (rcl_time_point_t *)PyCapsule_GetPointer( + pytime_point, "rcl_time_point_t"); + if (!time_point) { + return NULL; + } + + // TODO(dhood): Move to separate function + rcl_ret_t ret2 = rcl_enable_ros_time_override(clock); + if (ret2 != RCL_RET_OK) { + PyErr_Format(PyExc_RuntimeError, + "Failed to enable ROS time override for clock: %s", rcl_get_error_string_safe()); + rcl_reset_error(); + return NULL; + } + + rcl_ret_t ret = rcl_set_ros_time_override(clock, time_point->nanoseconds); + if (ret != RCL_RET_OK) { + PyErr_Format(PyExc_RuntimeError, + "Failed to set ROS time override for clock: %s", rcl_get_error_string_safe()); + rcl_reset_error(); + return NULL; + } + Py_RETURN_NONE; +} + /// Define the public methods of this module static PyMethodDef rclpy_methods[] = { { @@ -3528,6 +3623,16 @@ static PyMethodDef rclpy_methods[] = { "Get the current value of a clock." }, + { + "rclpy_clock_get_ros_time_override_is_enabled", rclpy_clock_get_ros_time_override_is_enabled, + METH_VARARGS, "Get if a clock using ROS time has the ROS time override enabled." + }, + + { + "rclpy_clock_set_ros_time_override", rclpy_clock_set_ros_time_override, METH_VARARGS, + "Set the current time of a clock using ROS time." + }, + {NULL, NULL, 0, NULL} /* sentinel */ }; diff --git a/rclpy/test/test_clock.py b/rclpy/test/test_clock.py index d234100a4..8ad325b56 100644 --- a/rclpy/test/test_clock.py +++ b/rclpy/test/test_clock.py @@ -28,8 +28,8 @@ def test_clock_construction(self): with self.assertRaises(TypeError): clock = Clock(clock_type='STEADY_TIME') - with self.assertRaises(NotImplementedError): - clock = Clock(clock_type=ClockType.ROS_TIME) + clock = Clock(clock_type=ClockType.ROS_TIME) + assert clock.clock_type == ClockType.ROS_TIME clock = Clock(clock_type=ClockType.STEADY_TIME) assert clock.clock_type == ClockType.STEADY_TIME clock = Clock(clock_type=ClockType.SYSTEM_TIME) diff --git a/rclpy/test/test_time_source.py b/rclpy/test/test_time_source.py new file mode 100644 index 000000000..bd7527d68 --- /dev/null +++ b/rclpy/test/test_time_source.py @@ -0,0 +1,68 @@ +# Copyright 2018 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. + +import time +import unittest + +import builtin_interfaces.msg +import rclpy +from rclpy.clock import Clock +from rclpy.clock import ClockType +from rclpy.time import Time +from rclpy.time_source import CLOCK_TOPIC +from rclpy.time_source import TimeSource + + +class TestTimeSource(unittest.TestCase): + + def setUp(self): + rclpy.init() + self.node = rclpy.create_node('TestTimeSource', namespace='/rclpy') + + def tearDown(self): + self.node.destroy_node() + rclpy.shutdown() + + def test_time_source_not_using_sim_time(self): + time_source = TimeSource(node=self.node) + clock = Clock(clock_type=ClockType.ROS_TIME) + time_source.attach_clock(clock) + + # When not using sim time, ROS time should look like system time + now = clock.now() + system_now = Clock(clock_type=ClockType.SYSTEM_TIME).now() + assert (system_now.nanoseconds - now.nanoseconds) < 1e9 + + def test_time_source_using_sim_time(self): + time_source = TimeSource(node=self.node) + clock = Clock(clock_type=ClockType.ROS_TIME) + time_source.attach_clock(clock) + + # When using sim time, ROS time should look like the messages received on /clock + # Receiving messages will currently cause the clock to have ROS time override enabled + # TODO(dhood): Remove the automatic use of sim time. + + # Publish to the clock topic + clock_pub = self.node.create_publisher(builtin_interfaces.msg.Time, CLOCK_TOPIC) + cycle_count = 0 + time_msg = builtin_interfaces.msg.Time() + while rclpy.ok() and cycle_count < 5: + time_msg.sec = cycle_count + clock_pub.publish(time_msg) + cycle_count += 1 + rclpy.spin_once(self.node, timeout_sec=1) + # TODO(dhood): use rate once available + time.sleep(1) + assert clock.now() > Time(seconds=0, clock_type=ClockType.ROS_TIME) + assert clock.now() <= Time(seconds=5, clock_type=ClockType.ROS_TIME) From 5451fe1fef268749ec8b8eefc6fd61b74c4dfd35 Mon Sep 17 00:00:00 2001 From: dhood Date: Thu, 19 Jul 2018 19:44:26 -0700 Subject: [PATCH 02/16] Add ability to set if ROS time override is enabled --- rclpy/rclpy/clock.py | 8 +++++ rclpy/rclpy/time_source.py | 4 +-- rclpy/src/rclpy/_rclpy.c | 58 ++++++++++++++++++++++++++++------ rclpy/test/test_time_source.py | 3 +- 4 files changed, 60 insertions(+), 13 deletions(-) diff --git a/rclpy/rclpy/clock.py b/rclpy/rclpy/clock.py index b0cc5d2da..1582cc067 100644 --- a/rclpy/rclpy/clock.py +++ b/rclpy/rclpy/clock.py @@ -48,6 +48,14 @@ def ros_time_is_active(self): raise RuntimeError('Only valid for clocks using ROS_TIME') return _rclpy.rclpy_clock_get_ros_time_override_is_enabled(self._clock_handle) + @ros_time_is_active.setter + def ros_time_is_active(self, enabled): + # TODO(dhood): Move to ROS_TIME-specific subclass? + from rclpy.time import Time + if self.clock_type != ClockType.ROS_TIME: + raise RuntimeError('Only valid for clocks using ROS_TIME') + _rclpy.rclpy_clock_set_ros_time_override_is_enabled(self._clock_handle, enabled) + def __repr__(self): return 'Clock(clock_type={0})'.format(self.clock_type.name) diff --git a/rclpy/rclpy/time_source.py b/rclpy/rclpy/time_source.py index 557d36a9c..b2d24b9ef 100644 --- a/rclpy/rclpy/time_source.py +++ b/rclpy/rclpy/time_source.py @@ -74,5 +74,5 @@ def clock_callback(self, msg): def _set_clock(self, time, clock): # TODO(dhood): clock jump notifications - # if clock.ros_time_is_active: - clock.set_ros_time_override(time) + if clock.ros_time_is_active: + clock.set_ros_time_override(time) diff --git a/rclpy/src/rclpy/_rclpy.c b/rclpy/src/rclpy/_rclpy.c index 0f4f99ce9..5f19affb9 100644 --- a/rclpy/src/rclpy/_rclpy.c +++ b/rclpy/src/rclpy/_rclpy.c @@ -3288,6 +3288,50 @@ rclpy_clock_get_ros_time_override_is_enabled(PyObject * Py_UNUSED(self), PyObjec } } +/// Set if a clock using ROS time has the ROS time override enabled. +/** + * On failure, an exception is raised and NULL is returned if: + * + * Raises ValueError if pyclock is not a clock capsule + * Raises RuntimeError if the clock's ROS time override cannot be set + * + * \param[in] pyclock Capsule pointing to the clock to set + * \param[in] enabled Override state to set + * \return NULL on failure + * None on success + */ +static PyObject * +rclpy_clock_set_ros_time_override_is_enabled(PyObject * Py_UNUSED(self), PyObject * args) +{ + PyObject * pyclock; + PyObject * pyenabled; + if (!PyArg_ParseTuple(args, "OO", &pyclock, &pyenabled)) { + return NULL; + } + + rcl_clock_t * clock = (rcl_clock_t *)PyCapsule_GetPointer( + pyclock, "rcl_clock_t"); + if (!clock) { + return NULL; + } + + bool enabled = PyObject_IsTrue(pyenabled); + + rcl_ret_t ret; + if (enabled) { + ret = rcl_enable_ros_time_override(clock); + } else { + ret = rcl_disable_ros_time_override(clock); + } + if (ret != RCL_RET_OK) { + PyErr_Format(PyExc_RuntimeError, + "Failed to set ROS time override for clock: %s", rcl_get_error_string_safe()); + rcl_reset_error(); + return NULL; + } + Py_RETURN_NONE; +} + /// Set the ROS time override for a clock using ROS time. /** * On failure, an exception is raised and NULL is returned if: @@ -3322,15 +3366,6 @@ rclpy_clock_set_ros_time_override(PyObject * Py_UNUSED(self), PyObject * args) return NULL; } - // TODO(dhood): Move to separate function - rcl_ret_t ret2 = rcl_enable_ros_time_override(clock); - if (ret2 != RCL_RET_OK) { - PyErr_Format(PyExc_RuntimeError, - "Failed to enable ROS time override for clock: %s", rcl_get_error_string_safe()); - rcl_reset_error(); - return NULL; - } - rcl_ret_t ret = rcl_set_ros_time_override(clock, time_point->nanoseconds); if (ret != RCL_RET_OK) { PyErr_Format(PyExc_RuntimeError, @@ -3628,6 +3663,11 @@ static PyMethodDef rclpy_methods[] = { METH_VARARGS, "Get if a clock using ROS time has the ROS time override enabled." }, + { + "rclpy_clock_set_ros_time_override_is_enabled", rclpy_clock_set_ros_time_override_is_enabled, + METH_VARARGS, "Set if a clock using ROS time has the ROS time override enabled." + }, + { "rclpy_clock_set_ros_time_override", rclpy_clock_set_ros_time_override, METH_VARARGS, "Set the current time of a clock using ROS time." diff --git a/rclpy/test/test_time_source.py b/rclpy/test/test_time_source.py index bd7527d68..dfcaf4ade 100644 --- a/rclpy/test/test_time_source.py +++ b/rclpy/test/test_time_source.py @@ -50,8 +50,7 @@ def test_time_source_using_sim_time(self): time_source.attach_clock(clock) # When using sim time, ROS time should look like the messages received on /clock - # Receiving messages will currently cause the clock to have ROS time override enabled - # TODO(dhood): Remove the automatic use of sim time. + clock.ros_time_is_active = True # Publish to the clock topic clock_pub = self.node.create_publisher(builtin_interfaces.msg.Time, CLOCK_TOPIC) From 3df0a7ec84b90dee559aa437f15dabff4fc0f4b9 Mon Sep 17 00:00:00 2001 From: dhood Date: Thu, 19 Jul 2018 19:47:19 -0700 Subject: [PATCH 03/16] Publisher on /clock shouldn't affect non-sim-time clock --- rclpy/test/test_time_source.py | 30 +++++++++++++++++++----------- 1 file changed, 19 insertions(+), 11 deletions(-) diff --git a/rclpy/test/test_time_source.py b/rclpy/test/test_time_source.py index dfcaf4ade..dfef2f0df 100644 --- a/rclpy/test/test_time_source.py +++ b/rclpy/test/test_time_source.py @@ -34,6 +34,18 @@ def tearDown(self): self.node.destroy_node() rclpy.shutdown() + def publish_clock_messages(self): + clock_pub = self.node.create_publisher(builtin_interfaces.msg.Time, CLOCK_TOPIC) + cycle_count = 0 + time_msg = builtin_interfaces.msg.Time() + while rclpy.ok() and cycle_count < 5: + time_msg.sec = cycle_count + clock_pub.publish(time_msg) + cycle_count += 1 + rclpy.spin_once(self.node, timeout_sec=1) + # TODO(dhood): use rate once available + time.sleep(1) + def test_time_source_not_using_sim_time(self): time_source = TimeSource(node=self.node) clock = Clock(clock_type=ClockType.ROS_TIME) @@ -44,6 +56,12 @@ def test_time_source_not_using_sim_time(self): system_now = Clock(clock_type=ClockType.SYSTEM_TIME).now() assert (system_now.nanoseconds - now.nanoseconds) < 1e9 + # Presence of clock publisher should not affect the clock + self.publish_clock_messages() + now = clock.now() + system_now = Clock(clock_type=ClockType.SYSTEM_TIME).now() + assert (system_now.nanoseconds - now.nanoseconds) < 1e9 + def test_time_source_using_sim_time(self): time_source = TimeSource(node=self.node) clock = Clock(clock_type=ClockType.ROS_TIME) @@ -52,16 +70,6 @@ def test_time_source_using_sim_time(self): # When using sim time, ROS time should look like the messages received on /clock clock.ros_time_is_active = True - # Publish to the clock topic - clock_pub = self.node.create_publisher(builtin_interfaces.msg.Time, CLOCK_TOPIC) - cycle_count = 0 - time_msg = builtin_interfaces.msg.Time() - while rclpy.ok() and cycle_count < 5: - time_msg.sec = cycle_count - clock_pub.publish(time_msg) - cycle_count += 1 - rclpy.spin_once(self.node, timeout_sec=1) - # TODO(dhood): use rate once available - time.sleep(1) + self.publish_clock_messages() assert clock.now() > Time(seconds=0, clock_type=ClockType.ROS_TIME) assert clock.now() <= Time(seconds=5, clock_type=ClockType.ROS_TIME) From d64dba008e6e25ebce872551c1f858cb9653679e Mon Sep 17 00:00:00 2001 From: dhood Date: Thu, 19 Jul 2018 20:32:32 -0700 Subject: [PATCH 04/16] Test custom getter/setter for ROS time is enabled --- rclpy/rclpy/clock.py | 1 - rclpy/test/test_time_source.py | 5 ++++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/rclpy/rclpy/clock.py b/rclpy/rclpy/clock.py index 1582cc067..566860bb6 100644 --- a/rclpy/rclpy/clock.py +++ b/rclpy/rclpy/clock.py @@ -51,7 +51,6 @@ def ros_time_is_active(self): @ros_time_is_active.setter def ros_time_is_active(self, enabled): # TODO(dhood): Move to ROS_TIME-specific subclass? - from rclpy.time import Time if self.clock_type != ClockType.ROS_TIME: raise RuntimeError('Only valid for clocks using ROS_TIME') _rclpy.rclpy_clock_set_ros_time_override_is_enabled(self._clock_handle, enabled) diff --git a/rclpy/test/test_time_source.py b/rclpy/test/test_time_source.py index dfef2f0df..1bf93ab21 100644 --- a/rclpy/test/test_time_source.py +++ b/rclpy/test/test_time_source.py @@ -50,6 +50,7 @@ def test_time_source_not_using_sim_time(self): time_source = TimeSource(node=self.node) clock = Clock(clock_type=ClockType.ROS_TIME) time_source.attach_clock(clock) + self.assertFalse(clock.ros_time_is_active) # When not using sim time, ROS time should look like system time now = clock.now() @@ -67,9 +68,11 @@ def test_time_source_using_sim_time(self): clock = Clock(clock_type=ClockType.ROS_TIME) time_source.attach_clock(clock) - # When using sim time, ROS time should look like the messages received on /clock + # Check attribute getting/setting clock.ros_time_is_active = True + self.assertTrue(clock.ros_time_is_active) + # When using sim time, ROS time should look like the messages received on /clock self.publish_clock_messages() assert clock.now() > Time(seconds=0, clock_type=ClockType.ROS_TIME) assert clock.now() <= Time(seconds=5, clock_type=ClockType.ROS_TIME) From 0670f5b2de13eafbc18bb242fa726c407063c8d3 Mon Sep 17 00:00:00 2001 From: dhood Date: Fri, 20 Jul 2018 03:22:37 -0700 Subject: [PATCH 05/16] Give node a clock with ROS time --- rclpy/rclpy/node.py | 11 +++++++++++ rclpy/rclpy/time_source.py | 2 +- rclpy/test/test_node.py | 2 ++ 3 files changed, 14 insertions(+), 1 deletion(-) diff --git a/rclpy/rclpy/node.py b/rclpy/rclpy/node.py index fbf1c0d92..d58fcd535 100644 --- a/rclpy/rclpy/node.py +++ b/rclpy/rclpy/node.py @@ -14,6 +14,8 @@ from rclpy.callback_groups import MutuallyExclusiveCallbackGroup from rclpy.client import Client +from rclpy.clock import Clock +from rclpy.clock import ClockType from rclpy.constants import S_TO_NS from rclpy.exceptions import NotInitializedException from rclpy.exceptions import NoTypeSupportImportedException @@ -25,6 +27,7 @@ from rclpy.qos import qos_profile_default, qos_profile_services_default from rclpy.service import Service from rclpy.subscription import Subscription +from rclpy.time_source import TimeSource from rclpy.timer import WallTimer from rclpy.utilities import ok from rclpy.validate_full_topic_name import validate_full_topic_name @@ -80,6 +83,11 @@ def __init__(self, node_name, *, cli_args=None, namespace=None, use_global_argum raise RuntimeError('rclpy_create_node failed for unknown reason') self._logger = get_logger(_rclpy.rclpy_get_node_logger_name(self.handle)) + # Clock that has support for ROS time (uses sim time if parameter has been set on the node) + self._clock = Clock(clock_type=ClockType.ROS_TIME) + self._time_source = TimeSource(node=self) + self._time_source.attach_clock(self._clock) + @property def handle(self): return self._handle @@ -94,6 +102,9 @@ def get_name(self): def get_namespace(self): return _rclpy.rclpy_get_node_namespace(self.handle) + def get_clock(self): + return self._clock + def get_logger(self): return self._logger diff --git a/rclpy/rclpy/time_source.py b/rclpy/rclpy/time_source.py index b2d24b9ef..0c63d868a 100644 --- a/rclpy/rclpy/time_source.py +++ b/rclpy/rclpy/time_source.py @@ -15,7 +15,6 @@ import builtin_interfaces.msg from rclpy.clock import Clock from rclpy.clock import ClockType -from rclpy.node import Node from rclpy.time import Time CLOCK_TOPIC = '/clock' @@ -32,6 +31,7 @@ def __init__(self, *, node=None): self.attach_node(node) def attach_node(self, node): + from rclpy.node import Node if not isinstance(node, Node): raise TypeError('Node must be of type rclpy.node.Node') # Remove an existing node. diff --git a/rclpy/test/test_node.py b/rclpy/test/test_node.py index 4271c2499..0b4a55b32 100644 --- a/rclpy/test/test_node.py +++ b/rclpy/test/test_node.py @@ -16,6 +16,7 @@ from rcl_interfaces.srv import GetParameters import rclpy +from rclpy.clock import ClockType from rclpy.exceptions import InvalidServiceNameException from rclpy.exceptions import InvalidTopicNameException from test_msgs.msg import Primitives @@ -42,6 +43,7 @@ def test_accessors(self): self.node.handle = 'garbage' self.assertEqual(self.node.get_name(), TEST_NODE) self.assertEqual(self.node.get_namespace(), TEST_NAMESPACE) + self.assertEqual(self.node.get_clock().clock_type, ClockType.ROS_TIME) def test_create_publisher(self): self.node.create_publisher(Primitives, 'chatter') From df7bca9337e0098716d699e956cdd25c10a199fb Mon Sep 17 00:00:00 2001 From: dhood Date: Mon, 30 Jul 2018 12:49:04 -0700 Subject: [PATCH 06/16] Set clock's use of sim time from time source's use --- rclpy/rclpy/time_source.py | 31 ++++++++++++++++++++++--------- rclpy/test/test_time_source.py | 19 ++++++++++++++++--- 2 files changed, 38 insertions(+), 12 deletions(-) diff --git a/rclpy/rclpy/time_source.py b/rclpy/rclpy/time_source.py index 0c63d868a..c8a42f23c 100644 --- a/rclpy/rclpy/time_source.py +++ b/rclpy/rclpy/time_source.py @@ -27,9 +27,28 @@ def __init__(self, *, node=None): self._node = None self._associated_clocks = [] self._last_time_set = None + self._ros_time_is_active = False if node is not None: self.attach_node(node) + @property + def ros_time_is_active(self): + return self._ros_time_is_active + + @ros_time_is_active.setter + def ros_time_is_active(self, enabled): + self._ros_time_is_active = enabled + for clock in self._associated_clocks: + clock.ros_time_is_active = True + + def _subscribe_to_clock_topic(self): + if self._clock_sub is not None and self._node is not None: + self._clock_sub = self._node.create_subscription( + builtin_interfaces.msg.Time, + CLOCK_TOPIC, + self.clock_callback + ) + def attach_node(self, node): from rclpy.node import Node if not isinstance(node, Node): @@ -37,14 +56,8 @@ def attach_node(self, node): # Remove an existing node. if self._node is not None: self.detach_node() - - # Create a subscription to the clock topic using the node. - self._clock_sub = node.create_subscription( - builtin_interfaces.msg.Time, - CLOCK_TOPIC, - self.clock_callback - ) self._node = node + self._subscribe_to_clock_topic() def detach_node(self): # Remove the subscription to the clock topic. @@ -63,6 +76,7 @@ def attach_clock(self, clock): raise ValueError('Only clocks with type ROS_TIME can be attached.') if self._last_time_set is not None: self._set_clock(self._last_time_set, clock) + clock.ros_time_is_active = self.ros_time_is_active self._associated_clocks.append(clock) def clock_callback(self, msg): @@ -74,5 +88,4 @@ def clock_callback(self, msg): def _set_clock(self, time, clock): # TODO(dhood): clock jump notifications - if clock.ros_time_is_active: - clock.set_ros_time_override(time) + clock.set_ros_time_override(time) diff --git a/rclpy/test/test_time_source.py b/rclpy/test/test_time_source.py index 1bf93ab21..8c80e1ce1 100644 --- a/rclpy/test/test_time_source.py +++ b/rclpy/test/test_time_source.py @@ -50,7 +50,6 @@ def test_time_source_not_using_sim_time(self): time_source = TimeSource(node=self.node) clock = Clock(clock_type=ClockType.ROS_TIME) time_source.attach_clock(clock) - self.assertFalse(clock.ros_time_is_active) # When not using sim time, ROS time should look like system time now = clock.now() @@ -59,17 +58,31 @@ def test_time_source_not_using_sim_time(self): # Presence of clock publisher should not affect the clock self.publish_clock_messages() + self.assertFalse(clock.ros_time_is_active) now = clock.now() system_now = Clock(clock_type=ClockType.SYSTEM_TIME).now() assert (system_now.nanoseconds - now.nanoseconds) < 1e9 + # Whether or not an attached clock is using ROS time should be determined by the time + # source managing it. + self.assertFalse(time_source.ros_time_is_active) + clock2 = Clock(clock_type=ClockType.ROS_TIME) + clock2.ros_time_is_active = True + time_source.attach_clock(clock2) + self.assertFalse(clock2.ros_time_is_active) + + def test_time_source_using_sim_time(self): time_source = TimeSource(node=self.node) clock = Clock(clock_type=ClockType.ROS_TIME) time_source.attach_clock(clock) - # Check attribute getting/setting - clock.ros_time_is_active = True + # Setting ROS time active on a time source should also cause attached clocks' use of ROS + # time to be set to active. + self.assertFalse(time_source.ros_time_is_active) + self.assertFalse(clock.ros_time_is_active) + time_source.ros_time_is_active = True + self.assertTrue(time_source.ros_time_is_active) self.assertTrue(clock.ros_time_is_active) # When using sim time, ROS time should look like the messages received on /clock From be9aaca49c17a64bb52790eef5ce8eb2a9f10d7c Mon Sep 17 00:00:00 2001 From: dhood Date: Mon, 30 Jul 2018 13:35:05 -0700 Subject: [PATCH 07/16] Make setting of Clock's use of ROS time private --- rclpy/rclpy/clock.py | 4 ++-- rclpy/rclpy/time_source.py | 4 ++-- rclpy/test/test_time_source.py | 3 +-- 3 files changed, 5 insertions(+), 6 deletions(-) diff --git a/rclpy/rclpy/clock.py b/rclpy/rclpy/clock.py index 566860bb6..243bd1c99 100644 --- a/rclpy/rclpy/clock.py +++ b/rclpy/rclpy/clock.py @@ -48,8 +48,8 @@ def ros_time_is_active(self): raise RuntimeError('Only valid for clocks using ROS_TIME') return _rclpy.rclpy_clock_get_ros_time_override_is_enabled(self._clock_handle) - @ros_time_is_active.setter - def ros_time_is_active(self, enabled): + def _set_ros_time_is_active(self, enabled): + # This is not public because it is only to be called by a TimeSource managing the Clock # TODO(dhood): Move to ROS_TIME-specific subclass? if self.clock_type != ClockType.ROS_TIME: raise RuntimeError('Only valid for clocks using ROS_TIME') diff --git a/rclpy/rclpy/time_source.py b/rclpy/rclpy/time_source.py index c8a42f23c..b53585045 100644 --- a/rclpy/rclpy/time_source.py +++ b/rclpy/rclpy/time_source.py @@ -39,7 +39,7 @@ def ros_time_is_active(self): def ros_time_is_active(self, enabled): self._ros_time_is_active = enabled for clock in self._associated_clocks: - clock.ros_time_is_active = True + clock._set_ros_time_is_active(True) def _subscribe_to_clock_topic(self): if self._clock_sub is not None and self._node is not None: @@ -76,7 +76,7 @@ def attach_clock(self, clock): raise ValueError('Only clocks with type ROS_TIME can be attached.') if self._last_time_set is not None: self._set_clock(self._last_time_set, clock) - clock.ros_time_is_active = self.ros_time_is_active + clock._set_ros_time_is_active(self.ros_time_is_active) self._associated_clocks.append(clock) def clock_callback(self, msg): diff --git a/rclpy/test/test_time_source.py b/rclpy/test/test_time_source.py index 8c80e1ce1..f1b738765 100644 --- a/rclpy/test/test_time_source.py +++ b/rclpy/test/test_time_source.py @@ -67,10 +67,9 @@ def test_time_source_not_using_sim_time(self): # source managing it. self.assertFalse(time_source.ros_time_is_active) clock2 = Clock(clock_type=ClockType.ROS_TIME) - clock2.ros_time_is_active = True + clock2._set_ros_time_is_active(True) time_source.attach_clock(clock2) self.assertFalse(clock2.ros_time_is_active) - def test_time_source_using_sim_time(self): time_source = TimeSource(node=self.node) From 5789eb58ffb3870c931cb36dd3e15cf25b594c1a Mon Sep 17 00:00:00 2001 From: dhood Date: Mon, 30 Jul 2018 16:04:49 -0700 Subject: [PATCH 08/16] Only subscribe to clock topic if ROS time is active --- rclpy/rclpy/time_source.py | 9 ++++++--- rclpy/test/test_time_source.py | 4 ++++ 2 files changed, 10 insertions(+), 3 deletions(-) diff --git a/rclpy/rclpy/time_source.py b/rclpy/rclpy/time_source.py index b53585045..9d53e2ae6 100644 --- a/rclpy/rclpy/time_source.py +++ b/rclpy/rclpy/time_source.py @@ -39,10 +39,12 @@ def ros_time_is_active(self): def ros_time_is_active(self, enabled): self._ros_time_is_active = enabled for clock in self._associated_clocks: - clock._set_ros_time_is_active(True) + clock._set_ros_time_is_active(enabled) + if enabled: + self._subscribe_to_clock_topic() def _subscribe_to_clock_topic(self): - if self._clock_sub is not None and self._node is not None: + if self._clock_sub is None and self._node is not None: self._clock_sub = self._node.create_subscription( builtin_interfaces.msg.Time, CLOCK_TOPIC, @@ -57,7 +59,8 @@ def attach_node(self, node): if self._node is not None: self.detach_node() self._node = node - self._subscribe_to_clock_topic() + if self.ros_time_is_active: + self._subscribe_to_clock_topic() def detach_node(self): # Remove the subscription to the clock topic. diff --git a/rclpy/test/test_time_source.py b/rclpy/test/test_time_source.py index f1b738765..14210b6f0 100644 --- a/rclpy/test/test_time_source.py +++ b/rclpy/test/test_time_source.py @@ -70,6 +70,7 @@ def test_time_source_not_using_sim_time(self): clock2._set_ros_time_is_active(True) time_source.attach_clock(clock2) self.assertFalse(clock2.ros_time_is_active) + assert time_source._clock_sub is None def test_time_source_using_sim_time(self): time_source = TimeSource(node=self.node) @@ -84,6 +85,9 @@ def test_time_source_using_sim_time(self): self.assertTrue(time_source.ros_time_is_active) self.assertTrue(clock.ros_time_is_active) + # A subscriber should have been created + assert time_source._clock_sub is not None + # When using sim time, ROS time should look like the messages received on /clock self.publish_clock_messages() assert clock.now() > Time(seconds=0, clock_type=ClockType.ROS_TIME) From a835e8b8a94e38668634b3596bef0112176ca867 Mon Sep 17 00:00:00 2001 From: dhood Date: Mon, 30 Jul 2018 16:21:52 -0700 Subject: [PATCH 09/16] More tests --- rclpy/test/test_time_source.py | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/rclpy/test/test_time_source.py b/rclpy/test/test_time_source.py index 14210b6f0..7f04ab3f6 100644 --- a/rclpy/test/test_time_source.py +++ b/rclpy/test/test_time_source.py @@ -92,3 +92,17 @@ def test_time_source_using_sim_time(self): self.publish_clock_messages() assert clock.now() > Time(seconds=0, clock_type=ClockType.ROS_TIME) assert clock.now() <= Time(seconds=5, clock_type=ClockType.ROS_TIME) + + # Check that attached clocks get the cached message + clock2 = Clock(clock_type=ClockType.ROS_TIME) + time_source.attach_clock(clock2) + assert clock2.now() > Time(seconds=0, clock_type=ClockType.ROS_TIME) + assert clock2.now() <= Time(seconds=5, clock_type=ClockType.ROS_TIME) + + # Check detaching the node + time_source.detach_node() + node2 = rclpy.create_node('TestTimeSource2', namespace='/rclpy') + time_source.attach_node(node2) + node2.destroy_node() + assert time_source._node == node2 + assert time_source._clock_sub is not None From 69a98cab46ef8e0a20c1fc8950d2e99d15fc0695 Mon Sep 17 00:00:00 2001 From: dhood Date: Mon, 30 Jul 2018 16:27:44 -0700 Subject: [PATCH 10/16] Error if the _node has been removed but not sub --- rclpy/rclpy/time_source.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/rclpy/rclpy/time_source.py b/rclpy/rclpy/time_source.py index 9d53e2ae6..748fb6fb7 100644 --- a/rclpy/rclpy/time_source.py +++ b/rclpy/rclpy/time_source.py @@ -66,9 +66,8 @@ def detach_node(self): # Remove the subscription to the clock topic. if self._clock_sub is not None: if self._node is None: - print('Unable to destroy previously created clock subscription') - else: - self._node.destroy_subscription(self._clock_sub) + raise RuntimeError('Unable to destroy previously created clock subscription') + self._node.destroy_subscription(self._clock_sub) self._clock_sub = None self._node = None From c1b59b5dd64c3c283615a45eed5c655d72d917ea Mon Sep 17 00:00:00 2001 From: dhood Date: Mon, 30 Jul 2018 17:03:28 -0700 Subject: [PATCH 11/16] Create ROSClock specialization --- rclpy/rclpy/clock.py | 31 +++++++++++++++++-------------- rclpy/rclpy/node.py | 8 ++++---- rclpy/rclpy/time_source.py | 3 +++ rclpy/test/test_time_source.py | 24 +++++++++++++++++++++--- 4 files changed, 45 insertions(+), 21 deletions(-) diff --git a/rclpy/rclpy/clock.py b/rclpy/rclpy/clock.py index 243bd1c99..53c3e31a4 100644 --- a/rclpy/rclpy/clock.py +++ b/rclpy/rclpy/clock.py @@ -41,33 +41,36 @@ def __init__(self, *, clock_type=ClockType.SYSTEM_TIME): def clock_type(self): return self._clock_type + def __repr__(self): + return 'Clock(clock_type={0})'.format(self.clock_type.name) + + def now(self): + from rclpy.time import Time + time_handle = _rclpy.rclpy_clock_get_now(self._clock_handle) + # TODO(dhood): Return a python object from the C extension + return Time( + nanoseconds=_rclpy.rclpy_time_point_get_nanoseconds(time_handle), + clock_type=self.clock_type) + + +class ROSClock(Clock): + + def __init__(self): + super(ROSClock, self).__init__(clock_type=ClockType.ROS_TIME) + @property def ros_time_is_active(self): - # TODO(dhood): Move to ROS_TIME-specific subclass? if self.clock_type != ClockType.ROS_TIME: raise RuntimeError('Only valid for clocks using ROS_TIME') return _rclpy.rclpy_clock_get_ros_time_override_is_enabled(self._clock_handle) def _set_ros_time_is_active(self, enabled): # This is not public because it is only to be called by a TimeSource managing the Clock - # TODO(dhood): Move to ROS_TIME-specific subclass? if self.clock_type != ClockType.ROS_TIME: raise RuntimeError('Only valid for clocks using ROS_TIME') _rclpy.rclpy_clock_set_ros_time_override_is_enabled(self._clock_handle, enabled) - def __repr__(self): - return 'Clock(clock_type={0})'.format(self.clock_type.name) - - def now(self): - from rclpy.time import Time - time_handle = _rclpy.rclpy_clock_get_now(self._clock_handle) - # TODO(dhood): Return a python object from the C extension - return Time( - nanoseconds=_rclpy.rclpy_time_point_get_nanoseconds(time_handle), - clock_type=self.clock_type) - def set_ros_time_override(self, time): - # TODO(dhood): Move to ROS_TIME-specific subclass? from rclpy.time import Time if self.clock_type != ClockType.ROS_TIME: raise RuntimeError('Only valid for clocks using ROS_TIME') diff --git a/rclpy/rclpy/node.py b/rclpy/rclpy/node.py index d58fcd535..e8b8998a1 100644 --- a/rclpy/rclpy/node.py +++ b/rclpy/rclpy/node.py @@ -14,8 +14,7 @@ from rclpy.callback_groups import MutuallyExclusiveCallbackGroup from rclpy.client import Client -from rclpy.clock import Clock -from rclpy.clock import ClockType +from rclpy.clock import ROSClock from rclpy.constants import S_TO_NS from rclpy.exceptions import NotInitializedException from rclpy.exceptions import NoTypeSupportImportedException @@ -83,8 +82,9 @@ def __init__(self, node_name, *, cli_args=None, namespace=None, use_global_argum raise RuntimeError('rclpy_create_node failed for unknown reason') self._logger = get_logger(_rclpy.rclpy_get_node_logger_name(self.handle)) - # Clock that has support for ROS time (uses sim time if parameter has been set on the node) - self._clock = Clock(clock_type=ClockType.ROS_TIME) + # Clock that has support for ROS time. + # TODO(dhood): use sim time if parameter has been set on the node. + self._clock = ROSClock() self._time_source = TimeSource(node=self) self._time_source.attach_clock(self._clock) diff --git a/rclpy/rclpy/time_source.py b/rclpy/rclpy/time_source.py index 748fb6fb7..94c1d5473 100644 --- a/rclpy/rclpy/time_source.py +++ b/rclpy/rclpy/time_source.py @@ -15,6 +15,7 @@ import builtin_interfaces.msg from rclpy.clock import Clock from rclpy.clock import ClockType +from rclpy.clock import ROSClock from rclpy.time import Time CLOCK_TOPIC = '/clock' @@ -76,6 +77,8 @@ def attach_clock(self, clock): raise TypeError('Clock must be of type rclpy.clock.Clock') if not clock.clock_type == ClockType.ROS_TIME: raise ValueError('Only clocks with type ROS_TIME can be attached.') + # "Cast" to ROSClock subclass so ROS time methods can be used. + clock.__class__ = ROSClock if self._last_time_set is not None: self._set_clock(self._last_time_set, clock) clock._set_ros_time_is_active(self.ros_time_is_active) diff --git a/rclpy/test/test_time_source.py b/rclpy/test/test_time_source.py index 7f04ab3f6..b1baadf41 100644 --- a/rclpy/test/test_time_source.py +++ b/rclpy/test/test_time_source.py @@ -19,6 +19,7 @@ import rclpy from rclpy.clock import Clock from rclpy.clock import ClockType +from rclpy.clock import ROSClock from rclpy.time import Time from rclpy.time_source import CLOCK_TOPIC from rclpy.time_source import TimeSource @@ -46,9 +47,26 @@ def publish_clock_messages(self): # TODO(dhood): use rate once available time.sleep(1) + def test_time_source_attach_clock(self): + time_source = TimeSource(node=self.node) + + # ROSClock is a specialization of Clock with ROS time methods. + time_source.attach_clock(ROSClock()) + + # A clock of type ROS_TIME can be attached. It will be converted to a ROSClock for storage. + time_source.attach_clock(Clock(clock_type=ClockType.ROS_TIME)) + + assert all((isinstance(clock, ROSClock) for clock in time_source._associated_clocks)) + + with self.assertRaises(ValueError): + time_source.attach_clock(Clock(clock_type=ClockType.SYSTEM_TIME)) + + with self.assertRaises(ValueError): + time_source.attach_clock(Clock(clock_type=ClockType.STEADY_TIME)) + def test_time_source_not_using_sim_time(self): time_source = TimeSource(node=self.node) - clock = Clock(clock_type=ClockType.ROS_TIME) + clock = ROSClock() time_source.attach_clock(clock) # When not using sim time, ROS time should look like system time @@ -66,7 +84,7 @@ def test_time_source_not_using_sim_time(self): # Whether or not an attached clock is using ROS time should be determined by the time # source managing it. self.assertFalse(time_source.ros_time_is_active) - clock2 = Clock(clock_type=ClockType.ROS_TIME) + clock2 = ROSClock() clock2._set_ros_time_is_active(True) time_source.attach_clock(clock2) self.assertFalse(clock2.ros_time_is_active) @@ -74,7 +92,7 @@ def test_time_source_not_using_sim_time(self): def test_time_source_using_sim_time(self): time_source = TimeSource(node=self.node) - clock = Clock(clock_type=ClockType.ROS_TIME) + clock = ROSClock() time_source.attach_clock(clock) # Setting ROS time active on a time source should also cause attached clocks' use of ROS From cb6245cb5dae5575849be5eabff8215d974cecf2 Mon Sep 17 00:00:00 2001 From: dhood Date: Mon, 30 Jul 2018 17:09:14 -0700 Subject: [PATCH 12/16] Remove checks for clock type of ROS_TIME in ROSClock --- rclpy/rclpy/clock.py | 6 ------ 1 file changed, 6 deletions(-) diff --git a/rclpy/rclpy/clock.py b/rclpy/rclpy/clock.py index 53c3e31a4..a1299b75e 100644 --- a/rclpy/rclpy/clock.py +++ b/rclpy/rclpy/clock.py @@ -60,20 +60,14 @@ def __init__(self): @property def ros_time_is_active(self): - if self.clock_type != ClockType.ROS_TIME: - raise RuntimeError('Only valid for clocks using ROS_TIME') return _rclpy.rclpy_clock_get_ros_time_override_is_enabled(self._clock_handle) def _set_ros_time_is_active(self, enabled): # This is not public because it is only to be called by a TimeSource managing the Clock - if self.clock_type != ClockType.ROS_TIME: - raise RuntimeError('Only valid for clocks using ROS_TIME') _rclpy.rclpy_clock_set_ros_time_override_is_enabled(self._clock_handle, enabled) def set_ros_time_override(self, time): from rclpy.time import Time - if self.clock_type != ClockType.ROS_TIME: - raise RuntimeError('Only valid for clocks using ROS_TIME') if not isinstance(time, Time): TypeError( 'Time must be specified as rclpy.time.Time. Received type: {0}'.format(type(time))) From 6a9d42b019f9ab533b6515f218ec75a6d97ca2d1 Mon Sep 17 00:00:00 2001 From: dhood Date: Thu, 2 Aug 2018 18:12:26 -0700 Subject: [PATCH 13/16] Parse predicate instead of using PyObject_IsTrue --- rclpy/src/rclpy/_rclpy.c | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/rclpy/src/rclpy/_rclpy.c b/rclpy/src/rclpy/_rclpy.c index 5f19affb9..c75a36a34 100644 --- a/rclpy/src/rclpy/_rclpy.c +++ b/rclpy/src/rclpy/_rclpy.c @@ -3304,8 +3304,8 @@ static PyObject * rclpy_clock_set_ros_time_override_is_enabled(PyObject * Py_UNUSED(self), PyObject * args) { PyObject * pyclock; - PyObject * pyenabled; - if (!PyArg_ParseTuple(args, "OO", &pyclock, &pyenabled)) { + bool enabled; + if (!PyArg_ParseTuple(args, "Op", &pyclock, &enabled)) { return NULL; } @@ -3315,8 +3315,6 @@ rclpy_clock_set_ros_time_override_is_enabled(PyObject * Py_UNUSED(self), PyObjec return NULL; } - bool enabled = PyObject_IsTrue(pyenabled); - rcl_ret_t ret; if (enabled) { ret = rcl_enable_ros_time_override(clock); From 9992b1f224570c9f18f5ed26156e457602a267fb Mon Sep 17 00:00:00 2001 From: dhood Date: Thu, 2 Aug 2018 18:41:26 -0700 Subject: [PATCH 14/16] Return a ROSClock from Clock constructor if appropriate --- rclpy/rclpy/clock.py | 10 ++++++---- rclpy/rclpy/time_source.py | 8 +------- rclpy/test/test_clock.py | 7 +++++-- rclpy/test/test_time_source.py | 6 +----- 4 files changed, 13 insertions(+), 18 deletions(-) diff --git a/rclpy/rclpy/clock.py b/rclpy/rclpy/clock.py index a1299b75e..a89b080d8 100644 --- a/rclpy/rclpy/clock.py +++ b/rclpy/rclpy/clock.py @@ -31,11 +31,16 @@ class ClockType(IntEnum): class Clock: - def __init__(self, *, clock_type=ClockType.SYSTEM_TIME): + def __new__(cls, *, clock_type=ClockType.SYSTEM_TIME): if not isinstance(clock_type, ClockType): raise TypeError('Clock type must be a ClockType enum') + if clock_type is ClockType.ROS_TIME: + self = super().__new__(ROSClock) + else: + self = super().__new__(cls) self._clock_handle = _rclpy.rclpy_create_clock(clock_type) self._clock_type = clock_type + return self @property def clock_type(self): @@ -55,9 +60,6 @@ def now(self): class ROSClock(Clock): - def __init__(self): - super(ROSClock, self).__init__(clock_type=ClockType.ROS_TIME) - @property def ros_time_is_active(self): return _rclpy.rclpy_clock_get_ros_time_override_is_enabled(self._clock_handle) diff --git a/rclpy/rclpy/time_source.py b/rclpy/rclpy/time_source.py index 94c1d5473..9eb9a4a15 100644 --- a/rclpy/rclpy/time_source.py +++ b/rclpy/rclpy/time_source.py @@ -13,8 +13,6 @@ # limitations under the License. import builtin_interfaces.msg -from rclpy.clock import Clock -from rclpy.clock import ClockType from rclpy.clock import ROSClock from rclpy.time import Time @@ -73,12 +71,8 @@ def detach_node(self): self._node = None def attach_clock(self, clock): - if not isinstance(clock, Clock): - raise TypeError('Clock must be of type rclpy.clock.Clock') - if not clock.clock_type == ClockType.ROS_TIME: + if not isinstance(clock, ROSClock): raise ValueError('Only clocks with type ROS_TIME can be attached.') - # "Cast" to ROSClock subclass so ROS time methods can be used. - clock.__class__ = ROSClock if self._last_time_set is not None: self._set_clock(self._last_time_set, clock) clock._set_ros_time_is_active(self.ros_time_is_active) diff --git a/rclpy/test/test_clock.py b/rclpy/test/test_clock.py index 8ad325b56..c8d39198e 100644 --- a/rclpy/test/test_clock.py +++ b/rclpy/test/test_clock.py @@ -17,6 +17,7 @@ from rclpy.clock import Clock from rclpy.clock import ClockType +from rclpy.clock import ROSClock from rclpy.time import Time @@ -28,12 +29,14 @@ def test_clock_construction(self): with self.assertRaises(TypeError): clock = Clock(clock_type='STEADY_TIME') - clock = Clock(clock_type=ClockType.ROS_TIME) - assert clock.clock_type == ClockType.ROS_TIME clock = Clock(clock_type=ClockType.STEADY_TIME) assert clock.clock_type == ClockType.STEADY_TIME clock = Clock(clock_type=ClockType.SYSTEM_TIME) assert clock.clock_type == ClockType.SYSTEM_TIME + # A subclass ROSClock is returned if ROS_TIME is specified. + clock = Clock(clock_type=ClockType.ROS_TIME) + assert clock.clock_type == ClockType.ROS_TIME + assert isinstance(clock, ROSClock) def test_clock_now(self): # System time should be roughly equal to time.time() diff --git a/rclpy/test/test_time_source.py b/rclpy/test/test_time_source.py index b1baadf41..7bcf3a4a5 100644 --- a/rclpy/test/test_time_source.py +++ b/rclpy/test/test_time_source.py @@ -53,11 +53,7 @@ def test_time_source_attach_clock(self): # ROSClock is a specialization of Clock with ROS time methods. time_source.attach_clock(ROSClock()) - # A clock of type ROS_TIME can be attached. It will be converted to a ROSClock for storage. - time_source.attach_clock(Clock(clock_type=ClockType.ROS_TIME)) - - assert all((isinstance(clock, ROSClock) for clock in time_source._associated_clocks)) - + # Other clock types are not supported. with self.assertRaises(ValueError): time_source.attach_clock(Clock(clock_type=ClockType.SYSTEM_TIME)) From cf38ae765503bff335b624c890ca5d0a7d30e227 Mon Sep 17 00:00:00 2001 From: dhood Date: Fri, 3 Aug 2018 10:57:52 -0700 Subject: [PATCH 15/16] Correctly initialise clock type for ROSClocks instantiated directly --- rclpy/rclpy/clock.py | 3 +++ rclpy/test/test_clock.py | 4 ++++ 2 files changed, 7 insertions(+) diff --git a/rclpy/rclpy/clock.py b/rclpy/rclpy/clock.py index a89b080d8..1008e3e5c 100644 --- a/rclpy/rclpy/clock.py +++ b/rclpy/rclpy/clock.py @@ -60,6 +60,9 @@ def now(self): class ROSClock(Clock): + def __new__(cls): + return super().__new__(Clock, clock_type=ClockType.ROS_TIME) + @property def ros_time_is_active(self): return _rclpy.rclpy_clock_get_ros_time_override_is_enabled(self._clock_handle) diff --git a/rclpy/test/test_clock.py b/rclpy/test/test_clock.py index c8d39198e..8fe23f6bd 100644 --- a/rclpy/test/test_clock.py +++ b/rclpy/test/test_clock.py @@ -38,6 +38,10 @@ def test_clock_construction(self): assert clock.clock_type == ClockType.ROS_TIME assert isinstance(clock, ROSClock) + # Direct instantiation of a ROSClock is also possible. + clock = ROSClock() + assert clock.clock_type == ClockType.ROS_TIME + def test_clock_now(self): # System time should be roughly equal to time.time() # There will still be differences between them, with the bound depending on the scheduler. From 6ac5bf98fbba8a62d8f2f59fc39bdc481112726e Mon Sep 17 00:00:00 2001 From: dhood Date: Fri, 3 Aug 2018 14:05:44 -0700 Subject: [PATCH 16/16] Predicate is parsed to an int not bool --- rclpy/src/rclpy/_rclpy.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rclpy/src/rclpy/_rclpy.c b/rclpy/src/rclpy/_rclpy.c index c75a36a34..ceb142a52 100644 --- a/rclpy/src/rclpy/_rclpy.c +++ b/rclpy/src/rclpy/_rclpy.c @@ -3304,7 +3304,7 @@ static PyObject * rclpy_clock_set_ros_time_override_is_enabled(PyObject * Py_UNUSED(self), PyObject * args) { PyObject * pyclock; - bool enabled; + int enabled; if (!PyArg_ParseTuple(args, "Op", &pyclock, &enabled)) { return NULL; }