Package Summary
Rosrecord has been deprecated as of ROS-1.1.5. Please transition over to use the rosbag package instead. 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.
- Author: Jeremy Leibs (leibs@willowgarage.com), python code by James Bowman (jamesb@willowgarage.com) and Ken Conley (kwc@willowgarage.com)
- License: BSD
- Repository: ros
- Source: svn https://code.ros.org/svn/ros/stacks/ros_comm/tags/ros_comm-1.4.8
As of ROS 1.1.5, rosrecord has been deprecated. |
For C Turtle, see rosbag |
Status
rosrecord was phased out in favor of a more unified interface, rosbag. rosrecord has been deprecated as of ROS 1.1.5.
All of its functionality is now contained in rosbag. In fact, rosrecord is now simply a wrapper around the underlying rosbag API.
Code API
The rosrecord programmatic API does not yet have a rosbag equivalent. It is still the main way to interact with bagfiles programmatically. However, this API is expected to change somewhat substantially in the move to rosbag and is slated for eventual deprecation.
ros::record::Recorder
The ros::record::Recorder allows you to populate a bag file without going through ros.
The Recorder has a fairly simpe interface for pushing messages into a bag file. open is used to open the file. Messages can then be added with sequential calls to record. When the bag file is complete, close it using close.
Example: To put your own message into a bag file
For more information see the C++ Code API.
ros::record::Player
The ros::record::Player class enables parsing of bag files without going through ros. This is very useful for converting .bag files to different formats.
The Player has an unfortunately complicated API at the moment. A set of callbacks can be registered on the Player using the addHandler call. This call takes a topic (which may be specified as "*"), and is templated on a particular type. The corresponding callback will be invoked when a message matching this topic and type is extracted from the bag through a call to player.nextMsg().
NOTE: The Player also has the ability to optionally construct a shifted and scaled time-line for your messages. This is what the start_time in the open call corresponds to. When the The callback is invoked it is passed TWO times. The first is a shifted and scaled representation of time, the second is the original timestamp stored in the bag. Internally rosplay does a remapping from the first time-stamp in your bag to whatever time is passed in as start_time to the open call. Additionally, if you have constructed your bag with a time_scale, the Player will scale the duration beween subsequent messages appropriately. For example, supposing your bag contains 3 messages with times: 30, 40, 50. If start_time is specified as 100 and time_scale is specified as 5, the shifted/scaled times passed into your callback would be 100, 102, 104.
Example: Iterating through a bag file programmatically
1 #include "ros/ros.h" 2 #include <string> 3 #include "rosrecord/Player.h" 4 #include "rosrecord/AnyMsg.h" 5 #include "std_msgs/String.h" 6 7 // Generic callback to be invoked for any message 8 void all_handler(std::string name, // Topic name 9 ros::Message* m, // Message pointer 10 ros::Time t, // Shifted and scaled time 11 ros::Time t_orig, // Message timestamp 12 void* n) // Void pointer 13 { 14 // Do something that doesn't require understanding the message contents 15 } 16 17 void string_handler(std::string name, // Topic name 18 std_msgs::String* str, // Message pointer 19 ros::Time t, // Shifted and scaled time 20 ros::Time t_orig, // Message timestamp 21 void* n) // Void pointer 22 { 23 // Do something with the std_msgs::String 24 } 25 26 int main(int argc, char **argv) 27 { 28 ros::record::Player player; 29 30 if (player.open(std::string("my.bag"), ros::Time())) 31 { 32 player.addHandler<AnyMsg>(std::string("*"), // Topic name 33 &all_handler, // Handler 34 NULL, // void* 35 false); // Don't deserialize 36 37 // NOTE: serialization is required by the signature of the 38 // handler above 39 player.addHandler<std_msgs::String>(std::string("chatter"), 40 &string_handler, 41 NULL); 42 } 43 44 // Spin until we have consumed the bag 45 while(player.nextMsg()) {} 46 47 return 0; 48 }
For more information see the C++ Code API.
rosrecord.py
The rosrecord module provides a simple API for iterating through messages in a bag file. By default, it will automatically deserialize each message for you into the appropriate Message instance. For higher performance, it can also operate in 'raw' mode, which returns the serialized bytes for each message.
Iterating over messages:
Rebagging messages:
For more information see the Python Code API
Bag File Maintenance
The following maintenance approaches should rarely be necessary except with particularly old bags. Going forward, the rosbag fix command should be all that is necessary.
Updating bag files after a msg change
When messages change md5sums will change. To update bags use the rosbag fix tool
Fixing md5sums after a move or rename
If you have moved or renamed a message but not changed the content, it is possible to convert old bag files to the new name. To do this you must generate a file with the old and new names as well as the old and new md5sums.
old/name OLDMD5 new/name NEWMD5
It is up to the user to generate these. I've attached an example file for our recent changes for ros release 0.4 combined_md5s.fixed
To generate this we used a combination of checking out old versions of the messages in their old position and the roslib script
roslib/scripts/gendeps.py -m "message/filename.msg"
This will return the md5sum for that message (it is not necessary for the messages to have been autogenerated)
Use this file with the script
rosrecord/scripts/fixed_moved_messages.py combined_md5s.fixed old.bag new.bag
Fixing bag ordering
When logging incoming messages are buffered but there is a race condition for getting a lock on the output file. Depending on how things work out this may mean that the order of items in the bag is out of order(up to seconds off, which can't be easily buffered). There is a script bagsort.py which will sort the bag to be in chronological order. This will get rid of dropped packets due to this.
rosrecord/scripts/bagsort.py old.bag new.bag
ROS 0.6: Fixing md5sums after the md5sum algorithm has been changed
ROS 0.6 included a change to the md5sum generation algorithm. This, unfortunately, breaks all current bags in the system. To bring your bags up to date use the python script: fix_md5sums.py in the rosrecord package.
The standard invocation is:
rosrun rosrecord fix_md5sums.py mybagfile.bag
When this completes, mybagfile.bag will have the new md5sum, and the original will be stored in mybagfile.bag.old
Other useful invocations are:
rosrun rosrecord fix_md5sums.py *.bag
find . -name *.bag | xargs rosrun rosrecord fix_md5sums.py
(NOTE: you may have to chmod the fix_md5sums.py file so that it is executable before you can rosrun it)
Technical Details
Please see bag format.
Command-Line Tools
The following command-line tools are being phased out. Please try to avoid using them. Instead use the corresponding rosbag utilities.
rosrecord
This command has been replaced by rosbag record
Usage: rosrecord [options] TOPIC1 [TOPIC2 TOPIC3...] rosrecord logs ROS message data to a file. Options: -c <num> : Only receive <num> messages on each topic -f <prefix> : Prepend file prefix to beginning of bag name (name will always end with date stamp) -F <fname> : Record to a file named exactly <fname>.bag -a : Record all published messages. -v : Display a message every time a message is received on a topic -m : Maximize internal buffer size in MB (Default: 256MB) 0 = infinite. -s : (EXPERIMENTAL) Enable snapshot recording (don't write to file unless triggered) -t : (EXPERIMENTAL) Trigger snapshot recording -h : Display this help message
rosrecord will generate a ".bag" file (so named for historical reasons) with the contents of all topics that you pass to it. The file simply contains interlaced, serialized ros messages dumped directly to a single file as they come in over the wire. This is the most performance and disk-friendly recording format possible. If you are recording messages at a high-bandwidth, such as from cameras, it is strongly recommended you run rosrecord on the same machine as the camera, and specify the file destination as being on the local machine disk.
If you run rosrecord with the "-a" option, it will attempt to record ALL messages available in the system. However, since this information requires polling the master periodically, it will likely miss the first several messages published on any topic.
As of ROS-0.10, rosrecord contains an experimental snapshot recorder. This will keep a rolling buffer (the size of the maximum internal buffer), which can be triggered by calling rosrecord -t. The API for using rosrecord in snapshot mode will likely change in ROS-0.11 based on feedback about 0.10.
rosrecord is installed to the $ROS_ROOT/bin directory and so can be used without needing rosrun.
Example usages
- Record all messages in the system.
rosrecord -a
Record all messages on the topics chatter and babble
rosrecord chatter babble
rosplay
This command has been replaced by rosbag play and rosbag info
usage: rosplay [-a][-p][-t <sec>] BAG1 [BAG2] -c check the contents of the bag without playing back -a playback all messages without waiting -p start in paused mode -s sec sleep <sec> sleep duration after every advertise call (to allow subscribers to connect) -t start <sec> seconds into the files -b publish the time at which the bag was recorded on the /time topic, at a frequency of <freq> Hz. -r increase the publishing rate with a factor <rate_change> -q sz Use an outgoing queue of size sz (defaults to 0) -h display this help message
rosplay will take the contents of 1 or more bag file, and play them back in a time-synchronized fashion. Time synchronization occurs based on the global time-stamps at which messages were received. Playing will begin immediately, and then future messages will be published according to the relative offset times. If two separate bag files are used, they are treated as a single bag with interlaced times according to the timestamps. This means if you record 1 bag, wait an hour, and record a second bag, when you play them back together you will have an hour-long dead period in the middle of your playback.
If you do not want to observe playback timing, the "-a" option will playback all messages from the file as fast as possible. Note that for large files this will often lead to exceeding your incoming buffers.
Additionally, during playing, you can pause at any time by hitting space. When paused, you can step through messages by pressing s.
To check the contents of a bag, run with the "-c" option. This will not play back the logfile, but will instead determine the count of each type of message in the file.
rosplay is installed to the $ROS_ROOT/bin directory and so can be used without needing rosrun.
Example usage:
rosplay demo_log.bag rosplay topics1.bag topics2.bag rosplay -a demo_log.bag
rosrebag
This command has been replaced by rosbag filter
rosrebag is a command-line tool for converting bag files using Python expressions. The Python expression can access any of the Python builtins plus:
topic: the topic of the message
m: the message
t: time of message. The time is represented as a rospy Time object (t.secs, t.nsecs)
Usage: rosrebag in.bag out.bag filter-expression filter-expression can be any Python-legal expression. The following variables are available: * topic: name of topic * m: message * t: time of message (t.secs, t.nsecs)
Example:
rosrebag chatter.bag rebag.bag "'1' in m.data"
In order to test the filter pattern that you pass in, you can also pass in a print expression. For example:
rosrebag --print "m.data" chatter.bag rebag.bag "'1' in m.data"
Example output:
NO MATCH hello world 68 NO MATCH hello world 69 NO MATCH hello world 70 MATCH hello world 71 NO MATCH hello world 72 NO MATCH hello world 73