Skip to content

RCLPY handles time being set back differently to RCLCPP #1490

@TenzinPlatter

Description

@TenzinPlatter

Generated by Generative AI

No

Operating System:

Linux tenzin-gr 6.14.0-27-generic #27~24.04.1-Ubuntu SMP PREEMPT_DYNAMIC Tue Jul 22 17:38:49 UTC 2 x86_64 x86_64 x86_64 GNU/Linux

ROS version or commit hash:

jazzy

RMW implementation (if applicable):

rmw_fastrtps_cpp

RMW Configuration (if applicable):

No response

Client library (if applicable):

rclpy

'ros2 doctor --report' output

ros2 doctor --report
   NETWORK CONFIGURATION
inet         : 127.0.0.1
inet4        : ['127.0.0.1']
inet6        : ['::1']
netmask      : 255.0.0.0
device       : lo
flags        : 73<RUNNING,LOOPBACK,UP>
mtu          : 65536
inet         : 10.71.10.226
inet4        : ['10.71.10.226']
ether        : e8:80:88:e0:82:9f
inet6        : ['fe80::69ed:2ec9:1a76:e6e3%enp49s0']
netmask      : 255.255.255.0
device       : enp49s0
flags        : 4163<RUNNING,BROADCAST,MULTICAST,UP>
mtu          : 1500
broadcast    : 10.71.10.255
inet         : 10.71.11.57
inet4        : ['10.71.11.57']
ether        : e0:2e:0b:2a:4e:5a
inet6        : ['fe80::5905:f69e:2cf8:76f4%wlp0s20f3']
netmask      : 255.255.255.0
device       : wlp0s20f3
flags        : 4163<RUNNING,BROADCAST,MULTICAST,UP>
mtu          : 1500
broadcast    : 10.71.11.255
inet         : 100.64.0.77
inet4        : ['100.64.0.77']
inet6        : ['fd7a:115c:a1e0::53', 'fe80::c32a:f2d4:4548:e67d%tailscale0']
netmask      : 255.255.255.255
device       : tailscale0
flags        : 4305<RUNNING,UP,NOARP,MULTICAST,PTP>
mtu          : 1280
inet         : 172.24.0.1
inet4        : ['172.24.0.1']
ether        : 02:42:13:10:7e:bd
netmask      : 255.255.0.0
device       : br-b140252d8cda
flags        : 4099<BROADCAST,MULTICAST,UP>
mtu          : 1500
broadcast    : 172.24.255.255
inet         : 172.22.0.1
inet4        : ['172.22.0.1']
ether        : 02:42:db:ca:80:b9
netmask      : 255.255.0.0
device       : br-0d7120003ede
flags        : 4099<BROADCAST,MULTICAST,UP>
mtu          : 1500
broadcast    : 172.22.255.255
inet         : 172.25.0.1
inet4        : ['172.25.0.1']
ether        : 02:42:cc:d9:7c:dd
netmask      : 255.255.0.0
device       : br-6f7654bffce6
flags        : 4099<BROADCAST,MULTICAST,UP>
mtu          : 1500
broadcast    : 172.25.255.255
inet         : 172.18.0.1
inet4        : ['172.18.0.1']
ether        : 02:42:9b:40:19:33
netmask      : 255.255.0.0
device       : br-84fea460f643
flags        : 4099<BROADCAST,MULTICAST,UP>
mtu          : 1500
broadcast    : 172.18.255.255
inet         : 172.19.0.1
inet4        : ['172.19.0.1']
ether        : 02:42:22:10:5d:de
netmask      : 255.255.0.0
device       : br-a5170c88b0a6
flags        : 4099<BROADCAST,MULTICAST,UP>
mtu          : 1500
broadcast    : 172.19.255.255
inet         : 172.17.0.1
inet4        : ['172.17.0.1']
ether        : 02:42:f2:b0:83:21
inet6        : ['fe80::42:f2ff:feb0:8321%docker0']
netmask      : 255.255.0.0
device       : docker0
flags        : 4099<BROADCAST,MULTICAST,UP>
mtu          : 1500
broadcast    : 172.17.255.255
inet         : 172.23.0.1
inet4        : ['172.23.0.1']
ether        : 02:42:77:79:2b:3c
netmask      : 255.255.0.0
device       : br-36730f958225
flags        : 4099<BROADCAST,MULTICAST,UP>
mtu          : 1500
broadcast    : 172.23.255.255
inet         : 172.21.0.1
inet4        : ['172.21.0.1']
ether        : 02:42:da:57:53:ec
netmask      : 255.255.0.0
device       : br-4924ab61600b
flags        : 4099<BROADCAST,MULTICAST,UP>
mtu          : 1500
broadcast    : 172.21.255.255

   PLATFORM INFORMATION
