recorder.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage, Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 ********************************************************************/
34 
35 #include "rosbag/recorder.h"
36 
37 #include <sys/stat.h>
38 #include <boost/filesystem.hpp>
39 // Boost filesystem v3 is default in 1.46.0 and above
40 // Fallback to original posix code (*nix only) if this is not true
41 #if BOOST_FILESYSTEM_VERSION < 3
42  #include <sys/statvfs.h>
43 #endif
44 #include <time.h>
45 
46 #include <queue>
47 #include <set>
48 #include <sstream>
49 #include <string>
50 
51 #include <boost/foreach.hpp>
52 #include <boost/lexical_cast.hpp>
53 #include <boost/regex.hpp>
54 #include <boost/thread.hpp>
55 #include <boost/thread/xtime.hpp>
56 #include <boost/date_time/local_time/local_time.hpp>
57 
58 #include <ros/ros.h>
60 
61 #include "ros/network.h"
62 #include "ros/xmlrpc_manager.h"
63 #include "xmlrpcpp/XmlRpc.h"
64 
65 #define foreach BOOST_FOREACH
66 
67 using std::cout;
68 using std::endl;
69 using std::set;
70 using std::string;
71 using std::vector;
72 using boost::shared_ptr;
73 using ros::Time;
74 
75 namespace rosbag {
76 
77 // OutgoingMessage
78 
80  topic(_topic), msg(_msg), connection_header(_connection_header), time(_time)
81 {
82 }
83 
84 // OutgoingQueue
85 
86 OutgoingQueue::OutgoingQueue(string const& _filename, std::queue<OutgoingMessage>* _queue, Time _time) :
87  filename(_filename), queue(_queue), time(_time)
88 {
89 }
90 
91 // RecorderOptions
92 
94  trigger(false),
95  record_all(false),
96  regex(false),
97  do_exclude(false),
98  quiet(false),
99  append_date(true),
100  snapshot(false),
101  verbose(false),
102  compression(compression::Uncompressed),
103  prefix(""),
104  name(""),
105  exclude_regex(),
106  buffer_size(1048576 * 256),
107  chunk_size(1024 * 768),
108  limit(0),
109  split(false),
110  max_size(0),
111  max_splits(0),
112  max_duration(-1.0),
113  node(""),
114  min_space(1024 * 1024 * 1024),
115  min_space_str("1G")
116 {
117 }
118 
119 // Recorder
120 
122  options_(options),
123  num_subscribers_(0),
124  exit_code_(0),
125  queue_size_(0),
126  split_count_(0),
127  writing_enabled_(true)
128 {
129 }
130 
132  if (options_.trigger) {
133  doTrigger();
134  return 0;
135  }
136 
137  if (options_.topics.size() == 0) {
138  // Make sure limit is not specified with automatic topic subscription
139  if (options_.limit > 0) {
140  fprintf(stderr, "Specifing a count is not valid with automatic topic subscription.\n");
141  return 1;
142  }
143 
144  // Make sure topics are specified
145  if (!options_.record_all && (options_.node == std::string(""))) {
146  fprintf(stderr, "No topics specified.\n");
147  return 1;
148  }
149  }
150 
151  ros::NodeHandle nh;
152  if (!nh.ok())
153  return 0;
154 
156  queue_ = new std::queue<OutgoingMessage>;
157 
158  // Subscribe to each topic
159  if (!options_.regex) {
160  foreach(string const& topic, options_.topics)
161  subscribe(topic);
162  }
163 
165  ROS_WARN("/use_sim_time set to true and no clock published. Still waiting for valid time...");
166 
168 
170 
171  // Don't bother doing anything if we never got a valid time
172  if (!nh.ok())
173  return 0;
174 
175  ros::Subscriber trigger_sub;
176 
177  // Spin up a thread for writing to the file
178  boost::thread record_thread;
179  if (options_.snapshot)
180  {
181  record_thread = boost::thread(boost::bind(&Recorder::doRecordSnapshotter, this));
182 
183  // Subscribe to the snapshot trigger
184  trigger_sub = nh.subscribe<std_msgs::Empty>("snapshot_trigger", 100, boost::bind(&Recorder::snapshotTrigger, this, _1));
185  }
186  else
187  record_thread = boost::thread(boost::bind(&Recorder::doRecord, this));
188 
189 
190 
191  ros::Timer check_master_timer;
192  if (options_.record_all || options_.regex || (options_.node != std::string("")))
193  {
194  // check for master first
196  check_master_timer = nh.createTimer(ros::Duration(1.0), boost::bind(&Recorder::doCheckMaster, this, _1, boost::ref(nh)));
197  }
198 
200  ros::spin(s);
201 
202  queue_condition_.notify_all();
203 
204  record_thread.join();
205 
206  delete queue_;
207 
208  return exit_code_;
209 }
210 
212  ROS_INFO("Subscribing to %s", topic.c_str());
213 
214  ros::NodeHandle nh;
215  shared_ptr<int> count(boost::make_shared<int>(options_.limit));
216  shared_ptr<ros::Subscriber> sub(boost::make_shared<ros::Subscriber>());
217 
219  ops.topic = topic;
220  ops.queue_size = 100;
221  ops.md5sum = ros::message_traits::md5sum<topic_tools::ShapeShifter>();
222  ops.datatype = ros::message_traits::datatype<topic_tools::ShapeShifter>();
223  ops.helper = boost::make_shared<ros::SubscriptionCallbackHelperT<
225  boost::bind(&Recorder::doQueue, this, _1, topic, sub, count));
227  *sub = nh.subscribe(ops);
228 
229  currently_recording_.insert(topic);
231 
232  return sub;
233 }
234 
235 bool Recorder::isSubscribed(string const& topic) const {
236  return currently_recording_.find(topic) != currently_recording_.end();
237 }
238 
239 bool Recorder::shouldSubscribeToTopic(std::string const& topic, bool from_node) {
240  // ignore already known topics
241  if (isSubscribed(topic)) {
242  return false;
243  }
244 
245  // subtract exclusion regex, if any
246  if(options_.do_exclude && boost::regex_match(topic, options_.exclude_regex)) {
247  return false;
248  }
249 
250  if(options_.record_all || from_node) {
251  return true;
252  }
253 
254  if (options_.regex) {
255  // Treat the topics as regular expressions
256  foreach(string const& regex_str, options_.topics) {
257  boost::regex e(regex_str);
258  boost::smatch what;
259  if (boost::regex_match(topic, what, e, boost::match_extra))
260  return true;
261  }
262  }
263  else {
264  foreach(string const& t, options_.topics)
265  if (t == topic)
266  return true;
267  }
268 
269  return false;
270 }
271 
272 template<class T>
273 std::string Recorder::timeToStr(T ros_t)
274 {
275  (void)ros_t;
276  std::stringstream msg;
277  const boost::posix_time::ptime now=
278  boost::posix_time::second_clock::local_time();
279  boost::posix_time::time_facet *const f=
280  new boost::posix_time::time_facet("%Y-%m-%d-%H-%M-%S");
281  msg.imbue(std::locale(msg.getloc(),f));
282  msg << now;
283  return msg.str();
284 }
285 
288  //void Recorder::doQueue(topic_tools::ShapeShifter::ConstPtr msg, string const& topic, shared_ptr<ros::Subscriber> subscriber, shared_ptr<int> count) {
289  Time rectime = Time::now();
290 
291  if (options_.verbose)
292  cout << "Received message on topic " << subscriber->getTopic() << endl;
293 
294  OutgoingMessage out(topic, msg_event.getMessage(), msg_event.getConnectionHeaderPtr(), rectime);
295 
296  {
297  boost::mutex::scoped_lock lock(queue_mutex_);
298 
299  queue_->push(out);
300  queue_size_ += out.msg->size();
301 
302  // Check to see if buffer has been exceeded
304  OutgoingMessage drop = queue_->front();
305  queue_->pop();
306  queue_size_ -= drop.msg->size();
307 
308  if (!options_.snapshot) {
309  Time now = Time::now();
310  if (now > last_buffer_warn_ + ros::Duration(5.0)) {
311  ROS_WARN("rosbag record buffer exceeded. Dropping oldest queued message.");
312  last_buffer_warn_ = now;
313  }
314  }
315  }
316  }
317 
318  if (!options_.snapshot)
319  queue_condition_.notify_all();
320 
321  // If we are book-keeping count, decrement and possibly shutdown
322  if ((*count) > 0) {
323  (*count)--;
324  if ((*count) == 0) {
325  subscriber->shutdown();
326 
328 
329  if (num_subscribers_ == 0)
330  ros::shutdown();
331  }
332  }
333 }
334 
336  vector<string> parts;
337 
338  std::string prefix = options_.prefix;
339  size_t ind = prefix.rfind(".bag");
340 
341  if (ind != std::string::npos && ind == prefix.size() - 4)
342  {
343  prefix.erase(ind);
344  }
345 
346  if (prefix.length() > 0)
347  parts.push_back(prefix);
348  if (options_.append_date)
349  parts.push_back(timeToStr(ros::WallTime::now()));
350  if (options_.split)
351  parts.push_back(boost::lexical_cast<string>(split_count_));
352 
353  if (parts.size() == 0)
354  {
355  throw BagException("Bag filename is empty (neither of these was specified: prefix, append_date, split)");
356  }
357 
358  target_filename_ = parts[0];
359  for (unsigned int i = 1; i < parts.size(); i++)
360  target_filename_ += string("_") + parts[i];
361 
362  target_filename_ += string(".bag");
363  write_filename_ = target_filename_ + string(".active");
364 }
365 
367 void Recorder::snapshotTrigger(std_msgs::Empty::ConstPtr trigger) {
368  (void)trigger;
369  updateFilenames();
370 
371  ROS_INFO("Triggered snapshot recording with name %s.", target_filename_.c_str());
372 
373  {
374  boost::mutex::scoped_lock lock(queue_mutex_);
375  queue_queue_.push(OutgoingQueue(target_filename_, queue_, Time::now()));
376  queue_ = new std::queue<OutgoingMessage>;
377  queue_size_ = 0;
378  }
379 
380  queue_condition_.notify_all();
381 }
382 
386 
387  updateFilenames();
388  try {
390  }
391  catch (rosbag::BagException e) {
392  ROS_ERROR("Error writing: %s", e.what());
393  exit_code_ = 1;
394  ros::shutdown();
395  }
396  ROS_INFO("Recording to %s.", target_filename_.c_str());
397 }
398 
400  ROS_INFO("Closing %s.", target_filename_.c_str());
401  bag_.close();
402  rename(write_filename_.c_str(), target_filename_.c_str());
403 }
404 
406 {
407  if(options_.max_splits>0)
408  {
409  current_files_.push_back(target_filename_);
411  {
412  int err = unlink(current_files_.front().c_str());
413  if(err != 0)
414  {
415  ROS_ERROR("Unable to remove %s: %s", current_files_.front().c_str(), strerror(errno));
416  }
417  current_files_.pop_front();
418  }
419  }
420 }
421 
423 {
424  if (options_.max_size > 0)
425  {
426  if (bag_.getSize() > options_.max_size)
427  {
428  if (options_.split)
429  {
430  stopWriting();
431  split_count_++;
432  checkNumSplits();
433  startWriting();
434  } else {
435  ros::shutdown();
436  return true;
437  }
438  }
439  }
440  return false;
441 }
442 
444 {
446  {
448  {
449  if (options_.split)
450  {
451  while (start_time_ + options_.max_duration < t)
452  {
453  stopWriting();
454  split_count_++;
455  checkNumSplits();
457  startWriting();
458  }
459  } else {
460  ros::shutdown();
461  return true;
462  }
463  }
464  }
465  return false;
466 }
467 
468 
471  // Open bag file for writing
472  startWriting();
473 
474  // Schedule the disk space check
476  checkDisk();
478 
479  // Technically the queue_mutex_ should be locked while checking empty.
480  // Except it should only get checked if the node is not ok, and thus
481  // it shouldn't be in contention.
482  ros::NodeHandle nh;
483  while (nh.ok() || !queue_->empty()) {
484  boost::unique_lock<boost::mutex> lock(queue_mutex_);
485 
486  bool finished = false;
487  while (queue_->empty()) {
488  if (!nh.ok()) {
489  lock.release()->unlock();
490  finished = true;
491  break;
492  }
493  boost::xtime xt;
494 #if BOOST_VERSION >= 105000
495  boost::xtime_get(&xt, boost::TIME_UTC_);
496 #else
497  boost::xtime_get(&xt, boost::TIME_UTC);
498 #endif
499  xt.nsec += 250000000;
500  queue_condition_.timed_wait(lock, xt);
502  {
503  finished = true;
504  break;
505  }
506  }
507  if (finished)
508  break;
509 
510  OutgoingMessage out = queue_->front();
511  queue_->pop();
512  queue_size_ -= out.msg->size();
513 
514  lock.release()->unlock();
515 
516  if (checkSize())
517  break;
518 
519  if (checkDuration(out.time))
520  break;
521 
522  if (scheduledCheckDisk() && checkLogging())
523  bag_.write(out.topic, out.time, *out.msg, out.connection_header);
524  }
525 
526  stopWriting();
527 }
528 
530  ros::NodeHandle nh;
531 
532  while (nh.ok() || !queue_queue_.empty()) {
533  boost::unique_lock<boost::mutex> lock(queue_mutex_);
534  while (queue_queue_.empty()) {
535  if (!nh.ok())
536  return;
537  queue_condition_.wait(lock);
538  }
539 
540  OutgoingQueue out_queue = queue_queue_.front();
541  queue_queue_.pop();
542 
543  lock.release()->unlock();
544 
545  string target_filename = out_queue.filename;
546  string write_filename = target_filename + string(".active");
547 
548  try {
549  bag_.open(write_filename, bagmode::Write);
550  }
551  catch (rosbag::BagException ex) {
552  ROS_ERROR("Error writing: %s", ex.what());
553  return;
554  }
555 
556  while (!out_queue.queue->empty()) {
557  OutgoingMessage out = out_queue.queue->front();
558  out_queue.queue->pop();
559 
560  bag_.write(out.topic, out.time, *out.msg);
561  }
562 
563  stopWriting();
564  }
565 }
566 
568  (void)e;
569  (void)node_handle;
571  if (ros::master::getTopics(topics)) {
572  foreach(ros::master::TopicInfo const& t, topics) {
574  subscribe(t.name);
575  }
576  }
577 
578  if (options_.node != std::string(""))
579  {
580 
582  req[0] = ros::this_node::getName();
583  req[1] = options_.node;
584  XmlRpc::XmlRpcValue resp;
585  XmlRpc::XmlRpcValue payload;
586 
587  if (ros::master::execute("lookupNode", req, resp, payload, true))
588  {
589  std::string peer_host;
590  uint32_t peer_port;
591 
592  if (!ros::network::splitURI(static_cast<std::string>(resp[2]), peer_host, peer_port))
593  {
594  ROS_ERROR("Bad xml-rpc URI trying to inspect node at: [%s]", static_cast<std::string>(resp[2]).c_str());
595  } else {
596 
597  XmlRpc::XmlRpcClient c(peer_host.c_str(), peer_port, "/");
598  XmlRpc::XmlRpcValue req2;
599  XmlRpc::XmlRpcValue resp2;
600  req2[0] = ros::this_node::getName();
601  c.execute("getSubscriptions", req2, resp2);
602 
603  if (!c.isFault() && resp2.valid() && resp2.size() > 0 && static_cast<int>(resp2[0]) == 1)
604  {
605  for(int i = 0; i < resp2[2].size(); i++)
606  {
607  if (shouldSubscribeToTopic(resp2[2][i][0], true))
608  subscribe(resp2[2][i][0]);
609  }
610  } else {
611  ROS_ERROR("Node at: [%s] failed to return subscriptions.", static_cast<std::string>(resp[2]).c_str());
612  }
613  }
614  }
615  }
616 }
617 
619  ros::NodeHandle nh;
620  ros::Publisher pub = nh.advertise<std_msgs::Empty>("snapshot_trigger", 1, true);
621  pub.publish(std_msgs::Empty());
622 
623  ros::Timer terminate_timer = nh.createTimer(ros::Duration(1.0), boost::bind(&ros::shutdown));
624  ros::spin();
625 }
626 
628  boost::mutex::scoped_lock lock(check_disk_mutex_);
629 
631  return true;
632 
634  return checkDisk();
635 }
636 
638 #if BOOST_FILESYSTEM_VERSION < 3
639  struct statvfs fiData;
640  if ((statvfs(bag_.getFileName().c_str(), &fiData)) < 0)
641  {
642  ROS_WARN("Failed to check filesystem stats.");
643  return true;
644  }
645  unsigned long long free_space = 0;
646  free_space = (unsigned long long) (fiData.f_bsize) * (unsigned long long) (fiData.f_bavail);
647  if (free_space < options_.min_space)
648  {
649  ROS_ERROR("Less than %s of space free on disk with %s. Disabling recording.", options_.min_space_str.c_str(), bag_.getFileName().c_str());
650  writing_enabled_ = false;
651  return false;
652  }
653  else if (free_space < 5 * options_.min_space)
654  {
655  ROS_WARN("Less than 5 x %s of space free on disk with %s.", options_.min_space_str.c_str(), bag_.getFileName().c_str());
656  }
657  else
658  {
659  writing_enabled_ = true;
660  }
661 #else
662  boost::filesystem::path p(boost::filesystem::system_complete(bag_.getFileName().c_str()));
663  p = p.parent_path();
664  boost::filesystem::space_info info;
665  try
666  {
667  info = boost::filesystem::space(p);
668  }
669  catch (boost::filesystem::filesystem_error &e)
670  {
671  ROS_WARN("Failed to check filesystem stats [%s].", e.what());
672  writing_enabled_ = false;
673  return false;
674  }
675  if ( info.available < options_.min_space)
676  {
677  ROS_ERROR("Less than %s of space free on disk with %s. Disabling recording.", options_.min_space_str.c_str(), bag_.getFileName().c_str());
678  writing_enabled_ = false;
679  return false;
680  }
681  else if (info.available < 5 * options_.min_space)
682  {
683  ROS_WARN("Less than 5 x %s of space free on disk with %s.", options_.min_space_str.c_str(), bag_.getFileName().c_str());
684  writing_enabled_ = true;
685  }
686  else
687  {
688  writing_enabled_ = true;
689  }
690 #endif
691  return true;
692 }
693 
695  if (writing_enabled_)
696  return true;
697 
699  if (now >= warn_next_) {
700  warn_next_ = now + ros::WallDuration().fromSec(5.0);
701  ROS_WARN("Not logging message because logging disabled. Most likely cause is a full disk.");
702  }
703  return false;
704 }
705 
706 } // namespace rosbag
void updateFilenames()
Definition: recorder.cpp:335
void checkNumSplits()
Definition: recorder.cpp:405
ros::TransportHints transport_hints
Definition: recorder.h:113
void doRecordSnapshotter()
Definition: recorder.cpp:529
ros::Time last_buffer_warn_
Definition: recorder.h:181
int exit_code_
eventual exit code
Definition: recorder.h:169
void publish(const boost::shared_ptr< M > &message) const
void open(std::string const &filename, uint32_t mode=bagmode::Read)
f
std::string getFileName() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
uint64_t queue_size_
queue size
Definition: recorder.h:174
ros::WallTime check_disk_next_
Definition: recorder.h:187
int size() const
boost::mutex queue_mutex_
mutex for queue
Definition: recorder.h:172
void setChunkThreshold(uint32_t chunk_threshold)
std::string target_filename_
Definition: recorder.h:162
XmlRpcServer s
bool valid() const
boost::regex exclude_regex
Definition: recorder.h:102
ROSCPP_DECL bool splitURI(const std::string &uri, std::string &host, uint32_t &port)
OutgoingQueue(std::string const &_filename, std::queue< OutgoingMessage > *_queue, ros::Time _time)
Definition: recorder.cpp:86
void startWriting()
Definition: recorder.cpp:383
ROSCPP_DECL const std::string & getName()
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
bool checkLogging()
Definition: recorder.cpp:694
topic_tools::ShapeShifter::ConstPtr msg
Definition: recorder.h:72
const boost::shared_ptr< M_string > & getConnectionHeaderPtr() const
std::vector< TopicInfo > V_TopicInfo
#define ROS_WARN(...)
void close()
std::string write_filename_
Definition: recorder.h:163
ros::Duration max_duration
Definition: recorder.h:109
std::set< std::string > currently_recording_
set of currenly recording topics
Definition: recorder.h:166
OutgoingMessage(std::string const &_topic, topic_tools::ShapeShifter::ConstPtr _msg, boost::shared_ptr< ros::M_string > _connection_header, ros::Time _time)
Definition: recorder.cpp:79
void doCheckMaster(ros::TimerEvent const &e, ros::NodeHandle &node_handle)
Definition: recorder.cpp:567
static std::string timeToStr(T ros_t)
Definition: recorder.cpp:273
std::queue< OutgoingMessage > * queue
Definition: recorder.h:83
ros::WallTime warn_next_
Definition: recorder.h:188
SubscriptionCallbackHelperPtr helper
std::string prefix
Definition: recorder.h:100
void stopWriting()
Definition: recorder.cpp:399
WallDuration & fromSec(double t)
bool scheduledCheckDisk()
Definition: recorder.cpp:627
bool isSubscribed(std::string const &topic) const
Definition: recorder.cpp:235
#define ROS_INFO(...)
void setCompression(CompressionType compression)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
RecorderOptions options_
Definition: recorder.h:158
std::list< std::string > current_files_
Definition: recorder.h:164
boost::condition_variable_any queue_condition_
conditional variable for queue
Definition: recorder.h:171
boost::shared_ptr< ros::Subscriber > subscribe(std::string const &topic)
Definition: recorder.cpp:211
std::string filename
Definition: recorder.h:82
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spin()
TransportHints transport_hints
unsigned long long min_space
Definition: recorder.h:111
void doQueue(const ros::MessageEvent< topic_tools::ShapeShifter const > &msg_event, std::string const &topic, boost::shared_ptr< ros::Subscriber > subscriber, boost::shared_ptr< int > count)
Callback to be invoked to save messages into a queue.
Definition: recorder.cpp:287
boost::mutex check_disk_mutex_
Definition: recorder.h:186
Recorder(RecorderOptions const &options)
Definition: recorder.cpp:121
bool writing_enabled_
Definition: recorder.h:185
bool checkDuration(const ros::Time &)
Definition: recorder.cpp:443
static WallTime now()
void snapshotTrigger(std_msgs::Empty::ConstPtr trigger)
Callback to be invoked to actually do the recording.
Definition: recorder.cpp:367
uint64_t split_count_
split count
Definition: recorder.h:177
std::queue< OutgoingQueue > queue_queue_
queue of queues to be used by the snapshot recorders
Definition: recorder.h:179
static Time now()
ros::Time start_time_
Definition: recorder.h:183
ROSCPP_DECL void shutdown()
void doRecord()
Thread that actually does writing to file.
Definition: recorder.cpp:470
int num_subscribers_
used for book-keeping of our number of subscribers
Definition: recorder.h:167
uint64_t getSize() const
std::queue< OutgoingMessage > * queue_
queue for storing
Definition: recorder.h:173
bool ok() const
CompressionType compression
Definition: recorder.h:99
Uncompressed
static bool waitForValid()
std::vector< std::string > topics
Definition: recorder.h:115
#define ROS_ERROR(...)
std::string min_space_str
Definition: recorder.h:112
bool shouldSubscribeToTopic(std::string const &topic, bool from_node=false)
Definition: recorder.cpp:239
void write(std::string const &topic, ros::MessageEvent< T > const &event)
boost::shared_ptr< M > getMessage() const
std::string topic
Definition: recorder.h:71
boost::shared_ptr< ros::M_string > connection_header
Definition: recorder.h:73


rosbag
Author(s): Tim Field, Jeremy Leibs, James Bowman, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:53:00