32 #include <std_msgs/Int32.h> 33 #include <tf2_msgs/TFMessage.h> 37 #include <geometry_msgs/TransformStamped.h> 42 #include <boost/filesystem.hpp> 43 #include <boost/make_shared.hpp> 44 #include <boost/shared_ptr.hpp> 64 if (!prefix_topic.empty())
79 boost::filesystem::path cur_path( boost::filesystem::current_path() );
86 timeinfo = std::localtime(&rawtime);
87 std::strftime(buffer,80,
"%d-%m-%Y_%I:%M:%S",timeinfo);
89 if (!prefix_bag.empty()) {
90 _nameBag = cur_path.string()+
"/"+prefix_bag+
"_"+buffer;
93 _nameBag = cur_path.string()+
"/"+buffer;
100 }
catch (std::exception e){
101 throw std::runtime_error(e.what());
105 qiLogError() <<
"Cannot start a record. The module is already recording.";
115 std::stringstream message;
121 current_path = getenv(
"HOME");
122 std::string cp = current_path;
123 if (!(cp.find(
"nao") == std::string::npos)) {
124 std::cout <<
BOLDRED <<
"To download this bag on your computer:" <<
RESETCOLOR << std::endl
125 <<
GREEN <<
"\t$ scp nao@" << robot_ip <<
":" << _nameBag <<
" <LOCAL_PATH>" <<
RESETCOLOR 130 return message.str();
133 qiLogError() <<
"Cannot stop recording while it has not been started.";
134 return "Cannot stop recording while it has not been started.";
145 std::string ros_topic;
154 tf2_msgs::TFMessage message;
156 if (!msgtf[0].header.stamp.isZero()) {
157 now = msgtf[0].header.stamp;
159 for (std::vector<geometry_msgs::TransformStamped>::const_iterator it = msgtf.begin(); it != msgtf.end(); ++it)
161 message.transforms.push_back(*it);
void startRecord(const std::string &prefix_bag="")
Initialize the recording of the ROSbag.
boost::mutex _processMutex
void open(std::string const &filename, uint32_t mode=bagmode::Read)
qiLogCategory("ros.Recorder")
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.
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)