API review
Proposer: Jeremy Leibs
Present at review:
- List reviewers
Proposed command-line APIs
rosbag record
Usage: rosbag record TOPIC1 [TOPIC2 TOPIC3 ...] Record a bag file with the contents of specified topics. Options: -h, --help show this help message and exit -a, --all record all topics -q, --quiet suppress console output -o PREFIX, --output-prefix=PREFIX append PREFIX to beginning of bag name (name will always end with date stamp) -O NAME, --output-name=NAME record to bag with namename NAME.bag -z, --gzip compress the message with gzip -j, --bzip compress the message with bzip2 -b SIZE, --buffsize=SIZE use in internal buffer of SIZE MB (Default: 256, 0 = infinite) -l NUM, --limit=NUM only record NUM messages on each topic
rosbag play
Usage: rosbag play BAGFILE1 [BAGFILE2 BAGFILE3 ...] Play back the contents of one or more bag files in a time-synchronized fashion. Options: -h, --help show this help message and exit -q, --quiet suppress console output -i, --immediate play back all messages without waiting --pause start in paused mode --queue=SIZE use an outgoing queue of size SIZE (defaults to 0) --frequency=HZ publish the log time at a frequency of HZ (default: 100) -d SEC, --delay=SEC Sleep SEC seconds after every advertise call (to allow subscribers to connect). -r FACTOR, --rate=FACTOR multiply the publish rate by FACTOR -s TIME, --start=TIME start TIME seconds into the bag files
rosbag info
Usage: rosbag info BAGFILE Summarize the contents of a bag file. Options: -h, --help show this help message and exit
Returns bag information in YAML format:
bag: 2009-12-16-10-49-50.bag version: 1.2 start_time: 1260989391943123000 end_time: 1260989403343135999 length: 11400012999 topics: - name: /bar count: 58 datatype: std_msgs/String md5sum: 992ce8a1687cec8c8bd883ec73ca41d1
rosbag check
Usage: rosbag check BAG [-g RULEFILE] [EXTRARULES1 EXTRARULES2 ...] Options: -h, --help show this help message and exit -g RULEFILE, --genrules=RULEFILE Generate a rulefile named RULEFILE. -a, --append Append to the end of an existing rulefile after loading it. -n, --noplugins Do not load rulefiles via plugins.
rosbag fix
Usage: rosbag fix INBAG OUTBAG [EXTRARULES1 EXTRARULES2 ...] Options: -h, --help show this help message and exit -n, --noplugins Do not load rulefiles via plugins.
rosbag filter
Usage: rosbag filter: INBAG OUTBAG EXPRESSION 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) Options: -h, --help show this help message and exit --print=PRINT-EXPRESSION Python expression to print for verbose debugging. Uses same variables as filter-expression.
Proposed programmatic APIs
C++
1 namespace rosbag
2 {
3 //! Base class for rosbag exceptions
4 class Exception : public std::runtime_error;
5
6 //! Exception thrown if trying to add or read from an unopened
7 // recorder/player
8 class BagNotOpenException : public Exception;
9
10 //! Exception thrown when assorted IO problems
11 class BagIOException : public Exception;
12
13 //! Exception thrown if an invalid MsgPos (such as from another bag)
14 // is passed to seek
15 class InvalidMsgPosException : public Exception;
16
17 //! Exception thrown if trying to instantiate a MsgInstance as the
18 // wrong type
19 class InstantiateException : public Exception;
20
21
22 //! Class for writinging to a bagfile
23 class Writer
24 {
25 //! Constructor
26 Writer();
27
28 //! Destructor
29 ~Writer();
30
31 //! Open a bagfile by name
32 bool open(const std::string &file_name);
33
34 //! Close bagfile
35 /*!
36 * Make sure bagfile is written out to disk, index is appended,
37 * file descriptor is closed, etc..
38 */
39 void close();
40
41 //! Write a message to the bag file
42 /*!
43 * \param topic_name The topic name
44 * \param time Timestamp of the message
45 * \param msg A pointer to the message to be added.
46 *
47 * Can throw BagNotOpenException or BagIOException
48 */
49 void write(const std::string& topic_name, ros::Time time, ros::Message::ConstPtr msg, );
50
51 //! Write a message to the bag file
52 /*!
53 * \param topic_name The topic name
54 * \param time Timestamp of the message
55 * \param msg A MessageInstance as reterned by reader
56 *
57 * Can throw BagNotOpenException or BagIOException
58 */
59 void write(const std::string& topic_name, ros::Time time, MessageInstance& msg, );
60 };
61
62 //! Class representing the location of a message in a bagfile
63 /*!
64 * This is stored in the index and allows for seeking in the bag
65 */
66 class MessageId
67 {
68 bool valid() const;
69
70 const std::string getTopic();
71 const std::string getDatatype();
72 const std::string getMd5sum();
73 const ros::Time getTime();
74
75 /*!
76 * Templated type-check
77 */
78 template <class T>
79 bool isType<T>();
80
81 private:
82
83 // Not part of user interface, but used to do seek on file
84 uint64_t pos;
85 };
86
87 //! Class representing an actual message
88 /*!
89 * This is basically identical to a MessageId, but additionally
90 * stores the data from the bag.
91 */
92 class MessageInstance : public MessageId
93 {
94 template <class T>
95 boost::shared_ptr<M> instantiate() const;
96 };
97
98
99 //! Typedef for index: map of topic_name -> list of MsgPos
100 typedef std::map<std::string, std::vector<MessageId> > Index;
101
102
103 //! Class for playing from a bagfile
104 class Reader
105 {
106 //! Constructor
107 Reader();
108
109 //! Destructor
110 ~Reader();
111
112 //! Open a bagfile by name
113 bool open(const std::string &file_name);
114
115 //! Close bagfile
116 void close();
117
118 //! Return the bagfile index.
119 /*!
120 * The bagfile index is a map of topics which point to vectors of
121 * MessageId. These MessageIds can then be used for seeking.
122 */
123 const Index& getIndex();
124
125 //! Seek to a specific location in a bagfile from the index
126 void seek(const MessageId& pos);
127
128 //! Seek to a specific location in the bagfile based on time
129 void seek(ros::Time time);
130
131 //! Return next message from player
132 MsgInstance next();
133
134 };
135 }
Example Usage
1 int main()
2 {
3 rosbag::Writer writer;
4 rosbag::Reader reader;
5
6 if (!writer.open('out.bag'))
7 ROS_FATAL("Could not open bag for writing.");
8 if (!reader.open('in.bag'))
9 ROS_FATAL("Could not open bag for reading.");
10
11 MessageInstance inst;
12
13 while ((inst = reader.next()).valid())
14 {
15 if (inst.isType<my_msgs::MyType>())
16 {
17 // Is there a slicker way of doing this with a change to topic tools?
18 my_msgs::MyType::Ptr msg = inst.instantiate<my_msgs::MyType>();
19
20 // Do something with msg here...
21
22 // Add it into our writer
23 writer.add(inst.topic, inst.time, msg);
24 }
25 }
26
27 reader.close();
28 writer.close();
29 }
Python API
The python API will mirror the ROS API with subtle pythonic differences where appropriate. I will do those in a separate review once the C++ API is determined.
Question / concerns / comments
Enter your thoughts on the API and any questions / concerns you have here. Please sign your name. Anything you want to address in the API review should be marked down here before the start of the meeting.
Jeremy
Should -O append .bag/.gz for you or not? What should behavior of -O foo.bag be? What about -zf foo.bag. Or worse: -zf foo.bag.bz2.
How hard should we work to avoid re-using options between different commands? For example -p to pause in rosplay but -p for prefix in rosrecord. Or -a is all in record but -a is append in check.
How important are single-character options in play for --pause, --queue, and --frequency?
- How should I deal with constness of things in the Player.
Josh
- C++ API
RosbagException -> Exception (already in the rosbag namespace)
JL: Done
- Recorder and Player don't seem like the right names for these classes -- they don't record/play, rather they are more like Reader/Writer
JL: Done
Msg -> Message in all instances
JL: Done
MsgPos seems like it should be MessageID or similar
JL: Done
- Constructors that take a filename would be nice
JL: Done
getIndex() should return a const Index&
JL: Done
- Why no 'prev()' ?
JL: Is there a usecase for this? Complicates some stuff. I think it could be added later since addition of prev wouldn't break API.
MsgInstance should probably have getTopic()/etc. instead of exposing the members explicitly
JL: Made MessageInstance a MessageID, and put all of those in there.
Manually comparing datatype seems error prone (especially since you really have to compare datatype and md5sum). A MsgInstance::isType<MyMessage>() call would help.
JL: Totally agree -- good call.
- Would be useful to be able to filter by which topics you're interested in
JL: Any suggestions for how you would like to do this syntactically? Note: the index is stored by topicname, so you could iterate through that and seek to each message of a particular type. But we could potentially wrap that with a helper of some form.
I assume the comment for InstantiateException means the wrong type, not wrong time?
JL: Yeah. Although perhapse an "Instance" exception would be the wrong time
- Does the reader do any in-memory caching, or does it just read off disk on demand?
JL: What kind of comments did you have in mind?
Ken
- rosbag looks like it will be a nice, powerful command
- Python: can we just copy rosrecord.py into rosbag.py? Given that we may or may not have a ROS 0.12, it seems like it's the API we have to run with. I would probably rename 'logplayer' to something more appropriate (i.e. 'reader' or just 'player'). The only other real 'API' is the rebag routine, which is functionally different from above.
JL: Question here comes down to the importance of deprecating the rosrecord.py API.
--frequency: would --hz be easier to remember, given rostopic hz?
JL: Probably
-g RULEFILE is a bit weird (i.e. g==gen), as it doesn't always generate a rule file. Rather, it just refers to a rule file, and assumes the action based on the presence of other options.
- typo: "use an outgoign"
JL: Fixed
no love for rosrebag? . More seriously, if we're looking to condense the toolchain, rosrebag should either get folded in or die.
JL: Adding as rosbag filter.
Patrick
- Command-line API
- Overall looks really nice
- What about rebagging? My suggestion was "rosbag filter".
- I vote -O append the extension for you.
- C++ API
- Generally agree with Josh's comments.
Really want Player/Reader to have an iterator interface. I'd love to use BOOST_FOREACH or standard algorithms on bags and next() doesn't provide that.
I'd consider having instantiate() return a NULL pointer instead of throwing. Then you can do:
if (my_msgs::MyType::Ptr msg = inst.instantiate<my_msgs::MyType>()) { // Do something with msg here... }
JL: This seems fairly reasonable.
Maybe too much to expect for 0.11 but food for thought: it seems there are a few different standard ways we want to traverse bag files. It could be very elegant to have Reader and/or Index use Boost.MultiIndex to allow visiting messages:
- sequenced in the order written
- ordered by time
- grouped by topic
Needs to be a way to take a MessageInstance and add it to a Writer without knowing the actual message type.
JL: Added a different Write
Nit: would spell MessageID as MessageId. I think capitalized abbreviations and camel-case don't mix well.
JL: Agreed
Meeting agenda
To be filled out by proposer based on comments gathered during API review period
Conclusion
Package status change mark change manifest)
Action items that need to be taken.
Major issues that need to be resolved