diff --git a/README.md b/README.md new file mode 100644 index 0000000..be7919b --- /dev/null +++ b/README.md @@ -0,0 +1,138 @@ +# rosbag_snapshot + +Solution for [this ros_comm issue](https://github.com/ros/ros_comm/issues/1399) which acts similarly to the deprecated `rosrecord -s` command but with additional features. It is added as a new package here rather than patching `rosbag` based on [the discussion here](https://github.com/ros/ros_comm/pull/1414). + +It subscribes to topics and maintains a buffer of recent messages like a dash cam. This is useful in live testing where unexpected events can occur which would be useful to have data on but the opportunity is missed if `rosbag record` was not running (disk space limits make always running `rosbag record` impracticable). Instead, users may run snapshot in the background and save data from the recent past to disk as needed. + + +## Usage + +`rosbag_snapshot` can be configured through command line flags and with ROS params for more granular control. By default, the command will run in server mode (buffering data). When certain flags are used, program will act as a client by requesting that the server write data to disk or freezing the buffer to preserve interesting data until a user can decide what to write. + +### CLI usage + +``` +$ rosrun rosbag_snapshot snapshot -h +Usage: snapshot [options] [topic1 topic2 ...] + +Buffer recent messages until triggered to write or trigger an already running instance. + +Options: + -h [ --help ] produce help message + -t [ --trigger-write ] Write buffer of selected topcis to a bag file + -p [ --pause ] Stop buffering new messages until resumed or + write is triggered + -r [ --resume ] Resume buffering new messages, writing over + older messages as needed + -s [ --size ] arg (=-1) Maximum memory per topic to use in buffering in + MB. Default: no limit + -d [ --duration ] arg (=30) Maximum difference between newest and oldest + buffered message per topic in seconds. Default: + 30 + -o [ --output-prefix ] arg When in trigger write mode, prepend PREFIX to + name of writting bag file + -O [ --output-filename ] arg When in trigger write mode, exact name of + written bag file + --topic arg Topic to buffer. If triggering write, write only + these topics instead of all buffered topics. +``` + +###### Hold a buffer of the last 30 seconds of data from selected topics until triggered to write +`rosrun rosbag_snapshot snapshot -d 30 /tf /odom /camera/image_color /camera/camera_info /velodyne_points` + +###### Buffer the most recent gigabyte of the following topics in the camera namespace +`ROS_NAMESPACE=camera rosrun rosbag_snapshot snapshot -s 1000 image_rect_color camera_info` + + +### Example launch file +``` + + + + 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 limit, inherit memory limit + duration: 2 + - test3: # Override both limits + duration: -1 # Negative means no duration limit + memory: 0.00 + + + +``` + +## Client examples + +###### Write all buffered data to `.bag` +`rosrun rosbag_snapshot snapshot -t` + +###### Write buffered data from selected topics to `new_lighting.bag` +`rosrun rosbag_snapshot snapshot -t -o new_lighting /camera/image_raw /camera/camera_info` + +###### Write all buffered data to `/home/user/crashed_into_wall.bag` +`rosrun rosbag_snapshot snapshot -t -O /home/user/crashed_into_wall` + +###### Pause buffering of new data, holding current buffer in memory until -t or -r is used +`rosrun rosbag_snapshot snapshot -p` + +###### Resume buffering new data +`rosrun rosbag_snapshot snapshot -r` + +###### Call trigger service manually, specifying absolute window start and stop time for written data + +``` +$ rosservice call /trigger_snapshot "filename: 'short_control_instability.bag' +topics: +- '/tf' +- '/odom' +- '/wrench' +- '/motors/cmd' +start_time: + secs: 62516 + nsecs: 0 +stop_time: + secs: 62528 + nsecs: 0" +``` + +###### View status of buffered data (useful for future tools/GUI) + +``` +$ rostopic echo /snapshot_status +topics: + - + topic: "/test" + node_pub: '' + node_sub: "/snapshot_1527185221120605085" + window_start: + secs: 62516 + nsecs: 761000000 + window_stop: + secs: 62521 + nsecs: 984000000 + delivered_msgs: 524 + dropped_msgs: 0 + traffic: 2096 + period_mean: + secs: 0 + nsecs: 0 + period_stddev: + secs: 0 + nsecs: 0 + period_max: + secs: 0 + nsecs: 0 + stamp_age_mean: + secs: 0 + nsecs: 0 + stamp_age_stddev: + secs: 0 + nsecs: 0 + stamp_age_max: + secs: 0 + nsecs: 0 +enabled: True +--- +``` diff --git a/rosbag_snapshot/CMakeLists.txt b/rosbag_snapshot/CMakeLists.txt index 70ca417..42c7f33 100644 --- a/rosbag_snapshot/CMakeLists.txt +++ b/rosbag_snapshot/CMakeLists.txt @@ -18,6 +18,15 @@ add_executable(snapshot src/snapshot.cpp) add_dependencies(snapshot ${catkin_EXPORTED_TARGETS}) target_link_libraries(snapshot rosbag_snapshot ${catkin_LIBRARIES}) +if(CATKIN_ENABLE_TESTING) + find_package(catkin REQUIRED COMPONENTS roslint rostest) + roslint_python(test) + roslint_cpp() + roslint_add_test() + + add_rostest(test/snapshot.test) +endif() + install(TARGETS snapshot RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) diff --git a/rosbag_snapshot/include/rosbag_snapshot/snapshotter.h b/rosbag_snapshot/include/rosbag_snapshot/snapshotter.h index 99fe1bb..bf7400c 100644 --- a/rosbag_snapshot/include/rosbag_snapshot/snapshotter.h +++ b/rosbag_snapshot/include/rosbag_snapshot/snapshotter.h @@ -34,9 +34,6 @@ #ifndef ROSBAG_SNAPSHOT_SNAPSHOTTER_H #define ROSBAG_SNAPSHOT_SNAPSHOTTER_H -#include -#include -#include #include #include #include @@ -45,9 +42,14 @@ #include #include #include -#include -#include "rosbag/bag.h" -#include "rosbag/macros.h" +#include +#include +#include +#include +#include +#include +#include +#include namespace rosbag_snapshot { @@ -96,7 +98,8 @@ struct ROSBAG_DECL SnapshotterOptions ros::Duration status_period = ros::Duration(1)); // Add a new topic to the configuration - void addTopic(std::string const& topic, ros::Duration duration_limit = SnapshotterTopicOptions::INHERIT_DURATION_LIMIT, + void addTopic(std::string const& topic, + ros::Duration duration_limit = SnapshotterTopicOptions::INHERIT_DURATION_LIMIT, int32_t memory_limit = SnapshotterTopicOptions::INHERIT_MEMORY_LIMIT); }; @@ -134,7 +137,7 @@ class ROSBAG_DECL MessageQueue boost::shared_ptr sub_; public: - MessageQueue(SnapshotterTopicOptions const& options); + explicit MessageQueue(SnapshotterTopicOptions const& options); // Add a new message to the internal queue if possible, truncating the front of the queue as needed to enforce limits void push(SnapshotMessage const& msg); // Removes the message at the front of the queue (oldest) and returns it @@ -171,7 +174,7 @@ class ROSBAG_DECL MessageQueue class ROSBAG_DECL Snapshotter { public: - Snapshotter(SnapshotterOptions const& options); + explicit Snapshotter(SnapshotterOptions const& options); // Sets up callbacks and spins until node is killed int run(); @@ -207,7 +210,8 @@ class ROSBAG_DECL Snapshotter void topicCB(const ros::MessageEvent& msg_event, boost::shared_ptr queue); // Service callback, write all of part of the internal buffers to a bag file according to request parameters - bool triggerSnapshotCb(rosbag_snapshot_msgs::TriggerSnapshot::Request& req, rosbag_snapshot_msgs::TriggerSnapshot::Response& res); + bool triggerSnapshotCb(rosbag_snapshot_msgs::TriggerSnapshot::Request& req, + rosbag_snapshot_msgs::TriggerSnapshot::Response& res); // Service callback, enable or disable recording (storing new messages into queue). Used to pause before writing bool enableCB(std_srvs::SetBool::Request& req, std_srvs::SetBool::Response& res); // Set recording_ to false and do nessesary cleaning, CALLER MUST OBTAIN LOCK @@ -219,7 +223,8 @@ class ROSBAG_DECL Snapshotter // Write the parts of message_queue within the time constraints of req to the queue // If returns false, there was an error opening/writing the bag and an error message was written to res.message bool writeTopic(rosbag::Bag& bag, MessageQueue& message_queue, std::string const& topic, - rosbag_snapshot_msgs::TriggerSnapshot::Request& req, rosbag_snapshot_msgs::TriggerSnapshot::Response& res); + rosbag_snapshot_msgs::TriggerSnapshot::Request& req, + rosbag_snapshot_msgs::TriggerSnapshot::Response& res); }; // Configuration for SnapshotterClient diff --git a/rosbag_snapshot/package.xml b/rosbag_snapshot/package.xml index 6021494..84cb217 100644 --- a/rosbag_snapshot/package.xml +++ b/rosbag_snapshot/package.xml @@ -3,7 +3,7 @@ rosbag_snapshot 0.0.0 The rosbag_snapshot package - + Kevin Allen David V. Lu!! BSD diff --git a/rosbag_snapshot/src/snapshot.cpp b/rosbag_snapshot/src/snapshot.cpp index 6af375e..d5eb753 100644 --- a/rosbag_snapshot/src/snapshot.cpp +++ b/rosbag_snapshot/src/snapshot.cpp @@ -32,12 +32,13 @@ * POSSIBILITY OF SUCH DAMAGE. ********************************************************************/ -#include "rosbag_snapshot/snapshotter.h" -#include "rosbag/exceptions.h" +#include +#include -#include "boost/program_options.hpp" +#include #include #include +#include namespace po = boost::program_options; @@ -66,11 +67,15 @@ bool parseOptions(po::variables_map& vm, int argc, char** argv) ("trigger-write,t", "Write buffer of selected topcis to a bag file") ("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()->default_value(-1), "Maximum memory per topic to use in buffering in MB. Default: no limit") - ("duration,d", po::value()->default_value(30.0), "Maximum difference between newest and oldest buffered message per topic in seconds. Default: 30") - ("output-prefix,o", po::value()->default_value(""), "When in trigger write mode, prepend PREFIX to name of writting bag file") + ("size,s", po::value()->default_value(-1), + "Maximum memory per topic to use in buffering in MB. Default: no limit") + ("duration,d", po::value()->default_value(30.0), + "Maximum difference between newest and oldest buffered message per topic in seconds. Default: 30") + ("output-prefix,o", po::value()->default_value(""), + "When in trigger write mode, prepend PREFIX to name of writting bag file") ("output-filename,O", po::value(), "When in trigger write mode, exact name of written bag file") - ("topic", po::value >(), "Topic to buffer. If triggering write, write only these topics instead of all buffered topics."); + ("topic", po::value >(), + "Topic to buffer. If triggering write, write only these topics instead of all buffered topics."); // clang-format on po::positional_options_description p; p.add("topic", -1); @@ -82,13 +87,13 @@ bool parseOptions(po::variables_map& vm, int argc, char** argv) } catch (boost::program_options::error const& e) { - std::cout << "rosbag snapshot: " << e.what() << std::endl; + std::cout << "rosbag_snapshot: " << e.what() << std::endl; return false; } if (vm.count("help")) { - std::cout << "Usage: rosbag snapshot [options] [topic1 topic2 ...]" << std::endl + std::cout << "Usage: rosrun rosbag_snapshot snapshot [options] [topic1 topic2 ...]" << std::endl << std::endl << "Buffer recent messages until triggered to write or trigger an already running instance." << std::endl << std::endl; @@ -103,10 +108,12 @@ bool parseVariablesMap(SnapshotterOptions& opts, po::variables_map const& vm) if (vm.count("topic")) { std::vector topics = vm["topic"].as >(); - BOOST_FOREACH (std::string& str, topics) + for (const std::string& str : topics) + { opts.addTopic(str); + } } - opts.default_memory_limit_ = int(MB_TO_BYTES * vm["size"].as()); + opts.default_memory_limit_ = static_cast(MB_TO_BYTES * vm["size"].as()); opts.default_duration_limit_ = ros::Duration(vm["duration"].as()); return true; } @@ -132,7 +139,7 @@ bool parseVariablesMapClient(SnapshotterClientOptions& opts, po::variables_map c /* Read configured topics and limits from ROS params * TODO: use exceptions instead of asserts to follow style conventions - * See snapshot.test in test_rosbag for an example + * See snapshot.test for an example */ void appendParamOptions(ros::NodeHandle& nh, SnapshotterOptions& opts) { @@ -142,7 +149,7 @@ void appendParamOptions(ros::NodeHandle& nh, SnapshotterOptions& opts) // Override program options for default limits if the parameters are set. double tmp; if (nh.getParam("default_memory_limit", tmp)) - opts.default_memory_limit_ = int(MB_TO_BYTES * tmp); + opts.default_memory_limit_ = static_cast(MB_TO_BYTES * tmp); if (nh.getParam("default_duration_limit", tmp)) opts.default_duration_limit_ = ros::Duration(tmp); @@ -195,7 +202,7 @@ void appendParamOptions(ros::NodeHandle& nh, SnapshotterOptions& opts) if (mem_limit.getType() == XmlRpcValue::TypeDouble) { double mb = mem_limit; - mem = int(MB_TO_BYTES * mb); + mem = static_cast(MB_TO_BYTES * mb); } else if (mem_limit.getType() == XmlRpcValue::TypeInt) { diff --git a/rosbag_snapshot/src/snapshotter.cpp b/rosbag_snapshot/src/snapshotter.cpp index 19197f8..8f23ba8 100644 --- a/rosbag_snapshot/src/snapshotter.cpp +++ b/rosbag_snapshot/src/snapshotter.cpp @@ -36,7 +36,6 @@ #include #include #include -#include #include #include #include @@ -44,7 +43,8 @@ #include #include #include -#include "rosbag_snapshot/snapshotter.h" +#include +#include using std::string; using boost::shared_ptr; @@ -130,7 +130,7 @@ ros::Duration MessageQueue::duration() const bool MessageQueue::preparePush(int32_t size, ros::Time const& time) { // If new message is older than back of queue, time has gone backwards and buffer must be cleared - if (!queue_.empty() and time < queue_.back().time) + if (!queue_.empty() && time < queue_.back().time) { ROS_WARN("Time has gone backwards. Clearing buffer for this topic."); _clear(); @@ -180,7 +180,7 @@ void MessageQueue::_push(SnapshotMessage const& _out) { int32_t size = _out.msg->size(); // If message cannot be added without violating limits, it must be dropped - if (not preparePush(size, _out.time)) + if (!preparePush(size, _out.time)) return; queue_.push_back(_out); // Add size of new message to running count to maintain correctness @@ -202,14 +202,14 @@ MessageQueue::range_t MessageQueue::rangeFromTimes(Time const& start, Time const range_t::second_type end = queue_.end(); // Increment / Decrement iterators until time contraints are met - if (not start.isZero()) + if (!start.isZero()) { - while (begin != end and (*begin).time < start) + while (begin != end && (*begin).time < start) ++begin; } - if (not stop.isZero()) + if (!stop.isZero()) { - while (end != begin and (*(end - 1)).time > stop) + while (end != begin && (*(end - 1)).time > stop) --end; } return range_t(begin, end); @@ -288,7 +288,8 @@ void Snapshotter::subscribe(string const& topic, boost::shared_ptr } bool Snapshotter::writeTopic(rosbag::Bag& bag, MessageQueue& message_queue, string const& topic, - rosbag_snapshot_msgs::TriggerSnapshot::Request& req, rosbag_snapshot_msgs::TriggerSnapshot::Response& res) + rosbag_snapshot_msgs::TriggerSnapshot::Request& req, + rosbag_snapshot_msgs::TriggerSnapshot::Response& res) { // acquire lock for this queue boost::mutex::scoped_lock l(message_queue.lock); @@ -296,7 +297,7 @@ bool Snapshotter::writeTopic(rosbag::Bag& bag, MessageQueue& message_queue, stri MessageQueue::range_t range = message_queue.rangeFromTimes(req.start_time, req.stop_time); // open bag if this the first valid topic and there is data - if (not bag.isOpen() and range.second > range.first) + if (!bag.isOpen() && range.second > range.first) { try { @@ -331,7 +332,7 @@ bool Snapshotter::writeTopic(rosbag::Bag& bag, MessageQueue& message_queue, stri bool Snapshotter::triggerSnapshotCb(rosbag_snapshot_msgs::TriggerSnapshot::Request& req, rosbag_snapshot_msgs::TriggerSnapshot::Response& res) { - if (not postfixFilename(req.filename)) + if (!postfixFilename(req.filename)) { res.success = false; res.message = "invalid"; @@ -371,7 +372,7 @@ bool Snapshotter::triggerSnapshotCb(rosbag_snapshot_msgs::TriggerSnapshot::Reque // Write each selected topic's queue to bag file if (req.topics.size()) { - BOOST_FOREACH (std::string& topic, req.topics) + for (std::string& topic : req.topics) { // Resolve and clean topic try @@ -393,24 +394,24 @@ bool Snapshotter::triggerSnapshotCb(rosbag_snapshot_msgs::TriggerSnapshot::Reque continue; } MessageQueue& message_queue = *(*found).second; - if (not writeTopic(bag, message_queue, topic, req, res)) + if (!writeTopic(bag, message_queue, topic, req, res)) return true; } } // If topic list empty, record all buffered topics else { - BOOST_FOREACH (buffers_t::value_type& pair, buffers_) + for (const buffers_t::value_type& pair : buffers_) { MessageQueue& message_queue = *(pair.second); std::string const& topic = pair.first; - if (not writeTopic(bag, message_queue, topic, req, res)) + if (!writeTopic(bag, message_queue, topic, req, res)) return true; } } // If no topics were subscribed/valid/contained data, this is considered a non-success - if (not bag.isOpen()) + if (!bag.isOpen()) { res.success = false; res.message = res.NO_DATA; @@ -423,7 +424,7 @@ bool Snapshotter::triggerSnapshotCb(rosbag_snapshot_msgs::TriggerSnapshot::Reque void Snapshotter::clear() { - BOOST_FOREACH (buffers_t::value_type& pair, buffers_) + for (const buffers_t::value_type& pair : buffers_) { pair.second->clear(); } @@ -452,12 +453,12 @@ bool Snapshotter::enableCB(std_srvs::SetBool::Request& req, std_srvs::SetBool::R return true; } // Obtain write lock and update state if requested state is different from current - if (req.data and not recording_) + if (req.data && !recording_) { boost::upgrade_to_unique_lock write_lock(read_lock); resume(); } - else if (not req.data and recording_) + else if (!req.data && recording_) { boost::upgrade_to_unique_lock write_lock(read_lock); pause(); @@ -473,14 +474,15 @@ void Snapshotter::publishStatus(ros::TimerEvent const& e) if (!status_pub_.getNumSubscribers()) return; - // TODO: consider options to make this faster (caching and updating last status, having queues track their own status) - rosbag_snapshot_msgs::SnapshotStatus msg; + // TODO(any): consider options to make this faster + // (caching and updating last status, having queues track their own status) + rosbag_msgs::SnapshotStatus msg; { boost::shared_lock lock(state_lock_); msg.enabled = recording_; } std::string node_id = ros::this_node::getName(); - BOOST_FOREACH (buffers_t::value_type& pair, buffers_) + for (const buffers_t::value_type& pair : buffers_) { rosgraph_msgs::TopicStatistics status; status.node_sub = node_id; @@ -498,7 +500,7 @@ int Snapshotter::run() return 0; // Create the queue for each topic and set up the subscriber to add to it on new messages - BOOST_FOREACH (SnapshotterOptions::topics_t::value_type& pair, options_.topics_) + for (SnapshotterOptions::topics_t::value_type& pair : options_.topics_) { string topic = ros::names::resolve(nh_.getNamespace(), pair.first); fixTopicOptions(pair.second); @@ -532,7 +534,7 @@ int SnapshotterClient::run(SnapshotterClientOptions const& opts) if (opts.action_ == SnapshotterClientOptions::TRIGGER_WRITE) { ros::ServiceClient client = nh_.serviceClient("trigger_snapshot"); - if (not client.exists()) + if (!client.exists()) { ROS_ERROR("Service %s does not exist. Is snapshot running in this namespace?", "trigger_snapshot"); return 1; @@ -556,18 +558,18 @@ int SnapshotterClient::run(SnapshotterClientOptions const& opts) } // Resolve filename relative to clients working directory to avoid confusion - if (req.filename.empty()) // Special case of no specified file, ensure still in working directory of client + if (req.filename.empty()) // Special case of no specified file, ensure still in working directory of client req.filename = "./"; boost::filesystem::path p(boost::filesystem::system_complete(req.filename)); req.filename = p.string(); rosbag_snapshot_msgs::TriggerSnapshotResponse res; - if (not client.call(req, res)) + if (!client.call(req, res)) { ROS_ERROR("Failed to call service"); return 1; } - if (not res.success) + if (!res.success) { ROS_ERROR("%s", res.message.c_str()); return 1; @@ -577,7 +579,7 @@ int SnapshotterClient::run(SnapshotterClientOptions const& opts) else if (opts.action_ == SnapshotterClientOptions::PAUSE || opts.action_ == SnapshotterClientOptions::RESUME) { ros::ServiceClient client = nh_.serviceClient("enable_snapshot"); - if (not client.exists()) + if (!client.exists()) { ROS_ERROR("Service %s does not exist. Is snapshot running in this namespace?", "enable_snapshot"); return 1; @@ -585,12 +587,12 @@ int SnapshotterClient::run(SnapshotterClientOptions const& opts) std_srvs::SetBoolRequest req; req.data = (opts.action_ == SnapshotterClientOptions::RESUME); std_srvs::SetBoolResponse res; - if (not client.call(req, res)) + if (!client.call(req, res)) { ROS_ERROR("Failed to call service."); return 1; } - if (not res.success) + if (!res.success) { ROS_ERROR("%s", res.message.c_str()); return 1; diff --git a/rosbag_snapshot/test/test_snapshot.py b/rosbag_snapshot/test/test_snapshot.py index 945190e..4706077 100755 --- a/rosbag_snapshot/test/test_snapshot.py +++ b/rosbag_snapshot/test/test_snapshot.py @@ -37,7 +37,6 @@ import unittest import rospy from rosbag import Bag -from std_msgs.msg import String from std_srvs.srv import SetBool from rosbag_snapshot_msgs.msg import SnapshotStatus from rosbag_snapshot_msgs.srv import TriggerSnapshot, TriggerSnapshotRequest, TriggerSnapshotResponse @@ -45,7 +44,7 @@ class TestRosbagSnapshot(unittest.TestCase): ''' - Tests the "rosbag snapshot" command. + Tests the "rosbag_snapshot" command. Relies on the nodes launched in snapshot.test ''' def __init__(self, *args): diff --git a/rosbag_snapshot_msgs/CMakeLists.txt b/rosbag_snapshot_msgs/CMakeLists.txt index 3fb69cd..3341745 100644 --- a/rosbag_snapshot_msgs/CMakeLists.txt +++ b/rosbag_snapshot_msgs/CMakeLists.txt @@ -2,10 +2,11 @@ cmake_minimum_required(VERSION 2.8.3) project(rosbag_snapshot_msgs) find_package(catkin REQUIRED COMPONENTS message_generation rosgraph_msgs) - -add_message_files(DIRECTORY msg FILES SnapshotStatus.msg) -add_service_files(DIRECTORY srv FILES TriggerSnapshot.srv) - +add_message_files(FILES SnapshotStatus.msg) +add_service_files(FILES TriggerSnapshot.srv) generate_messages(DEPENDENCIES rosgraph_msgs) -catkin_package(CATKIN_DEPENDS message_runtime rosgraph_msgs) +catkin_package( + CATKIN_DEPENDS message_runtime rosgraph_msgs +) + diff --git a/rosbag_snapshot_msgs/msg/SnapshotStatus.msg b/rosbag_snapshot_msgs/msg/SnapshotStatus.msg index 3ad7402..29e451f 100644 --- a/rosbag_snapshot_msgs/msg/SnapshotStatus.msg +++ b/rosbag_snapshot_msgs/msg/SnapshotStatus.msg @@ -4,5 +4,5 @@ # The period, stamp, node_pub, and dropped_msgs fields are left empty rosgraph_msgs/TopicStatistics[] topics # If true, new messages are being added to the snapshot buffers -# If false, snapshoter is currently paused or writing to a bag file +# If false, snapshotter is currently paused or writing to a bag file bool enabled diff --git a/rosbag_snapshot_msgs/package.xml b/rosbag_snapshot_msgs/package.xml index 825cd5e..e19a9b6 100644 --- a/rosbag_snapshot_msgs/package.xml +++ b/rosbag_snapshot_msgs/package.xml @@ -1,14 +1,18 @@ - + + rosbag_snapshot_msgs 1.0.0 Service and message definitions for rosbag_snapshot - Dirk Thomas + + Kevin Allen + David V. Lu!! + BSD - Kevin Allen - catkin + catkin + rosgraph_msgs message_generation - rosgraph_msgs - message_runtime - rosgraph_msgs + message_runtime + message_runtime + diff --git a/rosbag_snapshot_msgs/srv/TriggerSnapshot.srv b/rosbag_snapshot_msgs/srv/TriggerSnapshot.srv index e26ac60..fd334e6 100644 --- a/rosbag_snapshot_msgs/srv/TriggerSnapshot.srv +++ b/rosbag_snapshot_msgs/srv/TriggerSnapshot.srv @@ -1,18 +1,18 @@ -string filename # Name of bag file to save snapshot to. +string filename # Name of bag file to save snapshot to. # if it ends in .bag, this exact filename will be saved. - # otherwise, the current datatime and .bag will be appended to the name + # otherwise, the current datetime and .bag will be appended to the name # example: "test" -> test2018-05-23-10-04-20.bag # example: "test.bag" -> test.bag -string[] topics # List of topics to include in snapshot. +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 - # 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), start at the earliest message in each topic's buffer +time stop_time # Latest timestamp for a message to be included in written bag # If time(0), stop at the most recent message in each topic's buffer --- -bool success # True if snapshot succesfully written to disk +bool success # True if snapshot successfully written to disk string NO_DATA=no messages buffered on selected topics string message # Error description if failed