A dashcam for your robot. Continuously buffer recent sensor data, and when something important happens, automatically save a rosbag with the moments before and after the event.
When a robot does something unexpected β a collision, an emergency stop, a weird sensor reading β the data you really want is the few seconds leading up to it. But you can't record everything forever.
ROS Time Machine keeps a rolling, in-memory buffer of the last N seconds for each topic. The instant a trigger fires, it stitches that pre-event buffer together with live post-event recording into a single MCAP rosbag β capturing the full story of the moment, automatically.
Key idea: one circular buffer per topic is always recording. On a trigger, only the relevant slice is extracted and combined with live recording β so you pay memory cost, not disk cost, until it matters.
| βͺ Pre-event buffering | Circular buffers continuously hold recent data β capture what happened before the trigger |
| βΊοΈ Post-event recording | Keep recording for a configurable duration after the trigger |
| β‘ Flexible triggers | Watch any topic; fire on conditions (==, !=, >, <, >=, <=) over nested message fields |
| π Dynamic topic discovery | Auto-detects and subscribes to topics as they appear β no message-type codegen needed |
| π¦ Rate limiting | Cap recordings per minute/second to avoid runaway disk usage |
| πΎ MCAP format | Modern, efficient rosbag2 storage with compression |
| π§΅ Multi-threaded | Worker pool handles multiple simultaneous recordings |
| π REST API (optional) | Trigger & list snapshots over HTTP from web apps, mobile, or non-ROS systems |
Prerequisites: ROS 2 Jazzy (Ubuntu 24.04) Β· a C++17 compiler Β· rosbag2 with MCAP support
# 1. Clone & build
git clone https://github.com/arpitg1304/ros-time-machine.git
cd ros-time-machine
colcon build --packages-select ros_time_machine
source install/setup.bash
# 2. Launch (uses the bundled example config)
ros2 launch ros_time_machine time_machine.launch.py
# 3. Trigger a snapshot
ros2 topic pub -1 /time_machine/manual_trigger std_msgs/msg/Bool "{data: true}"
# 4. Find your recording
ls /tmp/ros_time_machine/snapshots/To use your own setup, copy and edit the example config:
cp src/ros_time_machine/config/example_snapshots.yaml my_config.yaml
ros2 launch ros_time_machine time_machine.launch.py config_file:=/path/to/my_config.yamlA snapshot ties together a trigger, the topics to record, and how much to keep before/after:
snapshots:
- name: "emergency_stop"
trigger:
topic: "/emergency_stop"
msg_type: "std_msgs/msg/Bool"
condition: { field: "data", operator: "==", value: true }
recording:
topics: ["/camera/image_raw", "/lidar/points", "/odom"]
pre_event_duration: 5.0 # seconds kept from the buffer (before)
post_event_duration: 10.0 # seconds recorded live (after)
rate_limit:
max_triggers_per_minute: 3
output:
path: "/tmp/ros_time_machine/snapshots"
name_pattern: "{snapshot_name}_{timestamp}"
format: "mcap"π Full configuration reference
- name β unique identifier for this snapshot type
- description β human-readable description (optional)
- topic β ROS topic to monitor
- msg_type β full message type, e.g.
std_msgs/msg/Bool - condition (optional) β fire only when this is true
- field β field path in the message (e.g.
data,linear_acceleration.x) - operator β one of
==,!=,>,<,>=,<= - value β value to compare against
- field β field path in the message (e.g.
- topics β list of topics to record
- pre_event_duration β seconds of buffered data to capture before the trigger
- post_event_duration β seconds to keep recording after the trigger
- max_triggers_per_minute β max triggers allowed per minute
- max_triggers_per_second β (alternative) max triggers per second
- window_size β time window in seconds for rate limiting
- path β directory to save recordings
- name_pattern β filename pattern (supports
{snapshot_name}and{timestamp}) - format β
mcap(recommended) orsqlite3
π More example snapshots (high-acceleration detection, multi-camera)
High-acceleration detection β fire when IMU acceleration exceeds a threshold:
snapshots:
- name: "high_accel"
trigger:
topic: "/imu/data"
msg_type: "sensor_msgs/msg/Imu"
condition: { field: "linear_acceleration.x", operator: ">", value: 5.0 }
recording:
topics: ["/camera/image", "/imu/data"]
pre_event_duration: 3.0
post_event_duration: 5.0
rate_limit:
max_triggers_per_minute: 10Multi-camera capture β grab all cameras on a manual trigger:
snapshots:
- name: "multi_camera"
trigger:
topic: "/capture_trigger"
msg_type: "std_msgs/msg/Bool"
recording:
topics:
- "/camera/front/image"
- "/camera/rear/image"
- "/camera/left/image"
- "/camera/right/image"
pre_event_duration: 1.0
post_event_duration: 2.0
output:
path: "/data/recordings"
format: "mcap"- π Collision detection β sensor data from 5s before impact to 10s after
- π Anomaly detection β record when unusual sensor readings occur
- π±οΈ Manual capture β trigger on demand via topic or REST API
- π Emergency events β auto-save when safety systems activate
- π± Remote monitoring β trigger snapshots from a dashboard or mobile app via REST
A single ROS 2 node runs four cooperating components, all driven by one YAML config:
For detailed diagrams, sequence flows, and component specs, see ARCHITECTURE.md.
Trigger and query snapshots over HTTP β ideal for web dashboards, mobile apps, and non-ROS integrations.
π Setup & endpoints
# Install deps & build
pip3 install --break-system-packages fastapi uvicorn pydantic
colcon build --packages-select ros_time_machine_rest_bridge
source install/setup.bash
# Run (default port 8080)
ros2 launch ros_time_machine_rest_bridge rest_bridge.launch.py # or: port:=9000| Method | Endpoint | Description |
|---|---|---|
GET |
/health |
Health check |
POST |
/api/snapshots/trigger |
Trigger a snapshot (optional reason, metadata) |
GET |
/api/snapshots |
List all snapshots |
GET |
/api/snapshots/{id} |
Snapshot details |
GET |
/docs |
Interactive Swagger UI |
# Trigger with metadata
curl -X POST http://localhost:8080/api/snapshots/trigger \
-H "Content-Type: application/json" \
-d '{"reason": "collision_detected", "metadata": {"severity": "high"}}'A test_rest_api.sh script is included to verify the API end-to-end.
βΆοΈ Playback, sim time, and viewing snapshots
Replaying a bag for testing (use simulated time so buffer timestamps line up):
# Terminal 1 β play the bag, publishing /clock
ros2 bag play your_bag.mcap --clock
# Terminal 2 β run with sim time
ros2 launch ros_time_machine time_machine.launch.py \
config_file:=my_config.yaml use_sim_time:=trueInspecting a snapshot:
ros2 bag info /tmp/ros_time_machine/snapshots/emergency_stop_1234567890 # metadata
ros2 bag play /tmp/ros_time_machine/snapshots/emergency_stop_1234567890 # replay
rqt_bag /tmp/ros_time_machine/snapshots/emergency_stop_1234567890 # GUIβοΈ Launch parameters & running without the launch file
ros2 launch ros_time_machine time_machine.launch.py \
config_file:=/path/to/config.yaml \
log_level:=debug \
use_sim_time:=true| Parameter | Description | Default |
|---|---|---|
config_file |
Path to YAML configuration | example_snapshots.yaml |
log_level |
debug, info, warn, error, fatal |
info |
use_sim_time |
Use simulated time from /clock |
false |
Direct run (no launch file):
ros2 run ros_time_machine time_machine_node \
--ros-args -p config_file:=/path/to/config.yaml -p use_sim_time:=true --log-level debugTry ROS Time Machine on real sensor data β NVIDIA Isaac R2B, AutoCore Ouster OS1-64, Intel RealSense D435. See docs/TESTING_WITH_DATASETS.md for download links, sample configs, and step-by-step instructions.
π§ Common issues
No messages being recorded
- Check topics are publishing:
ros2 topic list - Verify topic names in config match exactly (case-sensitive)
- Enable
log_level:=debugto see buffer status - Allow enough
pre_event_durationfor buffer warm-up
Gaps in recorded data
- Increase
pre_event_durationto extend buffer capacity - Ensure
use_sim_timeis set correctly during bag playback - Play bags with the
--clockflag
High memory usage
- Reduce
pre_event_duration/post_event_duration - Record fewer topics
- Use rate limiting to prevent excessive triggers
Contributions welcome! Please open an issue or discussion, or send a pull request.