Skip to main content
Deterministic replay lets you take a recording from a real robot run — or from a simulation — and play it back through your Units so they process exactly the same data in exactly the same order. The result is reproducible: the same recording produces the same outputs every time, regardless of the machine or time of day.
The open-source Replayer class described on this page publishes messages back through the live transport layer and is available to all users. Full deterministic replay — where a DeterministicReplayer drives handlers directly without requiring a running transport stack — is a premium feature. See DeterministicReplayer below for details.

The Replayer class

Replayer reads an MCAP file and republishes each message on the Basis transport as if it were being received live. Units that are subscribed to the recorded topics receive the messages through their normal subscriber callbacks.

Constructor and Config

namespace basis::replayer {
  struct Config {
    bool loop = false;           // replay the recording in a continuous loop
    std::filesystem::path input; // path to the .mcap file
  };
}

class Replayer {
public:
  Replayer(
    Config config,
    basis::core::transport::TransportManager &transport_manager,
    basis::core::transport::CoordinatorConnector &coordinator_connector
  );
};
Replayer does not own the TransportManager or CoordinatorConnector; you are responsible for their lifetimes.

Run()

virtual bool Run();
Run() opens the MCAP file, iterates over every message in timestamp order, and publishes each one through transport_manager using a raw publisher keyed by topic name. It blocks until the recording is exhausted (or forever if loop is true). Returns true on success, false if the recording could not be opened or is invalid.

StartTime() and EndTime()

basis::core::MonotonicTime StartTime();
basis::core::MonotonicTime EndTime();
These return the monotonic timestamps of the first and last messages in the recording, read from the MCAP file’s statistics block. Call them after constructing a Replayer but before calling Run() to know the time span of the recording.
basis::Replayer replayer(config, transport_manager, coordinator_connector);

auto start = replayer.StartTime();
auto end   = replayer.EndTime();

BASIS_LOG_INFO("Recording spans {:.3f}s",
    (end - start).ToSeconds());

replayer.Run();

How replay publishes messages

Internally, Replayer maintains a map from topic name to a PublisherRaw (an untyped publisher that sends pre-serialized bytes). For each message read from the MCAP file, it looks up or creates a PublisherRaw for that topic and calls Publish() with the raw bytes. It also manages a special time publisher on the /basis/time topic so that rate-based handlers and simulated-time code receive the correct playback timestamp.
// Members on Replayer — relevant to understanding the publish path
std::unordered_map<std::string,
    std::shared_ptr<basis::core::transport::PublisherRaw>> publishers;
std::shared_ptr<basis::core::transport::Publisher<
    basis::core::transport::proto::Time>> time_publisher;
Because messages go through the normal transport, any subscriber in the same process or a connected process receives them. This makes Replayer useful for both live debugging and automated integration tests that run Units in a test process alongside a replayer.

Example: replaying a recording

1

Set up the transport and coordinator

basis::core::logging::InitializeLoggingSystem();

auto transport_manager = basis::CreateStandardTransportManager();
auto coordinator_connector = basis::core::transport::CoordinatorConnector::Create();
2

Configure and construct the Replayer

basis::replayer::Config config;
config.input = "/data/recordings/robot_run_2024.mcap";
config.loop  = false;

basis::Replayer replayer(config, *transport_manager, *coordinator_connector);
3

Inspect the recording time span (optional)

BASIS_LOG_INFO("Replaying {:.3f}s of data",
    (replayer.EndTime() - replayer.StartTime()).ToSeconds());
4

Run

bool ok = replayer.Run();
if (!ok) {
  BASIS_LOG_ERROR("Replay failed");
}

The DeterministicReplayer class

