18 #ifndef GLOBALRECORDER_HPP
19 #define GLOBALRECORDER_HPP
34 # include <boost/thread/mutex.hpp>
40 #include <rosbag/bag.h>
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>");
81 void write(
const std::string& topic,
const T& msg,
const ros::Time& time = ros::Time::now() ) {
82 std::string ros_topic;
91 ros::Time time_msg = time;
94 _bag.write(ros_topic, time_msg, msg);
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.
Definition: globalrecorder.cpp:74
boost::mutex _processMutex
Definition: globalrecorder.hpp:107
std::string _nameBag
Definition: globalrecorder.hpp:109
std::vector< Topics > _topics
Definition: globalrecorder.hpp:113
bool isStarted()
Check if the ROSbag is opened.
Definition: globalrecorder.cpp:138
std::string _prefix_topic
Definition: globalrecorder.hpp:106
std::string stopRecord(const std::string &robot_ip="<ROBOT_IP>")
Terminate the recording of the ROSbag.
Definition: globalrecorder.cpp:109
rosbag::Bag _bag
Definition: globalrecorder.hpp:108
GlobalRecorder concept interface.
Definition: globalrecorder.hpp:57
void write(const std::string &topic, const T &msg, const ros::Time &time=ros::Time::now())
Insert data into the ROSbag.
Definition: globalrecorder.hpp:81
bool _isStarted
Definition: globalrecorder.hpp:110
GlobalRecorder(const std::string &prefix_topic)
Constructor for recorder interface.
Definition: globalrecorder.cpp:58