Contenuto principale

startRecording

Start recording live topic data from ROS 2 network into bag file

Since R2026a

    Description

    startRecording(bagrecorder, Name=Value) creates a bag file and starts writing to it based on the storage and recorder configurations, using one or more name-value arguments.

    example

    Examples

    collapse all

    Start, pause, resume, and stop a recording session dynamically while messages are being published from multiple data sources. The publishing continues uninterrupted, and you can control recording manually or based on external conditions.

    Create a node for a vehicle system that publishes telemetry, camera, and lidar data.

    vehicleNode = ros2node('/VehicleNode');
    telemetryPub = ros2publisher(vehicleNode,'/car_telemetry','std_msgs/String');
    cameraPub    = ros2publisher(vehicleNode,'/car_camera_feed','sensor_msgs/Image');
    temperaturePub     = ros2publisher(vehicleNode,'/temperature','sensor_msgs/Temperature');

    By default, the recorder captures all topics. In this example, you record topics using IncludeRegex and ExcludeTopics filters. It includes all topics matching /car* but excludes the back camera feed.

    bagName = "DynamicRecordingBag" + string(datetime("now",Format="_yyyyMMdd_HHmmss"));
    recorder = ros2bagrecorder(bagName);
    
    startRecording(recorder,IncludeRegex='/car*',ExcludeTopics='/car_camera_feed');
    disp("Recording started.");
    Recording started.
    

    Set up message structures for telemetry, camera, and temperature data.

    % Set up for callback structure
    pubStruct.telemetryPub = telemetryPub;
    pubStruct.cameraPub = cameraPub;
    pubStruct.temperaturePub = temperaturePub;
    
    % Set up for sample image message structure
    telemetryMsg = ros2message(telemetryPub);
    temperatureMsg = ros2message(temperaturePub);
    imageMsg = ros2message(cameraPub);
    imageMsg.height = uint32(480);
    imageMsg.width = uint32(640);
    imageMsg.step = uint32(imageMsg.width * 3); 
    imageMsg.encoding = 'rgb8';
    
    pubStruct.telemetryMsg = telemetryMsg;
    pubStruct.imageMsg = imageMsg;
    pubStruct.temperatureMsg = temperatureMsg;

    Publishing continues regardless of the recording state. The callback function sends telemetry, camera, and temperature messages at regular intervals until all messages are published or the script ends.

    function publishCallback(timerObj, pubStruct)
        idx = timerObj.UserData.idx;
        totalMsgs = timerObj.UserData.totalMsgs;
    
        if idx <= totalMsgs
            % Telemetry
            pubStruct.telemetryMsg.data = sprintf('Telemetry data message %d', idx);
            send(pubStruct.telemetryPub, pubStruct.telemetryMsg);
    
            % Back Camera
            pubStruct.imageMsg.data = randi([0 255], pubStruct.imageMsg.height, pubStruct.imageMsg.width, 3, 'uint8');
            send(pubStruct.cameraPub, pubStruct.imageMsg);
    
            % Temperature
            pubStruct.temperatureMsg.temperature = randi([0 100]);
            send(pubStruct.temperaturePub, pubStruct.temperatureMsg);
    
            timerObj.UserData.idx = idx + 1;
        else
            stop(timerObj);
        end
    end

    Create and start a timer to publish messages at a fixed rate.

    timerObj = timer('ExecutionMode','fixedRate','Period',0.5,...
        'TimerFcn', @(timerObj,~)publishCallback(timerObj,pubStruct));
    timerObj.UserData.idx = 1;
    timerObj.UserData.totalMsgs = 2000;
    start(timerObj);

    You can pause, resume, or stop recording manually at any time or based on external conditions. These options enable you to control the recording during a live session.

    pauseRecording(recorder);
    disp("Paused recording");
    Paused recording
    
    resumeRecording(recorder);
    disp("Resumed recording");
    Resumed recording
    
    stopRecording(recorder);
    disp("Recording stopped.")
    Recording stopped.
    

    After stopping the recording, inspect the recorded topics and message types.

    bagReader = ros2bagreader(bagName);
    disp(bagReader.AvailableTopics(:,1:2))
                          NumMessages      MessageType  
                          ___________    _______________
    
        /car_telemetry         1         std_msgs/String
    

    You can see that messages published when the recording was active are stored in the bag file, while those published when the recording was paused are not recorded.

    Input Arguments

    collapse all

    ROS 2 bag recorder, specified as a ros2bagrecorder object.

    Name-Value Arguments

    expand all

    Specify optional pairs of arguments as Name1=Value1,...,NameN=ValueN, where Name is the argument name and Value is the corresponding value. Name-value arguments must appear after other arguments, but the order of the pairs does not matter.

    Before R2021a, use commas to separate each name and value, and enclose Name in quotes.

    Example: startRecording(IncludeTopics = {"/cam", "/imu"}, IncludeTopicTypes = {'sensor_msgs/Image'})

    Include Filters

    expand all

    Name of topics to include during recording, specified as a string scalar, character vector, or a cell array.

    You can apply or modify these settings only through the startRecording function when you start a new recording on the same object after deleting the previous bag file.

    Name of topic types to include during recording, specified as a string scalar, character vector, or a cell array.

    You can apply or modify these settings only through the startRecording function when you start a new recording on the same object after deleting the previous bag file.

    Name of topics to include during recording, that matches regular expressions, specified as a string scalar or character vector.

    You can apply or modify these settings only through the startRecording function when you start a new recording on the same object after deleting the previous bag file.

    Option to record hidden topics, specified as "false" (0) or "true" (1).

    You can apply or modify these settings only through the startRecording function when you start a new recording on the same object after deleting the previous bag file.

    Option to record unpublished topics, specified as "false" (0) or "true" (1).

    You can apply or modify these settings only through the startRecording function when you start a new recording on the same object after deleting the previous bag file.

    Exclude Filters

    expand all

    Name of topics to exclude from recording, specified as a string scalar, character vector, or a cell array.

    You can apply or modify these settings only through the startRecording function when you start a new recording on the same object after deleting the previous bag file.

    Name of topic types to exclude from recording, specified as a string scalar, character vector, or a cell array.

    You can apply or modify these settings only through the startRecording function when you start a new recording on the same object after deleting the previous bag file.

    Name of topics to exclude from recording, that matches regular expressions, specified as a string scalar or character vector.

    You can apply or modify these settings only through the startRecording function when you start a new recording on the same object after deleting the previous bag file.

    Option to exclude leaf topics from recording, specified as "false" (0) or "true" (1).

    You can apply or modify these settings only through the startRecording function when you start a new recording on the same object after deleting the previous bag file.

    Version History

    Introduced in R2026a