Go to the documentation of this file.
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 write(const std::string &topic, const T &msg, const ros::Time &time=ros::Time::now())
Insert data into the ROSbag.
std::string stopRecord(const std::string &robot_ip="<ROBOT_IP>")
Terminate the recording of the ROSbag.
std::vector< Topics > _topics
boost::mutex _processMutex
void startRecord(const std::string &prefix_bag="")
Initialize the recording of the ROSbag.
std::string _prefix_topic
void write(std::string const &topic, ros::MessageEvent< T > const &event)
GlobalRecorder(const std::string &prefix_topic)
Constructor for recorder interface.
GlobalRecorder concept interface.
bool isStarted()
Check if the ROSbag is opened.
naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06