Record experiments with rosbag (MCAP)
Capture a complete telemetry trace of any bringup — joints, FSM
transitions, safety status, policy I/O — to a MCAP
file. MCAP is the cross-language replacement for the legacy sqlite3
rosbag backend; it's the default in ROS 2 Jazzy and what Foxglove
Studio / mcap-cli consume directly.
Record everything
The one-liner most operators want:
ros2 bag record -s mcap --all -o lite_$(date +%Y%m%d_%H%M%S)
Breaking down the flags:
| Flag | Meaning |
|---|---|
-s mcap | Use the MCAP storage plugin. Without this you get the legacy sqlite3 .db3 format. |
--all | Subscribe every topic visible at start time. Late-joiners are not picked up automatically — restart the recorder if you launch new nodes. |
-o <dir> | Output directory name. The recorder writes <dir>/<dir>_0.mcap plus a metadata.yaml. Stamping with $(date …) keeps successive runs from colliding. |
Stop with Ctrl+C. The MCAP file is finalized on shutdown.
Record a focused subset
--all is heavy on disk and wall-clock CPU. For a tuning session
where you only care about the control loop, name the topics
explicitly:
ros2 bag record -s mcap -o tuning_$(date +%Y%m%d_%H%M%S) \
/lite/joint_states \
/control_mode \
/standby_controller/state \
/safety_status \
/joy \
/tf /tf_static
For a policy session, also add the policy command topic
/remote_policy_controller/command (bar_msgs/MITCommand). For piano
runs, capture /piano/target_keys and /piano/key_state; both are
pianist_msgs/PianoKeyState, and the pair is the source for offline
F1 / precision / recall computed via pianist_metrics.
Tips
- Where to put bags: pick a path outside the workspace
(
~/bags/...) socolcon builddoesn't try to index multi-GB.mcapfiles. The workspace's.gitignorealready excludesbag_*/*.mcapat the repo root, but a path under~is safest. - TRANSIENT_LOCAL topics (e.g.
/robot_description,/safety_status): the recorder captures the latched value the moment it subscribes, so startros2 bag recordafter the launch is up if you want the URDF in the bag. - Sim time: when recording from MuJoCo the timestamps come from
/clock, so the bag is already on sim time. Replay with--clockand start downstream consumers withuse_sim_time:=trueif you want consistentnow()semantics across the playback. - Compression: MCAP supports built-in zstd compression — add
--compression-mode message --compression-format zstd. Roughly 2× shrink on typical float-heavy/lite/joint_statestraffic, at ~5% CPU overhead.
Inspect a recording
# Topic list + message counts + duration
ros2 bag info -s mcap <bag-dir>
# Or use mcap-cli directly on the file (no ROS needed):
mcap info <bag-dir>/<bag-dir>_0.mcap
mcap list channels <bag-dir>/<bag-dir>_0.mcap
mcap-cli ships in the pixi env (available as mcap … inside
pixi shell). For interactive plotting, drop the .mcap into
Foxglove Studio (foxglove-studio package,
also pixi-installed).
Replay
ros2 bag play -s mcap <bag-dir>
For replaying into a stack that uses sim time, add
--clock 200 (publishes /clock at 200 Hz) and launch your
consumers with use_sim_time:=true. Note that replay does not
re-run the controllers — it just re-publishes the recorded topics.
To replay an action stream into the live controller chain, see
Switch controllers manually.
Post-process piano runs
The pianist_metrics numpy package (installed via pixi pypi-deps from
the upstream pianist-tracking-mj repo) is the source of truth for
piano evaluation metrics. Capture both topics during the run:
ros2 bag record -s mcap -o piano_$(date +%Y%m%d_%H%M%S) \
/piano/target_keys /piano/key_state
Then offline:
import pianist_metrics as pm
# target, pressed: (T, 88) bool arrays from the bag
precision = pm.precision(target, pressed)
recall = pm.recall(target, pressed)
f1 = pm.f1(target, pressed)
There is no live ROS node computing these — bag-based post-processing is the deployment-side evaluation path.
See also
- Frozen schemas — why
/control_mode//safety_status/ etc. fields don't shift between releases (so old bags stay readable). - MCAP spec & tooling — file format,
mcap-clireference, ecosystem.