Skip to content

RCL_ROS_TIME: how to get sim-time-aware monotonic timing? #3122

@tonynajjar

Description

@tonynajjar

Description

When use_sim_time=true, an RCL_ROS_TIME clock sources time from the /clock topic. When use_sim_time=false, it falls back to RCL_SYSTEM_TIME unconditionally. This fallback is hardcoded in rcl.

There is currently no native way to create a clock that uses /clock in simulation and RCL_STEADY_TIME (monotonic wall time) on real hardware. The only two options available are:

  • RCL_STEADY_TIME — monotonic but ignores sim time entirely
  • RCL_ROS_TIME — sim-time-aware, but falls back to RCL_SYSTEM_TIME (not RCL_STEADY_TIME) on real hardware

This is a problem for any node that needs different clock behaviors for different purposes within the same node. For example, a controller node typically needs:

Use case Real hardware Simulation
Control loop timer RCL_STEADY_TIME (monotonic, NTP-immune) /clock
Message timestamps RCL_SYSTEM_TIME (wall clock) /clock

Today, both of these are impossible to satisfy with a single RCL_ROS_TIME clock because the fallback is always RCL_SYSTEM_TIME. Using the node's clock for a control loop timer silently introduces NTP sensitivity on real hardware.

Motivation

This came up in ros-navigation/navigation2#6063, which makes various Nav2 components sim-time-aware by switching from rclcpp::WallRate to rclcpp::Rate(freq, node->get_clock()). This is the right thing to do for simulation, but it silently changes the real-hardware behavior from RCL_STEADY_TIME (monotonic) to RCL_SYSTEM_TIME (NTP-adjustable), because that's the only fallback RCL_ROS_TIME supports.

Current workaround

The only workaround is to check use_sim_time at construction and branch between create_timer and create_wall_timer:

class Controller : public rclcpp::Node
{
public:
  Controller() : Node("controller")
  {
    if (get_parameter("use_sim_time").as_bool()) {
      timer_ = create_timer(100ms, std::bind(&Controller::control_loop, this));
    } else {
      timer_ = create_wall_timer(100ms, std::bind(&Controller::control_loop, this));
    }
  }

  void control_loop()
  {
    auto cmd = compute_velocity();
    cmd.header.stamp = now();
    pub_->publish(cmd);
  }
};

This is fragile — use_sim_time is checked once at construction, so runtime parameter changes are ignored. Every node or library that needs monotonic + sim-aware timing must duplicate this pattern. The same issue applies to rclcpp::Rate and rclcpp::WallRate, where there is no equivalent workaround at all.

Question

What is the intended way to get sim-time-aware monotonic timing in rclcpp? Is there an existing mechanism we are missing, or does rclcpp need a way to configure the fallback clock type for RCL_ROS_TIME?

Metadata

Metadata

Assignees

No one assigned

    Labels

    enhancementNew feature or request

    Type

    No type
    No fields configured for issues without a type.

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions