globalrecorder.cpp
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 /*
19 * LOCAL includes
20 */
22 
23 /*
24 * STANDARD includes
25 */
26 #include <ctime>
27 #include <sstream>
28 
29 /*
30 * ROS includes
31 */
32 #include <std_msgs/Int32.h>
33 #include <tf2_msgs/TFMessage.h>
34 #include <ros/ros.h>
35 #include <rosbag/bag.h>
36 #include <rosbag/view.h>
37 #include <geometry_msgs/TransformStamped.h>
38 
39 /*
40 * BOOST includes
41 */
42 #include <boost/filesystem.hpp>
43 #include <boost/make_shared.hpp>
44 #include <boost/shared_ptr.hpp>
45 
46 /*
47 * ALDEBARAN includes
48 */
49 #include <qi/log.hpp>
50 
51 qiLogCategory("ros.Recorder");
52 
53 namespace naoqi
54 {
55 namespace recorder
56 {
57 
58  GlobalRecorder::GlobalRecorder(const std::string& prefix_topic):
59  _bag()
60  , _processMutex()
61  , _nameBag("")
62  , _isStarted(false)
63  {
64  if (!prefix_topic.empty())
65  {
66  _prefix_topic = "/"+prefix_topic+"/";
67  }
68  else
69  {
70  _prefix_topic = "/";
71  }
72  }
73 
74  void GlobalRecorder::startRecord(const std::string& prefix_bag) {
75  boost::mutex::scoped_lock startLock( _processMutex );
76  if (!_isStarted) {
77  try {
78  // Get current path
79  boost::filesystem::path cur_path( boost::filesystem::current_path() );
80 
81  // Get time
82  time_t rawtime;
83  struct tm * timeinfo;
84  char buffer[80];
85  std::time(&rawtime);
86  timeinfo = std::localtime(&rawtime);
87  std::strftime(buffer,80,"%d-%m-%Y_%I:%M:%S",timeinfo);
88 
89  if (!prefix_bag.empty()) {
90  _nameBag = cur_path.string()+"/"+prefix_bag+"_"+buffer;
91  }
92  else {
93  _nameBag = cur_path.string()+"/"+buffer;
94  }
95  _nameBag.append(".bag");
96 
98  _isStarted = true;
99  std::cout << YELLOW << "The bag " << BOLDCYAN << _nameBag << RESETCOLOR << YELLOW << " is opened" << RESETCOLOR << std::endl;
100  } catch (std::exception e){
101  throw std::runtime_error(e.what());
102  }
103  }
104  else {
105  qiLogError() << "Cannot start a record. The module is already recording.";
106  }
107  }
108 
109  std::string GlobalRecorder::stopRecord(const std::string& robot_ip) {
110  boost::mutex::scoped_lock stopLock( _processMutex );
111  if (_isStarted) {
112  _bag.close();
113  _isStarted = false;
114 
115  std::stringstream message;
116  message << _nameBag;
117  std::cout << YELLOW << "The bag " << BOLDCYAN << _nameBag << RESETCOLOR << YELLOW << " is closed" << RESETCOLOR << std::endl;
118 
119  // Check if we are on a robot
120  char* current_path;
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
126  << std::endl;
127  }
128 
129  _nameBag.clear();
130  return message.str();
131  }
132  else {
133  qiLogError() << "Cannot stop recording while it has not been started.";
134  return "Cannot stop recording while it has not been started.";
135  }
136  }
137 
139  return _isStarted;
140  }
141 
142  void GlobalRecorder::write(const std::string& topic, const std::vector<geometry_msgs::TransformStamped>& msgtf) {
143  if (!msgtf.empty())
144  {
145  std::string ros_topic;
146  if (topic[0]!='/')
147  {
148  ros_topic = _prefix_topic+topic;
149  }
150  else
151  {
152  ros_topic = topic;
153  }
154  tf2_msgs::TFMessage message;
155  ros::Time now = ros::Time::now();
156  if (!msgtf[0].header.stamp.isZero()) {
157  now = msgtf[0].header.stamp;
158  }
159  for (std::vector<geometry_msgs::TransformStamped>::const_iterator it = msgtf.begin(); it != msgtf.end(); ++it)
160  {
161  message.transforms.push_back(*it);
162  }
163  boost::mutex::scoped_lock writeLock( _processMutex );
164  if (_isStarted) {
165  _bag.write(ros_topic, now, message);
166  }
167  }
168  }
169 
170 } // recorder
171 } // naoqi
void startRecord(const std::string &prefix_bag="")
Initialize the recording of the ROSbag.
void open(std::string const &filename, uint32_t mode=bagmode::Read)
#define GREEN
Definition: tools.hpp:23
qiLogCategory("ros.Recorder")
#define BOLDRED
Definition: tools.hpp:25
void close()
#define RESETCOLOR
Definition: tools.hpp:22
bool isStarted()
Check if the ROSbag is opened.
#define BOLDCYAN
Definition: tools.hpp:28
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.
static Time now()
GlobalRecorder(const std::string &prefix_topic)
Constructor for recorder interface.
void write(std::string const &topic, ros::MessageEvent< T > const &event)
#define YELLOW
Definition: tools.hpp:26


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 15 2020 03:24:26