Main Content

rosbag

Open and parse rosbag log file

Description

bag = rosbag(filename) creates an indexable BagSelection object, bag, that contains all the message indexes from the rosbag at path filename. To get a BagSelection object, use rosbag. To access the data, call readMessages or timeseries to extract relevant data.

A rosbag, or bag, is a file format for storing ROS message data. They are used primarily to log messages within the ROS network. You can use these bags for offline analysis, visualization, and storage. See the ROS Wiki page for more information about rosbags.

example

bagInfo = rosbag('info',filename) returns information as a structure, bagInfo, which is about the contents of the rosbag at filename.

rosbag info filename displays information in the MATLAB® Command Window about the contents of the rosbag at filename. The information includes the number of messages, start and end times, topics, and message types.

example

Examples

collapse all

Retrieve information from the rosbag. Specify the full path to the rosbag if it is not already available on the MATLAB® path.

bagselect = rosbag('ex_multiple_topics.bag');

Select a subset of the messages, filtered by time and topic.

bagselect2 = select(bagselect,'Time',...
    [bagselect.StartTime bagselect.StartTime + 1],'Topic','/odom');

To view information about a rosbag log file, use rosbag info filename, where filename is a rosbag (.bag) file.

rosbag info 'ex_multiple_topics.bag'
Path:     /tmp/Bdoc24b_2725827_1909987/tp5f907611/ros-ex32890909/ex_multiple_topics.bag
Version:  2.0
Duration: 2:00s (120s)
Start:    Dec 31 1969 19:03:21.34 (201.34)
End:      Dec 31 1969 19:05:21.34 (321.34)
Size:     23.6 MB
Messages: 36963
Types:    gazebo_msgs/LinkStates [48c080191eb15c41858319b4d8a609c2]
          nav_msgs/Odometry      [cd5e73d190d741a2f92e81eda573aca7]
          rosgraph_msgs/Clock    [a9c97c1d230cfc112e270351a944ee47]
          sensor_msgs/LaserScan  [90c7ef2dc6895d81024acba2ac42f369]
Topics:   /clock               12001 msgs  : rosgraph_msgs/Clock   
          /gazebo/link_states  11999 msgs  : gazebo_msgs/LinkStates
          /odom                11998 msgs  : nav_msgs/Odometry     
          /scan                  965 msgs  : sensor_msgs/LaserScan 

Get transformations from rosbag (.bag) files by loading the rosbag and checking the available frames. From these frames, use getTransform to query the transformation between two coordinate frames.

Load the rosbag.

bag = rosbag('ros_turtlesim.bag');

Get a list of available frames.

frames = bag.AvailableFrames;

Get the latest transformation between two coordinate frames.

tf = getTransform(bag,'world',frames{1});

Check for a transformation available at a specific time and retrieve the transformation. Use canTransform to check if the transformation is available. Specify the time using rostime.

tfTime = rostime(bag.StartTime + 1);
if (canTransform(bag,'world',frames{1},tfTime))
    tf2 = getTransform(bag,'world',frames{1},tfTime);
end

Load the rosbag.

bag = rosbag('ros_turtlesim.bag');

Select a specific topic.

bSel = select(bag,'Topic','/turtle1/pose');

Read messages as a structure. Specify the DataFormat name-value pair when reading the messages. Inspect the first structure in the returned cell array of structures.

msgStructs = readMessages(bSel,'DataFormat','struct');
msgStructs{1}
ans = struct with fields:
        MessageType: 'turtlesim/Pose'
                  X: 5.5016
                  Y: 6.3965
              Theta: 4.5377
     LinearVelocity: 1
    AngularVelocity: 0

Extract the xy points from the messages and plot the robot trajectory.

Use cellfun to extract all the X and Y fields from the structure. These fields represent the xy positions of the robot during the rosbag recording.

xPoints = cellfun(@(m) double(m.X),msgStructs);
yPoints = cellfun(@(m) double(m.Y),msgStructs);
plot(xPoints,yPoints)

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

Input Arguments

collapse all

Name of file and path for the rosbag you want to access, specified as a string scalar or character vector. This path can be relative or absolute.

Output Arguments

collapse all

Selection of rosbag messages, returned as a BagSelection object handle.

Information about the contents of the rosbag, returned as a structure. This structure contains fields related to the rosbag file and its contents. A sample output for a rosbag as a structure is:

Path:     \ros\data\ex_multiple_topics.bag
Version:  2.0
Duration: 2:00s (120s)
Start:    Dec 31 1969 19:03:21.34 (201.34)
End:      Dec 31 1969 19:05:21.34 (321.34)
Size:     23.6 MB
Messages: 36963
Types:    gazebo_msgs/LinkStates [48c080191eb15c41858319b4d8a609c2]
          nav_msgs/Odometry      [cd5e73d190d741a2f92e81eda573aca7]
          rosgraph_msgs/Clock    [a9c97c1d230cfc112e270351a944ee47]
          sensor_msgs/LaserScan  [90c7ef2dc6895d81024acba2ac42f369]
Topics:   /clock               12001 msgs  : rosgraph_msgs/Clock   
          /gazebo/link_states  11999 msgs  : gazebo_msgs/LinkStates
          /odom                11998 msgs  : nav_msgs/Odometry     
          /scan                  965 msgs  : sensor_msgs/LaserScan 

Version History

Introduced in R2019b