ROS 2 Time & Clock Guide 2026
Master ROS 2 time: RCL_ROS_TIME vs STEADY_TIME, the use_sim_time parameter, publishing /clock, ros2 bag play --clock, tf2 simulation time, and the complete rclcpp/rclpy Time API.
The Golden Rule
Always use node->now() (C++) or node.get_clock().now() (Python) — never std::chrono::system_clock::now() or Python's time.time(). The node clock automatically follows use_sim_time so your code works identically in real deployments and simulation/bag playback without any code changes.
ROS 2 Time Types
ROS 2 has three clock types. Choosing the wrong one causes timing bugs during simulation or bag playback.
ROS 2 Clock Types
═══════════════════════════════════════════════════════
RCL_ROS_TIME (default when use_sim_time=true)
• Tracks /clock topic
• Frozen when no /clock publisher is active
• Used for: simulation, bag playback, reproducible testing
• rclcpp: node->get_clock()->now()
• rclpy: node.get_clock().now()
RCL_SYSTEM_TIME
• Wall-clock (gettimeofday / std::chrono::system_clock)
• Advances regardless of ROS activity
• Not monotonic — can jump on NTP sync
• Used for: logging with wall time, real-world deadlines
• rclcpp: rclcpp::Clock(RCL_SYSTEM_TIME).now()
RCL_STEADY_TIME
• Monotonic clock (std::chrono::steady_clock)
• Never jumps backward — safe for duration measurement
• Unaffected by use_sim_time
• Used for: benchmarking, timeouts, measuring elapsed time
• rclcpp: rclcpp::Clock(RCL_STEADY_TIME).now()
Key rule:
use_sim_time=false → node->now() returns SYSTEM time
use_sim_time=true → node->now() returns /clock (sim time)
Timer callbacks with create_timer() respect use_sim_time
rclcpp::Clock(RCL_STEADY_TIME) always returns real wall time⚡ node->now() (ROS time) is the correct choice for 99% of robotics code. Use STEADY only when measuring real elapsed time (e.g. watchdog timers that must fire in real seconds even during simulation).
C++ Time API — rclcpp::Time and rclcpp::Duration
rclcpp::Time wraps nanoseconds as int64_t. rclcpp::Duration represents a difference between two times. Both have arithmetic operators.
#include <rclcpp/rclcpp.hpp>
class TimeNode : public rclcpp::Node {
public:
TimeNode() : Node("time_node") {
// ── Current ROS time (respects use_sim_time) ────────
rclcpp::Time now = this->now();
int64_t ns = now.nanoseconds(); // epoch ns
double sec = now.seconds(); // epoch seconds (double)
// ── Time arithmetic ─────────────────────────────────
rclcpp::Duration dt(1, 500000000); // 1.5 seconds
rclcpp::Time future = now + dt;
rclcpp::Duration elapsed = future - now; // = 1.5s
// ── Convert rclcpp::Time ↔ builtin_interfaces::msg::Time ─
// (used in message headers)
auto msg_time = now; // implicit conversion
builtin_interfaces::msg::Time stamp;
stamp.sec = static_cast<int32_t>(now.seconds());
stamp.nanosec = now.nanoseconds() % 1'000'000'000;
// ── Duration from std::chrono ────────────────────────
auto chrono_dur = std::chrono::milliseconds(100);
rclcpp::Duration ros_dur = rclcpp::Duration(chrono_dur);
// ── Specific clock types ─────────────────────────────
rclcpp::Clock steady_clock(RCL_STEADY_TIME);
rclcpp::Time t0 = steady_clock.now();
// ... do work ...
rclcpp::Time t1 = steady_clock.now();
auto real_elapsed = t1 - t0;
RCLCPP_INFO(get_logger(), "Took %.3f ms",
real_elapsed.seconds() * 1000.0);
// ── Timer that fires in sim time ─────────────────────
timer_ = this->create_wall_timer(
std::chrono::seconds(1),
[this]() {
RCLCPP_INFO(get_logger(), "Sim time: %.3f", this->now().seconds());
}
);
}
private:
rclcpp::TimerBase::SharedPtr timer_;
};Python Time API — rclpy Time and Duration
rclpy mirrors the C++ API with Python idioms. Time and Duration are in the rclpy.time module.
import rclpy
from rclpy.node import Node
from rclpy.time import Time, Duration
from rclpy.clock import ClockType
class TimeNode(Node):
def __init__(self):
super().__init__("time_node")
# ── Current ROS time ──────────────────────────────
now: Time = self.get_clock().now()
ns: int = now.nanoseconds # int, total nanoseconds
sec: float = now.nanoseconds / 1e9 # epoch seconds
# ── Arithmetic ────────────────────────────────────
dt = Duration(seconds=1, nanoseconds=500_000_000) # 1.5s
future: Time = now + dt
elapsed: Duration = future - now # 1.5s
# ── Convert to/from builtin_interfaces.msg.Time ───
from builtin_interfaces.msg import Time as TimeMsg
msg_time: TimeMsg = now.to_msg()
back: Time = Time.from_msg(msg_time)
# ── Specific clock types ──────────────────────────
from rclpy.clock import Clock
steady = Clock(clock_type=ClockType.STEADY_TIME)
t0 = steady.now()
# ... do work ...
t1 = steady.now()
real_ms = (t1 - t0).nanoseconds / 1e6
self.get_logger().info(f"Elapsed: {real_ms:.2f} ms")
# ── Timer (respects use_sim_time) ─────────────────
self.timer = self.create_timer(1.0, self._on_timer)
def _on_timer(self):
t = self.get_clock().now().nanoseconds / 1e9
self.get_logger().info(f"Sim time: {t:.3f}")use_sim_time — Synchronize to Simulation
Setting use_sim_time=true makes a node subscribe to /clock and use it as its time source. Timers, tf2 lookups, and message timestamps all use simulated time.
# In a launch file — set use_sim_time for specific nodes
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument
def generate_launch_description():
use_sim_time = LaunchConfiguration("use_sim_time", default="false")
return LaunchDescription([
DeclareLaunchArgument("use_sim_time", default_value="false"),
Node(
package="my_pkg",
executable="my_node",
parameters=[{"use_sim_time": use_sim_time}],
),
# Or hardcode for simulation-only nodes:
Node(
package="nav2_costmap_2d",
executable="nav2_costmap_2d",
parameters=[{"use_sim_time": True}], # always sim time
),
])
# ── Set use_sim_time at runtime ──────────────────────────
# ros2 param set /my_node use_sim_time true
# ── In code — check if using sim time ────────────────────
# C++:
# bool is_sim = this->get_parameter("use_sim_time").as_bool();
# Python:
# is_sim = self.get_parameter("use_sim_time").value⚡ use_sim_time must be set BEFORE the node spins — setting it after initialization has no effect on timers already created. In simulation, set it in launch files or via -p use_sim_time:=true on ros2 run.
Publishing to /clock (Custom Time Source)
Any node can act as a clock source by publishing rosgraph_msgs/msg/Clock to /clock. Gazebo, Isaac Sim, and ros2 bag play do this automatically.
#include <rclcpp/rclcpp.hpp>
#include <rosgraph_msgs/msg/clock.hpp>
class ClockPublisher : public rclcpp::Node {
public:
ClockPublisher() : Node("clock_publisher") {
pub_ = create_publisher<rosgraph_msgs::msg::Clock>("/clock", 10);
// Publish at 100x real speed (for accelerated sim)
wall_timer_ = create_wall_timer(
std::chrono::milliseconds(10), // real: 100Hz
[this]() {
sim_time_ns_ += 100'000'000; // advance 100ms sim time
rosgraph_msgs::msg::Clock msg;
msg.clock.sec = sim_time_ns_ / 1'000'000'000;
msg.clock.nanosec = sim_time_ns_ % 1'000'000'000;
pub_->publish(msg);
}
);
}
private:
rclcpp::Publisher<rosgraph_msgs::msg::Clock>::SharedPtr pub_;
rclcpp::TimerBase::SharedPtr wall_timer_;
int64_t sim_time_ns_ = 0;
};Bag Playback with Simulated Time
ros2 bag play can publish a /clock topic from bag-recorded timestamps, letting all nodes replay at the exact timing of the original recording.
# Play a bag and publish /clock so nodes follow bag timestamps
ros2 bag play my_recording.db3 --clock
# Set rate to 0.5× for slow-motion replay
ros2 bag play my_recording.db3 --clock --rate 0.5
# Set rate to 2× for fast forward
ros2 bag play my_recording.db3 --clock --rate 2.0
# Start paused (press space to step)
ros2 bag play my_recording.db3 --clock --start-paused
# ── Nodes must have use_sim_time=true to follow bag time ──
ros2 run my_pkg my_node --ros-args -p use_sim_time:=true
# ── Verify /clock is publishing ───────────────────────────
ros2 topic hz /clock
# → average rate: 100.0 (default 100 Hz)
ros2 topic echo /clock --once
# → clock:
# → sec: 1718900400
# → nanosec: 123456789
# ── tf2 lookups also need sim time ────────────────────────
# tf2_ros::Buffer uses node's clock → set use_sim_time=true
# on the node that creates the Buffer⚡ If you forget --clock with ros2 bag play, nodes with use_sim_time=true will have frozen time (no /clock publisher = time stands still). All tf2 lookups and timer callbacks will stall.
Time Comparison and tf2 Lookups
Comparing ROS times and using tf2 with sim time requires careful handling to avoid clock mismatch errors.
from rclpy.time import Time, Duration
from rclpy.duration import Duration as RclpyDuration
import rclpy
class TfSimTimeNode(Node):
def __init__(self):
super().__init__("tf_sim_node")
# ── Time comparison ───────────────────────────────
t1 = self.get_clock().now()
t2 = self.get_clock().now()
if t2 > t1:
elapsed = (t2 - t1).nanoseconds / 1e9
self.get_logger().info(f"Elapsed: {elapsed:.6f} s")
# ── Check if time is valid (not zero) ─────────────
zero = Time(nanoseconds=0)
if t1 == zero:
self.get_logger().warn("Time is zero — /clock not publishing?")
# ── tf2 with sim time ──────────────────────────────
import tf2_ros
self.tf_buffer = tf2_ros.Buffer()
self.tf_listener = tf2_ros.TransformListener(
self.tf_buffer, self
)
self.timer = self.create_timer(0.1, self._lookup)
def _lookup(self):
try:
# Time(0) = "latest available" — works with sim time
tf = self.tf_buffer.lookup_transform(
"map", "base_link",
rclpy.time.Time() # Time(0) = latest
)
self.get_logger().info(
f"Position: ({tf.transform.translation.x:.2f}, "
f"{tf.transform.translation.y:.2f})"
)
except Exception as e:
self.get_logger().warn(f"TF error: {e}")Quick Reference
| Concept | Details |
|---|---|
| RCL_ROS_TIME | Default. Follows /clock when use_sim_time=true, else system time |
| RCL_SYSTEM_TIME | Wall clock — not monotonic, can jump on NTP sync |
| RCL_STEADY_TIME | Monotonic — safe for measuring elapsed time, unaffected by sim |
| node->now() / node.get_clock().now() | ROS time — respects use_sim_time parameter |
| use_sim_time=true | Node subscribes to /clock; all timers use sim time |
| ros2 bag play --clock | Bag publishes /clock from recorded timestamps |
| rclcpp::Duration(sec, ns) | Construct duration — first arg seconds, second nanoseconds |
| Time(0) | Zero time = request latest TF transform (use in tf2 lookups) |
| Frozen time symptom | use_sim_time=true but no /clock publisher → all timers stall |
| Check /clock | ros2 topic hz /clock → should be ~100Hz during bag/sim playback |