18 #ifndef GLOBALRECORDER_HPP    19 #define GLOBALRECORDER_HPP    34 # include <boost/thread/mutex.hpp>    41 #include <geometry_msgs/TransformStamped.h>    70   void startRecord(
const std::string& prefix_bag = 
"");
    75   std::string 
stopRecord(
const std::string& robot_ip = 
"<ROBOT_IP>");
    82     std::string ros_topic;
    98   void write(
const std::string& topic, 
const std::vector<geometry_msgs::TransformStamped>& msgtf);
 void startRecord(const std::string &prefix_bag="")
Initialize the recording of the ROSbag. 
boost::mutex _processMutex
std::vector< Topics > _topics
bool isStarted()
Check if the ROSbag is opened. 
std::string _prefix_topic
std::string stopRecord(const std::string &robot_ip="<ROBOT_IP>")
Terminate the recording of the ROSbag. 
GlobalRecorder concept interface. 
void write(const std::string &topic, const T &msg, const ros::Time &time=ros::Time::now())
Insert data into the ROSbag. 
GlobalRecorder(const std::string &prefix_topic)
Constructor for recorder interface. 
void write(std::string const &topic, ros::MessageEvent< T > const &event)