19 #ifndef DATA_BAGGER_DATA_BAGGER_H_
20 #define DATA_BAGGER_DATA_BAGGER_H_
22 #include <boost/date_time/posix_time/posix_time.hpp>
30 #include <ff_msgs/DataToDiskState.h>
31 #include <ff_msgs/DataTopicsList.h>
32 #include <ff_msgs/EnableRecording.h>
33 #include <ff_msgs/SetDataToDisk.h>
38 #include <pluginlib/class_list_macros.h>
41 #include <ros/package.h>
44 #include <sys/types.h>
59 ff_msgs::SetDataToDisk::Response &res);
63 ff_msgs::EnableRecording::Response &res);
74 bool MakeDir(std::string dir,
bool assert_init_fault, std::string &err_msg);
77 std::string GetDate(
bool with_time);
80 void AddTopicNamespace(std::string &topic);
83 void OnStartupTimer(ros::TimerEvent
const& event);
86 bool SetImmediateDataToDisk(std::string &err_msg);
88 bool SetDelayedDataToDisk(ff_msgs::DataToDiskState &
state,
89 std::string &err_msg);
92 void StartDelayedRecording();
93 void StartImmediateRecording();
96 void ResetRecorders(
bool immediate);
99 void GenerateCombinedState(ff_msgs::DataToDiskState *ground_state);
108 ff_msgs::DataToDiskState default_data_state_, combined_data_state_;
111 unsigned int startup_time_secs_;
112 int64_t bag_size_bytes_;
114 ros::Publisher pub_data_state_, pub_data_topics_;
115 ros::Timer startup_timer_;
117 ros::ServiceServer set_service_, record_service_;
119 rosbag::RecorderOptions recorder_options_delayed_;
120 rosbag::RecorderOptions recorder_options_immediate_;
122 std::thread delayed_thread_, immediate_thread_;
123 std::string save_dir_, robot_name_, delayed_profile_name_;
128 #endif // DATA_BAGGER_DATA_BAGGER_H_