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>    83     std::queue<OutgoingMessage>* 
queue;
   125     bool isSubscribed(std::string 
const& topic) 
const;
   134     void updateFilenames();
   139     bool scheduledCheckDisk();
   142     void snapshotTrigger(std_msgs::Empty::ConstPtr trigger);
   146     void checkNumSplits();
   149     void doRecordSnapshotter();
   152     bool shouldSubscribeToTopic(std::string 
const& topic, 
bool from_node = 
false);
   155     static std::string timeToStr(T ros_t);
 
ros::TransportHints transport_hints
ros::Time last_buffer_warn_
int exit_code_
eventual exit code 
uint64_t queue_size_
queue size 
ros::WallTime check_disk_next_
boost::mutex queue_mutex_
mutex for queue 
std::string target_filename_
boost::regex exclude_regex
topic_tools::ShapeShifter::ConstPtr msg
std::string write_filename_
ros::Duration max_duration
std::set< std::string > currently_recording_
set of currenly recording topics 
std::queue< OutgoingMessage > * queue
std::list< std::string > current_files_
boost::condition_variable_any queue_condition_
conditional variable for queue 
unsigned long long min_space
boost::mutex check_disk_mutex_
uint64_t split_count_
split count 
std::queue< OutgoingQueue > queue_queue_
queue of queues to be used by the snapshot recorders 
uint64_t max_queue_size_
max queue size 
int num_subscribers_
used for book-keeping of our number of subscribers 
std::queue< OutgoingMessage > * queue_
queue for storing 
CompressionType compression
std::vector< std::string > topics
std::string min_space_str
boost::shared_ptr< ros::M_string > connection_header