Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

rcl_jump_threshold does not disable forward jump #947

Closed
Kettenhoax opened this issue Nov 2, 2021 · 1 comment · Fixed by #948
Closed

rcl_jump_threshold does not disable forward jump #947

Kettenhoax opened this issue Nov 2, 2021 · 1 comment · Fixed by #948
Labels
bug Something isn't working

Comments

@Kettenhoax
Copy link

Bug report

Required Info:

  • Operating System:
    • Ubuntu 20.04
  • Installation type:
    • rolling binaries
  • Version or commit hash:
    • ros-rolling-rcl 4.0.0-1focal.20210921.175344
  • DDS implementation:
    • CycloneDDS
  • Client library (if applicable):
    • rclcpp

Steps to reproduce issue

Define a clock jump handler for your node, and set the forward threshold to 0, which according to rcl/time.h should disable forward jumps.

#include <functional>
#include "rclcpp/rclcpp.hpp"

class TestNode : public rclcpp::Node
{
private:
  rclcpp::JumpHandler::SharedPtr jump_handler_;

public:
  TestNode() : Node("test")
  {
    rcl_jump_threshold_t jump_threshold;
    jump_threshold.on_clock_change = true;
    jump_threshold.min_forward.nanoseconds = 0;
    jump_threshold.min_backward.nanoseconds = -1;
    jump_handler_ =
      get_clock()->create_jump_callback(
      nullptr,
      std::bind(&TestNode::onJump, this, std::placeholders::_1), jump_threshold);
  }

private:
  void onJump(const rcl_time_jump_t & jump)
  {
    RCLCPP_INFO(this->get_logger(), "Jump of '%li'", jump.delta.nanoseconds);
  }
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<TestNode>());
  rclcpp::shutdown();
  return 0;
}

Compile and run with sim time

./jump --ros-args -p use_sim_time:=true

Simultaneously publish /clock messages:

import rclpy
from rclpy.qos import qos_profile_sensor_data
from rclpy.node import Node
from rosgraph_msgs.msg import Clock

class PublishClock(Node):
    def __init__(self):
        super().__init__('publish_clock')
        self._pub = self.create_publisher(Clock, 'clock', qos_profile_sensor_data)
        self._timer = self.create_timer(1.0, self._on_timer)

    def _on_timer(self):
        msg = Clock()
        msg.clock = self.get_clock().now().to_msg()
        self._pub.publish(msg)

rclpy.init()
rclpy.spin(PublishClock())

Expected behavior

The callback is never called and there's no output.

Actual behavior

Output is written at every received /clock message.

Additional Information

Works as expected without sim time

@sloretz
Copy link
Contributor

sloretz commented Nov 3, 2021

I just ran into this too while looking at ros2/rclcpp#1814 :)

I think these checks

rcl/rcl/src/rcl/time.c

Lines 276 to 282 in d8817fd

if (
(is_clock_change && info->threshold.on_clock_change) ||
(time_jump->delta.nanoseconds < 0 &&
time_jump->delta.nanoseconds <= info->threshold.min_backward.nanoseconds) ||
(time_jump->delta.nanoseconds > 0 &&
time_jump->delta.nanoseconds >= info->threshold.min_forward.nanoseconds))
{

Are supposed to be

    if (
      (is_clock_change && info->threshold.on_clock_change) ||
      (info->threshold.min_backward.nanoseconds < 0 &&
      time_jump->delta.nanoseconds <= info->threshold.min_backward.nanoseconds) ||
      (info->threshold.min_forward.nanoseconds > 0 &&
      time_jump->delta.nanoseconds >= info->threshold.min_forward.nanoseconds))
    {

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
None yet
Development

Successfully merging a pull request may close this issue.

3 participants