35 #ifndef ROSBAG_RECORDER_H
36 #define ROSBAG_RECORDER_H
39 #if !defined(_MSC_VER)
50 #include <boost/thread/condition.hpp>
51 #include <boost/thread/mutex.hpp>
52 #include <boost/regex.hpp>
57 #include <std_msgs/Empty.h>
58 #include <std_msgs/String.h>
81 OutgoingQueue(std::string
const& _filename, std::queue<OutgoingMessage>* _queue,
ros::Time _time);
84 std::queue<OutgoingMessage>* queue;
105 boost::regex exclude_regex;
106 uint32_t buffer_size;
114 unsigned long long min_space;
115 std::string min_space_str;
118 std::vector<std::string> topics;
128 bool isSubscribed(std::string
const& topic)
const;
137 void updateFilenames();
142 bool scheduledCheckDisk();
145 void snapshotTrigger(std_msgs::Empty::ConstPtr trigger);
149 void checkNumSplits();
152 void doRecordSnapshotter();
155 bool shouldSubscribeToTopic(std::string
const& topic,
bool from_node =
false);
158 static std::string timeToStr(T ros_t);
165 std::string target_filename_;
166 std::string write_filename_;
167 std::list<std::string> current_files_;
169 std::set<std::string> currently_recording_;
170 int num_subscribers_;
174 std::map<std::pair<std::string, std::string>,
OutgoingMessage> latched_msgs_;
176 boost::condition_variable_any queue_condition_;
177 boost::mutex queue_mutex_;
178 std::queue<OutgoingMessage>* queue_;
179 uint64_t queue_size_;
180 uint64_t max_queue_size_;
182 uint64_t split_count_;
184 std::queue<OutgoingQueue> queue_queue_;
190 bool writing_enabled_;
191 boost::mutex check_disk_mutex_;