diff --git a/rclpy/package.xml b/rclpy/package.xml
index 6ba620d9a..0d3d001f4 100644
--- a/rclpy/package.xml
+++ b/rclpy/package.xml
@@ -25,6 +25,7 @@
ament_index_python
builtin_interfaces
+ rosgraph_msgs
ament_cmake_pytest
ament_lint_auto
diff --git a/rclpy/rclpy/time_source.py b/rclpy/rclpy/time_source.py
index 110883ca4..dccec253d 100644
--- a/rclpy/rclpy/time_source.py
+++ b/rclpy/rclpy/time_source.py
@@ -12,12 +12,12 @@
# See the License for the specific language governing permissions and
# limitations under the License.
-import builtin_interfaces.msg
from rcl_interfaces.msg import SetParametersResult
from rclpy.clock import ClockType
from rclpy.clock import ROSClock
from rclpy.parameter import Parameter
from rclpy.time import Time
+import rosgraph_msgs.msg
CLOCK_TOPIC = '/clock'
@@ -55,7 +55,7 @@ def ros_time_is_active(self, enabled):
def _subscribe_to_clock_topic(self):
if self._clock_sub is None and self._node is not None:
self._clock_sub = self._node.create_subscription(
- builtin_interfaces.msg.Time,
+ rosgraph_msgs.msg.Clock,
CLOCK_TOPIC,
self.clock_callback
)
@@ -102,7 +102,7 @@ def attach_clock(self, clock):
def clock_callback(self, msg):
# Cache the last message in case a new clock is attached.
- time_from_msg = Time.from_msg(msg)
+ time_from_msg = Time.from_msg(msg.clock)
self._last_time_set = time_from_msg
for clock in self._associated_clocks:
clock.set_ros_time_override(time_from_msg)
diff --git a/rclpy/test/test_time_source.py b/rclpy/test/test_time_source.py
index aea286e55..e935be1c4 100644
--- a/rclpy/test/test_time_source.py
+++ b/rclpy/test/test_time_source.py
@@ -16,7 +16,6 @@
import unittest
from unittest.mock import Mock
-import builtin_interfaces.msg
import rclpy
from rclpy.clock import Clock
from rclpy.clock import ClockChange
@@ -28,6 +27,7 @@
from rclpy.time import Time
from rclpy.time_source import CLOCK_TOPIC
from rclpy.time_source import TimeSource
+import rosgraph_msgs.msg
from .mock_compat import __name__ as _ # noqa: ignore=F401
@@ -44,11 +44,11 @@ def tearDown(self):
rclpy.shutdown(context=self.context)
def publish_clock_messages(self):
- clock_pub = self.node.create_publisher(builtin_interfaces.msg.Time, CLOCK_TOPIC)
+ clock_pub = self.node.create_publisher(rosgraph_msgs.msg.Clock, CLOCK_TOPIC)
cycle_count = 0
- time_msg = builtin_interfaces.msg.Time()
+ time_msg = rosgraph_msgs.msg.Clock()
while rclpy.ok(context=self.context) and cycle_count < 5:
- time_msg.sec = cycle_count
+ time_msg.clock.sec = cycle_count
clock_pub.publish(time_msg)
cycle_count += 1
executor = rclpy.executors.SingleThreadedExecutor(context=self.context)
@@ -57,11 +57,11 @@ def publish_clock_messages(self):
time.sleep(1)
def publish_reversed_clock_messages(self):
- clock_pub = self.node.create_publisher(builtin_interfaces.msg.Time, CLOCK_TOPIC)
+ clock_pub = self.node.create_publisher(rosgraph_msgs.msg.Clock, CLOCK_TOPIC)
cycle_count = 0
- time_msg = builtin_interfaces.msg.Time()
+ time_msg = rosgraph_msgs.msg.Clock()
while rclpy.ok(context=self.context) and cycle_count < 5:
- time_msg.sec = 6 - cycle_count
+ time_msg.clock.sec = 6 - cycle_count
clock_pub.publish(time_msg)
cycle_count += 1
executor = rclpy.executors.SingleThreadedExecutor(context=self.context)