34 #ifndef ROSBAG_SNAPSHOT_SNAPSHOTTER_H
35 #define ROSBAG_SNAPSHOT_SNAPSHOTTER_H
37 #include <boost/atomic.hpp>
38 #include <boost/thread/mutex.hpp>
39 #include <boost/thread/shared_mutex.hpp>
42 #include <rosbag_snapshot_msgs/TriggerSnapshot.h>
43 #include <std_srvs/SetBool.h>
45 #include <rosgraph_msgs/TopicStatistics.h>
46 #include <rosbag_snapshot_msgs/SnapshotStatus.h>
68 static const int32_t NO_MEMORY_LIMIT;
70 static const int32_t NO_COUNT_LIMIT;
74 static const int32_t INHERIT_MEMORY_LIMIT;
76 static const int32_t INHERIT_COUNT_LIMIT;
81 int32_t memory_limit_;
86 int32_t memory_limit = INHERIT_MEMORY_LIMIT, int32_t count_limit = INHERIT_COUNT_LIMIT);
97 int32_t default_memory_limit_;
99 int32_t default_count_limit_;
107 std::string compression_;
112 typedef std::map<std::string, SnapshotterTopicOptions> topics_t;
118 bool clear_buffer =
true);
121 bool addTopic(std::string
const& topic,
155 typedef std::deque<SnapshotMessage> queue_t;
173 void fillStatus(rosgraph_msgs::TopicStatistics& status);
174 typedef std::pair<queue_t::const_iterator, queue_t::const_iterator> range_t;
209 typedef std::map<std::string, boost::shared_ptr<MessageQueue> > buffers_t;
212 boost::upgrade_mutex state_lock_;
227 bool postfixFilename(std::string& file);
229 std::string timeAsStr();
238 bool triggerSnapshotCb(rosbag_snapshot_msgs::TriggerSnapshot::Request& req,
239 rosbag_snapshot_msgs::TriggerSnapshot::Response& res);
241 bool enableCB(std_srvs::SetBool::Request& req, std_srvs::SetBool::Response& res);
253 rosbag_snapshot_msgs::TriggerSnapshot::Request& req,
254 rosbag_snapshot_msgs::TriggerSnapshot::Response& res);
270 std::vector<std::string> topics_;
272 std::string filename_;
282 int run(SnapshotterClientOptions
const& opts);
290 #endif // ROSBAG_SNAPSHOT_SNAPSHOTTER_H