system           : Linux
platform info    : Linux-6.14.0-27-generic-x86_64-with-glibc2.39
release          : 6.14.0-27-generic
processor        : x86_64

   QOS COMPATIBILITY LIST
compatibility status    : No publisher/subscriber pairs found

   RMW MIDDLEWARE
middleware name    : rmw_fastrtps_cpp

   ROS 2 INFORMATION
distribution name      : jazzy
distribution type      : ros2
distribution status    : active
release platforms      : {'debian': ['bookworm'], 'rhel': ['9'], 'ubuntu': ['noble']}

   TOPIC LIST
topic               : none
publisher count     : 0
subscriber count    : 0

Steps to reproduce issue

  1. Install rclpy pub example with
sudo apt install ros-jazzy-examples-rclpy-minimal-publisher
  1. Run the publisher with: ros2 run examples_rclpy_minimal_publisher publisher_local_function --ros-args --log-level debug
  2. On another machine echo the topic with ros2 topic echo /topic or run the minimal subscriber example
  3. Set the system clock of the publishing machine back with sudo date -s "-1 minute"

Expected behavior

When using the rclcpp publisher example the node continues to publish and syncs to the new system time, reflected in the log time.

Actual behavior

The rclpy node stops publishing until the system clock has returned to where it was before the step. Stepping the clock back does not fix this, but waiting the amount of time you stepped the clock back does (i.e. setting the clock back 1 minute then forward 1 minute will not resume publishing until 1 minute of real time has passed from the step backward). Writing a simple test node also reveals that any callbacks specified in a call to self.get_clock().create_jump_callback() are not called.

Additional information

Test Node:

import rclpy
from rclpy.duration import Duration
from rclpy.node import Node
from std_msgs.msg import String
from rclpy.clock import JumpHandle, JumpThreshold, JumpHandlePreCallbackType, TimeJump


class ScratchNode(Node):
    def __init__(self) -> None:
        super().__init__("scratch_publisher")
        self.pub = self.create_publisher(String, "topic", 10)
        self.timer = self.create_timer(0.5, self.cb)
        threshold = JumpThreshold(
            min_backward=Duration(seconds=-30), min_forward=Duration(seconds=30)
        )
        self.get_clock().create_jump_callback(
            threshold, pre_callback=self.pre_cb, post_callback=self.post_cb
        )
        self.timer_2 = self.create_timer(0.5, self.cb_2)
        self.get_logger().info("created")

    def cb_2(self):
        self.get_logger().info("callback!")

    def pre_cb(self):
        self.get_logger().info(
            f"got pre time jump at {self.get_clock().now().seconds_nanoseconds()}"
        )

    def post_cb(self, time_jump: TimeJump):
        self.get_logger().info(
            f"got post time jump at {self.get_clock().now().seconds_nanoseconds()}"
        )

        with open("file.txt", "w") as f:
            f.write(f"clock jump type: {time_jump.clock_change.value}\n")
            f.write(f"jump delta: {time_jump.delta.nanoseconds}\n")

    def cb(self):
        now = self.get_clock().now().seconds_nanoseconds()
        msg = String()
        msg.data = f"Publishing at: {now}"
        self.pub.publish(msg)
        self.get_logger().info(f"Publishing {msg.data} at {now}")


def main():
    rclpy.init()
    try:
        rclpy.spin(ScratchNode())
    except KeyboardInterrupt:
        pass

    rclpy.shutdown()

Metadata

Metadata

Assignees

Labels

bugSomething isn't working

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions