rosbag Documentation

rosbag: ROS Bag Tools

This is a set of tools for recording from and playing back to ROS topics. It is intended to be high performance and avoids deserialization and reserialization of the messages.

  • Homepage: http://ros.org/wiki/rosbag
  • rosbag is a set of tools and API's for recording/writing messages to bag files and playing/reading them back.

    Code API

    The C++ and Python API's are provided for serializing bag files. The C++ API consists of the following classes:

    Here's a simple example of writing to a bag file:

    #include "rosbag/bag.h"
    ...
    rosbag::Bag bag("test.bag", rosbag::bagmode::Write);
    std_msgs::Int32 i;
    i.data = 42;
    bag.write("numbers", ros::Time::now(), i);
    bag.close();
    

    Likewise, to read from that bag file:

    #include "rosbag/bag.h"
    ...
    rosbag::Bag bag("test.bag");
    rosbag::View view(bag, rosbag::TopicQuery("numbers"));
    BOOST_FOREACH(rosbag::MessageInstance const m, view)
    {
        std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
        if (i != NULL)
        	std::cout << i->data << std::endl;
    }
    bag.close();
    

    The Python API is similar. Writing to a bag file:

    import rosbag
    from std_msgs.msg import Int32, String
    bag = rosbag.Bag('test.bag', 'w')
    i = Int32()
    i.data = 42
    bag.write('numbers', i);
    bag.close();
    

    Example usage for read:

    import rosbag
    bag = rosbag.Bag('test.bag')
    for topic, msg, t in bag.read_messages('numbers'):
        print msg.data
    bag.close();
    
     All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


    rosbag
    Author(s): Jeremy Leibs (leibs@willowgarage.com), James Bowman (jamesb@willowgarage.com), Ken Conley (kwc@willowgarage.com), and Tim Field (tfield@willowgarage.com)
    autogenerated on Fri Jan 11 10:11:38 2013