DeterministicReplayer is a premium feature that provides stronger guarantees than the transport-based Replayer. Instead of publishing messages through the transport layer, it drives a Unit’s HandlerPubSub map directly, bypassing all network and thread-scheduling non-determinism. The Unit base class declares DeterministicReplayer as a friend, giving it access to the internal handlers map and deserialization_helpers:
// From unit.h
class Unit {
  // ...
  friend class basis::DeterministicReplayer;
  std::map<std::string, HandlerPubSub *> handlers;
  std::unordered_map<std::string, DeserializationHelper> deserialization_helpers;
  // ...
};
For each message in the recording, DeterministicReplayer:
  1. Looks up the topic in the Unit’s handlers map to find the TypeErasedCallback registered for that topic.
  2. Calls deserialization_helpers[type_name] to deserialize the raw bytes into a std::shared_ptr<const void>.
  3. Invokes the TypeErasedCallback directly with the deserialized message pointer and a HandlerExecutingCallback*.
  4. If the synchronizer fires, calls the HandlerExecutingCallback to run the handler and collect outputs.
Because the DeterministicReplayer never touches the transport, outputs, or timing subsystems, the same recording always produces the same handler invocations in the same order — regardless of system load.
To use DeterministicReplayer, contact Basis Robotics about a commercial license. The Replayer class and all recording infrastructure are open source.

Why this enables identical test results

The key insight is that robot handler code is a pure function of its inputs: given the same messages in the same order, it should always produce the same outputs. Non-determinism in conventional systems comes from:
  • Wall-clock timers firing at slightly different times
  • Thread scheduling affecting message delivery order
  • Network latency between pub and sub
DeterministicReplayer eliminates all three. It feeds messages in the exact recorded order and at the exact recorded timestamps, using UnitInitializeOptions{.create_subscribers = false} to suppress real subscriber creation. There is no transport, no threading, and no wall clock.

Practical workflow: record on robot, replay in CI

1

Record on the robot

Add a RecordingSettings block to your launch file or attach a Recorder to your Unit:
launch.yaml
recording:
  async: true
  name: ci_capture
  directory: /data/recordings
  patterns:
    - .*   # record everything
See Recording for the full API.
2

Archive the MCAP file

Copy the .mcap file to your artifact store (S3, a network share, CI artifact storage, etc.). The file is self-describing — it includes all schemas — so no recompilation is needed to read it.
3

Write a replay test

In CI, construct your Unit with create_subscribers = false, then run DeterministicReplayer against the archived file:
// Premium: DeterministicReplayer drives handlers directly
MyUnit unit;
unit.CreateTransportManager();
unit.Initialize({.create_subscribers = false});

basis::DeterministicReplayer replayer(
    {.input = "ci_capture.mcap"}, unit);
replayer.Run();

// Assert on captured outputs
ASSERT_EQ(expected_output_count, replayer.OutputCount("/control/cmd"));
For open-source users, use Replayer with a live Unit in a test process:
// Open source: Replayer publishes through the transport
MyUnit unit;
unit.WaitForCoordinatorConnection();
unit.CreateTransportManager();
unit.Initialize();

basis::replayer::Config config;
config.input = "ci_capture.mcap";

basis::Replayer replayer(config, *transport_manager, *coordinator_connector);
replayer.Run();
4

Assert and report

Compare outputs against a known-good baseline. Because the recording is fixed, any deviation in output indicates a regression in your handler code.
Record a diverse set of robot scenarios — edge cases, recovery behaviors, sensor dropouts — and keep them as a regression suite. Running all of them in CI costs only the time to replay the files, not the time to physically reproduce the scenarios.
Replay correctness depends on your handler code being stateless with respect to wall time and external I/O. Handlers that read from files, call external services, or branch on std::chrono::system_clock::now() will produce different results during replay. Use basis::core::MonotonicTime (which is advanced by the replayer) for all time-dependent logic.

Next steps

Recording

Set up the Recorder or AsyncRecorder and configure topic filtering

Testing overview

The Inputs→Handler→Outputs model and how it enables deterministic testing

Build docs developers (and LLMs) love