Skip to content

Commit

Permalink
ROSBAG SNAPSHOT: documentation
Browse files Browse the repository at this point in the history
  • Loading branch information
Kevin Allen committed May 29, 2018
1 parent eeb4377 commit de67d28
Show file tree
Hide file tree
Showing 5 changed files with 16 additions and 19 deletions.
16 changes: 8 additions & 8 deletions test/test_rosbag/test/snapshot.test
Original file line number Diff line number Diff line change
@@ -1,18 +1,18 @@
<launch>
<node name="snapshot" pkg="rosbag" type="snapshot" args="">
<rosparam>
default_duration_limit: 1
default_memory_limit: 0.1
default_duration_limit: 1 # Maximum time difference between newest and oldest message, seconds, overrides -d flag
default_memory_limit: 0.1 # Maximum memory used by messages in each topic's buffer, MB, override -s flag
topics:
- test1 # Inherit defaults
- test2: # Override duration
- test1 # Inherit defaults
- test2: # Override duration limit, inherit memory limit
duration: 2
- test3: # Override both
duration: -1
memory: 0.002
- test3: # Override both limits
duration: -1 # Negative means no duration limit
memory: 0.00
</rosparam>
</node>
<!-- A bunch of fixed frequency publihers, each 64bits to make size calculations easy -->
<!-- A bunch of fixed frequency publishers, each 64bits to make size calculations easy -->
<node name="test1pub" pkg="rostopic" type="rostopic" args="pub /test1 std_msgs/Time '{data:{ secs: 0, nsecs: 0}}' -r2"/>
<node name="test2pub" pkg="rostopic" type="rostopic" args="pub /test2 std_msgs/Int64 'data: 1337' -r12"/>
<node name="test3pub" pkg="rostopic" type="rostopic" args="pub /test3 std_msgs/Float64 'data: 42.00' -r25" />
Expand Down
2 changes: 1 addition & 1 deletion tools/rosbag/include/rosbag/snapshoter.h
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@ class ROSBAG_DECL MessageQueue

/* Snapshoter node. Maintains a circular buffer of the most recent messages from configured topics
* while enforcing limits on memory and duration. The node can be triggered to write some or all
* of these buffers to a bag file via an action goal. Useful in live testing scenerios where interesting
* of these buffers to a bag file via a service call. Useful in live testing scenerios where interesting
* data may be produced before a user has the oppurtunity to "rosbag record" the data.
*/
class ROSBAG_DECL Snapshoter
Expand Down
11 changes: 2 additions & 9 deletions tools/rosbag/src/snapshot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ bool parseOptions(po::variables_map& vm, int argc, char** argv)
desc.add_options()
("help,h", "produce help message")
("trigger-write,t", "Write buffer of selected topcis to a bag file")
("pause,p", "Stop buffering new messages until resumed of write is triggered")
("pause,p", "Stop buffering new messages until resumed or write is triggered")
("resume,r", "Resume buffering new messages, writing over older messages as needed")
("size,s", po::value<double>()->default_value(-1), "Maximum memory per topic to use in buffering in MB. Default: no limit")
("duration,d", po::value<double>()->default_value(30.0), "Maximum difference between newest and oldest buffered message per topic in seconds. Default: 30")
Expand Down Expand Up @@ -132,14 +132,7 @@ bool parseVariablesMapClient(SnapshoterClientOptions& opts, po::variables_map co

/* Read configured topics and limits from ROS params
* TODO: use exceptions instead of asserts to follow style conventions
* This param should be set in the following (YAML represented) structure
* <rosparam>
* topics: # List of topics
* - /topic1 # Topic which will adopt default memory and duration limits
* - topic2: # Topic with overriden memory and duration limit
* memory: 5000 # 5000 Byte limit on buffered data from this topic
* duration: 30 # 30 second duration limit between newest and oldest message from this topic
* </rosparam>
* See snapshot.test in test_rosbag for an example
*/
void appendParamOptions(ros::NodeHandle& nh, SnapshoterOptions& opts)
{
Expand Down
2 changes: 2 additions & 0 deletions tools/rosbag_msgs/msg/SnapshotStatus.msg
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
# Describes the current status of a running 'rosbag snapshot' node

# Information about the buffer of subscribed topics
# The period, stamp, node_pub, and dropped_msgs fields are left empty
rosgraph_msgs/TopicStatistics[] topics
Expand Down
4 changes: 3 additions & 1 deletion tools/rosbag_msgs/srv/TriggerSnapshot.srv
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,9 @@ string filename # Name of bag file to save snapshot to.
string[] topics # List of topics to include in snapshot.
# If empty, all buffered topics will be written
time start_time # Earliest timestamp for a message to be included in written bag
time stop_time # Latest timestamp for a message to be incldued in written bag
# If time(0), start at the ealiest message in each topic's buffer
time stop_time # Latest timestamp for a message to be includued in written bag
# If time(0), stop at the most recent message in each topic's buffer

---

Expand Down

0 comments on commit de67d28

Please sign in to comment.