Main Content

ros2bagwriter

Create and write logs to ROS 2 bag log file

    Description

    Use the ros2bagwriter object to create a ROS 2 bag log file (.db3) in a folder that you specify. Use the write function to write logs to the ROS 2 bag file. Each log contains a topic, its corresponding timestamp, and a ROS 2 message. After writing the logs to the ROS 2 bag file, call the delete function to close the opened ROS 2 bag file, create the metadata.yaml file, and remove the object from memory.

    Note

    The ros2bagwriter object locks the created ROS 2 bag file. Delete and clear the ros2bagwriter object to use the ROS 2 bag file.

    Creation

    Description

    example

    bagwriter = ros2bagwriter(path) creates a ROS 2 bag file in the location specified by path and returns its corresponding ros2bagwriter object. Use the object to write records into the ROS 2 bag file. Use the path input argument to set the Path property.

    The name of the ROS 2 bag file is the name of the folder containing it. If the folders specified in path are not in the directory, the object creates them and places the ROS 2 bag file accordingly.

    example

    bagwriter = ros2bagwriter(path,Name=Value) sets the CacheSize property using a name-value argument.

    Properties

    expand all

    Note

    This property becomes a read-only after creation of the object.

    Path to the ROS 2 bag folder, specified as a string scalar or character vector.

    Data Types: char | string

    This property is read-only.

    Earliest timestamp of the messages written to the ROS 2 bag file, specified as a nonnegative numeric scalar in seconds.

    Data Types: single | double

    This property is read-only.

    Latest timestamp of the messages written to the ROS 2 bag file, specified as a nonnegative numeric scalar in seconds.

    Data Types: single | double

    This property is read-only.

    Number of messages written to the ROS 2 bag file, specified as a nonnegative numeric scalar.

    Data Types: single | double

    This property is read-only.

    Size of the cache for writing messages to the ROS 2 bag file, specified as a positive integer in bytes. This value specifies the total size of the messages, that the buffer of the cache holds in the object. If you reduce this value, the object writes more messages to the disk, which consumes more time and decreases performance of the drive.

    Data Types: uint64

    This property is read-only.

    Storage format of the ROS 2 bag file, specified as 'sqlite3'.

    Data Types: char | string

    This property is read-only.

    Serialization format of messages in the ROS 2 bag file, specified as 'cdr'. This value is the default binary serialization format used by Data Distribution Service (DDS), which is the default middleware of ROS 2.

    Data Types: char | string

    Object Functions

    writeWrite logs to ROS 2 bag log file
    deleteRemove ros2bagwriter object from memory

    Examples

    collapse all

    Extract the zip file that contains the ROS 2 bag log file and specify the full path to the log folder.

    unzip('ros2_netwrk_bag.zip');
    folderPath = fullfile(pwd,'ros2_netwrk_bag');

    Get all the information from the ROS 2 bag log file.

    bag2info = ros2("bag","info",folderPath);

    Create a ros2bagreader object that contains all messages in the log file.

    bag = ros2bagreader(folderPath);
    bag.AvailableTopics
    ans=4×3 table
                    NumMessages         MessageType                                                   MessageDefinition                                           
                    ___________    _____________________    ______________________________________________________________________________________________________
    
        /clock       1.607e+05     rosgraph_msgs/Clock      {'%...'                                                                                              }
        /cmd_vel             3     geometry_msgs/Twist      {'...'                                                                                               }
        /odom             5275     nav_msgs/Odometry        {'% The pose in this message should be specified in the coordinate frame given by header.frame_id...'}
        /scan              892     sensor_msgs/LaserScan    {'%...'                                                                                              }
    
    

    Select a subset of the messages, by applying filters to the topic and timestamp.

    start = bag.StartTime;
    odomBagSel = select(bag,"Time",[start start + 30e+09],"Topic","/odom")
    odomBagSel = 
      ros2bagreader with properties:
    
               FilePath: '/tmp/Bdoc22b_2134332_1954357/tpdf3c6620/ros-ex95368813/ros2_netwrk_bag/ros2_netwrk_bag.db3'
              StartTime: 1601984883976047597
                EndTime: 1601984913775044431
        AvailableTopics: [1x3 table]
            MessageList: [801x3 table]
            NumMessages: 801
    
    

    Get the messages in the selection.

    odomMsgs = readMessages(odomBagSel);

    Retrieve the list of timestamps from the topic. Convert the list to values with the double data type.

    timestamps = odomBagSel.MessageList.Time;
    timestamps_double = num2cell(double(timestamps)/1e+09);

    Create a ros2bagwriter object and a ROS 2 bag file in the specified folder.

    bagwriter = ros2bagwriter("myRos2bag");

    Write the messages related to the topic '/odom' to the ROS 2 bag file.

    write(bagwriter,"/odom",timestamps_double,odomMsgs)

    Close the bag file, remove the ros2bagwriter object from memory, and clear the associated object.

    delete(bagwriter)
    clear bagwriter

    Load the new ROS 2 bag log file.

    bagOdom = ros2bagreader("myRos2bag");

    Retrieve messages from the ROS 2 bag log file.

    msgs = readMessages(bagOdom);

    Plot the coordinates for the messages in the ROS 2 bag log file.

    Remove the myRos2bag file and the ros2_netwrk_bag file from memory to run the example again.

    plot(cellfun(@(msg) msg.pose.pose.position.x,msgs),cellfun(@(msg) msg.twist.twist.angular.z,msgs))

    Figure contains an axes object. The axes object contains an object of type line.

    Create a ros2bagwriter object and a ROS 2 bag file in the specified folder.

    bagwriter = ros2bagwriter("myRos2bag");

    Write a single log to the ROS 2 bag file.

    topic = "/odom";
    message = ros2message("nav_msgs/Odometry");
    timestamp = ros2time(1.6170e+09);
    write(bagwriter,topic,timestamp,message)

    Close the bag file, remove the ros2bagwriter object from memory, and clear the associated object.

    delete(bagwriter)
    clear bagwriter

    Create a ros2bagwriter object and a ROS 2 bag file in the specified folder. Specify the cache size for each message.

    bagwriter = ros2bagwriter("bag_files/my_bag_file",CacheSize=1500);

    Write multiple logs to the ROS 2 bag file.

    message1 = ros2message("nav_msgs/Odometry");
    message2 = ros2message("geometry_msgs/Twist");
    message3 = ros2message("sensor_msgs/Image");
    write(bagwriter, ...
          ["/odom","cmd_vel","/camera/rgb/image_raw"], ...
          {ros2time(1.6160e+09),ros2time(1.6170e+09),ros2time(1.6180e+09)}, ...
          {message1,message2,message3})

    Close the bag file, remove the ros2bagwriter object from memory, and clear the associated object.

    delete(bagwriter)
    clear bagwriter

    Create a ros2bagwriter object and a ROS 2 bag file in the specified folder.

    bagwriter = ros2bagwriter("myBag");

    Write multiple logs for the same topic to the ROS 2 bag file.

    pointMsg1 = ros2message("geometry_msgs/Point");
    pointMsg1.x = 1;
    pointMsg2 = ros2message("geometry_msgs/Point");
    pointMsg2.x = 2;
    pointMsg3 = ros2message("geometry_msgs/Point");
    pointMsg3.x = 3;
    write(bagwriter, ...
          "/point", ...
          {1.6190e+09, 1.6200e+09,1.6210e+09}, ...
          {pointMsg1,pointMsg2,pointMsg3})

    Close the bag file, remove the ros2bagwriter object from memory, and clear the associated object.

    delete(bagwriter)
    clear bagwriter

    Version History

    Introduced in R2022b