naoqidriver
globalrecorder.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Aldebaran
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef GLOBALRECORDER_HPP
19 #define GLOBALRECORDER_HPP
20 
21 /*
22 * LOCAL includes
23 */
24 #include <naoqi_driver/tools.hpp>
25 
26 /*
27 * STANDARD includes
28 */
29 #include <string>
30 
31 /*
32 * BOOST includes
33 */
34 # include <boost/thread/mutex.hpp>
35 
36 /*
37 * ROS includes
38 */
39 #include <ros/ros.h>
40 #include <rosbag/bag.h>
41 #include <geometry_msgs/TransformStamped.h>
42 
43 
44 
45 namespace naoqi
46 {
47 namespace recorder
48 {
49 
58 {
59 
60 public:
61 
65  GlobalRecorder(const std::string& prefix_topic);
66 
70  void startRecord(const std::string& prefix_bag = "");
71 
75  std::string stopRecord(const std::string& robot_ip = "<ROBOT_IP>");
76 
80  template <class T>
81  void write(const std::string& topic, const T& msg, const ros::Time& time = ros::Time::now() ) {
82  std::string ros_topic;
83  if (topic[0]!='/')
84  {
85  ros_topic = _prefix_topic+topic;
86  }
87  else
88  {
89  ros_topic = topic;
90  }
91  ros::Time time_msg = time;
92  boost::mutex::scoped_lock writeLock( _processMutex );
93  if (_isStarted) {
94  _bag.write(ros_topic, time_msg, msg);
95  }
96  }
97 
98  void write(const std::string& topic, const std::vector<geometry_msgs::TransformStamped>& msgtf);
99 
103  bool isStarted();
104 
105 private:
106  std::string _prefix_topic;
107  boost::mutex _processMutex;
108  rosbag::Bag _bag;
109  std::string _nameBag;
111 
112  // TOPICS
113  std::vector<Topics> _topics;
114 
115 }; // class globalrecorder
116 } // recorder
117 } //naoqi
118 
119 #endif
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
Definition: audio.cpp:29
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