Event-triggered recording system for ROS 2 that captures sensor data snapshots with pre-event buffering.
Capture the moments that matter by recording data before and after specific events occur. Perfect for debugging, data collection, and critical event analysis in robotics applications.
- Pre-Event Buffering: Circular buffers continuously store recent data, capturing what happened before a trigger
- Post-Event Recording: Continue recording for a specified duration after the trigger
- Dynamic Topic Discovery: Automatically detects and subscribes to topics as they become available
- Flexible Triggers: Monitor any ROS topic and trigger on custom conditions
- Rate Limiting: Prevent excessive recordings with configurable trigger limits
- MCAP Format: Modern, efficient rosbag2 storage with compression support
- Multi-threaded: Handle multiple simultaneous recordings efficiently
- REST API Bridge: Optional HTTP API for triggering snapshots from web apps, mobile devices, or non-ROS systems
The Time Machine continuously buffers incoming messages in memory. When a trigger event occurs, it combines buffered pre-event data with live post-event recording to create a complete snapshot.
gantt
title Recording Timeline
dateFormat X
axisFormat %s
section Circular Buffer
Continuous buffering (oldest dropped) :active, buffer, 0, 10
section Trigger Event
⚡ Event detected at t=5s :milestone, trigger, 5, 0
section Rosbag Output
Pre-event (from buffer) :pre, 2, 5
Post-event (live recording) :post, 5, 8
flowchart LR
subgraph CircularBuffer["🔄 Circular Buffer (Always Running)"]
direction TB
B1["t-5s"] --> B2["t-4s"] --> B3["t-3s"] --> B4["t-2s"] --> B5["t-1s"] --> B6["t=0"]
style B1 fill:#c0392b,color:#fff,stroke:#922b21,stroke-width:2px
style B2 fill:#e74c3c,color:#fff,stroke:#c0392b,stroke-width:2px
style B3 fill:#f39c12,color:#fff,stroke:#d68910,stroke-width:2px
style B4 fill:#f1c40f,color:#000,stroke:#d4ac0d,stroke-width:2px
style B5 fill:#2ecc71,color:#fff,stroke:#27ae60,stroke-width:2px
style B6 fill:#27ae60,color:#fff,stroke:#1e8449,stroke-width:2px
end
subgraph Trigger["⚡ Trigger"]
T["Event Detected!"]
end
subgraph Recording["📹 Recording Process"]
direction TB
R1["1. Dump buffer<br/>(pre-event data)"]
R2["2. Record live<br/>(post-event data)"]
R3["3. Save rosbag"]
R1 --> R2 --> R3
end
subgraph Output["💾 Output Rosbag"]
direction LR
O1["Pre-event<br/>messages<br/>(t-3s to t=0)"]
O2["Post-event<br/>messages<br/>(t=0 to t+5s)"]
O1 --- O2
end
CircularBuffer --> Trigger
Trigger --> Recording
Recording --> Output
style T fill:#e74c3c,color:#fff,stroke:#c0392b,stroke-width:3px
style R1 fill:#3498db,color:#fff,stroke:#2980b9,stroke-width:2px
style R2 fill:#9b59b6,color:#fff,stroke:#8e44ad,stroke-width:2px
style R3 fill:#27ae60,color:#fff,stroke:#1e8449,stroke-width:2px
style O1 fill:#e67e22,color:#fff,stroke:#d35400,stroke-width:2px
style O2 fill:#16a085,color:#fff,stroke:#138d75,stroke-width:2px
Key Concept: The circular buffer continuously stores the last N seconds of data. When triggered, only the relevant portion is extracted and combined with live post-event recording.
- Collision Detection: Capture sensor data from 5 seconds before impact to 10 seconds after
- Anomaly Detection: Record when unusual sensor readings occur
- Manual Capture: Trigger recordings on demand via topic or REST API
- Emergency Events: Automatically save data when safety systems activate
- Remote Monitoring: Trigger snapshots from a web dashboard or mobile app using the REST API
- ROS 2 Jazzy (Ubuntu 24.04)
- C++17 compatible compiler
- rosbag2 with MCAP support
# Clone the repository
git clone https://github.com/arpitg1304/ros_time_machine.git
cd ros_time_machine
# Build the package
colcon build --packages-select ros_time_machine
# Source the workspace
source install/setup.bash- Create a configuration file (or use the example):
# Copy the example config
cp src/ros_time_machine/config/example_snapshots.yaml my_config.yaml
# Edit to match your topics and trigger conditions
nano my_config.yaml- Launch the Time Machine node:
# With default config
ros2 launch ros_time_machine time_machine.launch.py
# With custom config
ros2 launch ros_time_machine time_machine.launch.py \
config_file:=/path/to/my_config.yaml
# With debug logging
ros2 launch ros_time_machine time_machine.launch.py \
config_file:=/path/to/my_config.yaml \
log_level:=debug- Trigger a recording:
# Manual trigger (requires manual_capture snapshot in config)
ros2 topic pub -1 /time_machine/manual_trigger std_msgs/msg/Bool "{data: true}"
# Or let automatic triggers activate based on your conditions- Find your recordings:
# Default location
ls /tmp/ros_time_machine/snapshots/
# Or your configured output pathThe Time Machine uses YAML configuration files to define snapshots, triggers, and recording parameters.
snapshots:
- name: "my_snapshot"
description: "Description of what this captures"
trigger:
topic: "/trigger/topic"
msg_type: "std_msgs/msg/Bool"
condition:
field: "data"
operator: "=="
value: true
recording:
topics:
- "/camera/image_raw"
- "/lidar/points"
pre_event_duration: 5.0 # seconds before trigger
post_event_duration: 10.0 # seconds after trigger
rate_limit:
max_triggers_per_minute: 3
output:
path: "/tmp/ros_time_machine/snapshots"
name_pattern: "{snapshot_name}_{timestamp}"
format: "mcap"- name: Unique identifier for this snapshot type
- description: Human-readable description
- topic: ROS topic to monitor
- msg_type: Full message type (e.g., "std_msgs/msg/Bool")
- condition: (Optional) Condition to evaluate
- field: Field path in message (e.g., "data" or "linear_acceleration.x")
- operator: Comparison operator (
==,!=,>,<,>=,<=) - value: Value to compare against
- topics: List of topics to record
- pre_event_duration: Seconds of data to capture before trigger
- post_event_duration: Seconds to continue recording after trigger
- max_triggers_per_minute: Maximum number of triggers allowed per minute
- max_triggers_per_second: (Alternative) Maximum 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: Storage format ("mcap" recommended, or "sqlite3")
snapshots:
- name: "manual_capture"
trigger:
topic: "/time_machine/manual_trigger"
msg_type: "std_msgs/msg/Bool"
condition:
field: "data"
operator: "=="
value: true
recording:
topics:
- "/camera/image"
- "/odom"
pre_event_duration: 2.0
post_event_duration: 3.0
output:
path: "/tmp/snapshots"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: 10snapshots:
- 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"When playing back rosbag files for testing, use simulated time:
# Terminal 1: Play bag with clock
ros2 bag play your_bag.mcap --clock
# Terminal 2: Launch Time Machine with simulated time
ros2 launch ros_time_machine time_machine.launch.py \
config_file:=my_config.yaml \
use_sim_time:=true# Get info about a recording
ros2 bag info /tmp/ros_time_machine/snapshots/manual_1234567890
# Play back a recording
ros2 bag play /tmp/ros_time_machine/snapshots/manual_1234567890
# View with rqt_bag (GUI)
rqt_bag /tmp/ros_time_machine/snapshots/manual_1234567890The REST API bridge allows you to trigger snapshots via HTTP requests without requiring ROS tools. This is perfect for:
- Web dashboards and mobile apps
- Remote operation and monitoring
- Integration with non-ROS systems
- Cloud-based control interfaces
The REST bridge requires FastAPI dependencies:
# Install FastAPI dependencies
pip3 install --break-system-packages fastapi uvicorn pydantic
# Build the REST bridge package
colcon build --packages-select ros_time_machine_rest_bridge
source install/setup.bash# Using launch file (recommended)
ros2 launch ros_time_machine_rest_bridge rest_bridge.launch.py
# With custom port
ros2 launch ros_time_machine_rest_bridge rest_bridge.launch.py port:=9000
# Direct run
ros2 run ros_time_machine_rest_bridge rest_bridge_nodeThe API will be available at http://localhost:8080 by default.
Health Check
curl http://localhost:8080/healthTrigger a Snapshot
# Simple trigger
curl -X POST http://localhost:8080/api/snapshots/trigger \
-H "Content-Type: application/json" \
-d '{"reason": "manual_api_trigger"}'
# With metadata
curl -X POST http://localhost:8080/api/snapshots/trigger \
-H "Content-Type: application/json" \
-d '{"reason": "collision_detected", "metadata": {"severity": "high", "location": "intersection_5"}}'List All Snapshots
curl http://localhost:8080/api/snapshotsGet Snapshot Details
curl http://localhost:8080/api/snapshots/{snapshot_id}Interactive API Documentation
Visit http://localhost:8080/docs in your browser for interactive Swagger UI documentation.
A test script is provided to verify the REST API functionality:
bash test_rest_api.shWant to try ROS Time Machine with real sensor data? See our guide on testing with publicly available datasets including:
- NVIDIA Isaac R2B - Multi-sensor dataset with cameras, LiDAR, and IMU (15.5 GB)
- AutoCore Ouster OS1-64 - High-quality LiDAR point clouds
- Intel RealSense D435 - RGB-D camera data
See docs/TESTING_WITH_DATASETS.md for download links, sample configs, and step-by-step instructions.
ros2 launch ros_time_machine time_machine.launch.py \
config_file:=/path/to/config.yaml \
log_level:=debug \
use_sim_time:=trueAvailable parameters:
config_file: Path to YAML configuration (default: example_snapshots.yaml)log_level: Logging level (debug, info, warn, error, fatal)use_sim_time: Use simulated time from /clock topic (default: false)
ros2 run ros_time_machine time_machine_node \
--ros-args \
-p config_file:=/path/to/config.yaml \
-p use_sim_time:=true \
--log-level debug- Check that topics are publishing:
ros2 topic list - Verify topic names in config match exactly (case-sensitive)
- Enable debug logging to see buffer status
- Ensure sufficient pre-event duration for buffer warm-up
- Increase buffer capacity by extending
pre_event_duration - Check that
use_sim_timeis set correctly when using bag playback - Verify rosbag is played with
--clockflag
- Reduce
pre_event_durationandpost_event_duration - Limit number of topics being recorded
- Use rate limiting to prevent excessive triggers
┌─────────────────┐
│ Config Manager │ Loads and validates YAML config
└────────┬────────┘
│
┌────────▼────────┐
│ Buffer Manager │ Circular buffers for each topic
│ │ • Dynamic topic discovery
│ │ • Time-based retrieval
└────────┬────────┘
│
┌────────▼────────┐
│ Trigger Monitor │ Monitors topics for conditions
│ │ • Condition evaluation
│ │ • Rate limiting
└────────┬────────┘
│
┌────────▼────────┐
│ Recorder │ Writes snapshots to disk
│ │ • Pre + post event data
│ │ • MCAP format
│ │ • Multi-threaded
└─────────────────┘
For detailed architecture diagrams and component specifications, see ARCHITECTURE.md.
Apache 2.0
Contributions welcome! Please open an issue or pull request.