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/lexical_cast.hpp>
52 #include <boost/regex.hpp>
53 #include <boost/thread.hpp>
54 #include <boost/thread/xtime.hpp>
55 #include <boost/date_time/local_time/local_time.hpp>
56 
57 #include <ros/ros.h>
59 
60 #include "ros/network.h"
61 #include "ros/xmlrpc_manager.h"
62 #include "xmlrpcpp/XmlRpc.h"
63 
64 using std::cout;
65 using std::endl;
66 using std::set;
67 using std::string;
68 using std::vector;
69 using boost::shared_ptr;
70 using ros::Time;
71 
72 namespace rosbag {
73 
74 // OutgoingMessage
75 
77  topic(_topic), msg(_msg), connection_header(_connection_header), time(_time)
78 {
79 }
80 
81 // OutgoingQueue
82 
83 OutgoingQueue::OutgoingQueue(string const& _filename, std::queue<OutgoingMessage>* _queue, Time _time) :
84  filename(_filename), queue(_queue), time(_time)
85 {
86 }
87 
88 // RecorderOptions
89 
91  trigger(false),
92  record_all(false),
93  regex(false),
94  do_exclude(false),
95  quiet(false),
96  append_date(true),
97  snapshot(false),
98  verbose(false),
99  publish(false),
100  repeat_latched(false),
101  compression(compression::Uncompressed),
102  prefix(""),
103  name(""),
104  exclude_regex(),
105  buffer_size(1048576 * 256),
106  chunk_size(1024 * 768),
107  limit(0),
108  split(false),
109  max_size(0),
110  max_splits(0),
111  max_duration(-1.0),
112  node(""),
113  min_space(1024 * 1024 * 1024),
114  min_space_str("1G")
115 {
116 }
117 
118 // Recorder
119 
121  options_(options),
122  num_subscribers_(0),
123  exit_code_(0),
124  queue_size_(0),
125  split_count_(0),
126  writing_enabled_(true)
127 {
128 }
129 
131  if (options_.trigger) {
132  doTrigger();
133  return 0;
134  }
135 
136  if (options_.topics.size() == 0) {
137  // Make sure limit is not specified with automatic topic subscription
138  if (options_.limit > 0) {
139  fprintf(stderr, "Specifying a count is not valid with automatic topic subscription.\n");
140  return 1;
141  }
142 
143  // Make sure topics are specified
144  if (!options_.record_all && (options_.node == std::string(""))) {
145  fprintf(stderr, "No topics specified.\n");
146  return 1;
147  }
148  }
149 
150  ros::NodeHandle nh;
151  if (!nh.ok())
152  return 0;
153 
154  if (options_.publish)
155  {
156  pub_begin_write = nh.advertise<std_msgs::String>("begin_write", 1, true);
157  }
158 
160  queue_ = new std::queue<OutgoingMessage>;
161 
162  // Subscribe to each topic
163  if (!options_.regex) {
164  for (string const& topic : options_.topics)
165  subscribe(topic);
166  }
167 
169  ROS_WARN("/use_sim_time set to true and no clock published. Still waiting for valid time...");
170 
172 
174 
175  // Don't bother doing anything if we never got a valid time
176  if (!nh.ok())
177  return 0;
178 
179  ros::Subscriber trigger_sub;
180 
181  // Spin up a thread for writing to the file
182  boost::thread record_thread;
183  if (options_.snapshot)
184  {
185  record_thread = boost::thread([this]() {
186  try
187  {
188  this->doRecordSnapshotter();
189  }
190  catch (const rosbag::BagException& ex)
191  {
192  ROS_ERROR_STREAM(ex.what());
193  exit_code_ = 1;
194  }
195  catch (const std::exception& ex)
196  {
197  ROS_ERROR_STREAM(ex.what());
198  exit_code_ = 2;
199  }
200  catch (...)
201  {
202  ROS_ERROR_STREAM("Unknown exception thrown while recording bag, exiting.");
203  exit_code_ = 3;
204  }
205  });
206 
207  // Subscribe to the snapshot trigger
208  trigger_sub = nh.subscribe<std_msgs::Empty>("snapshot_trigger", 100, boost::bind(&Recorder::snapshotTrigger, this, boost::placeholders::_1));
209  }
210  else
211  {
212  record_thread = boost::thread([this]() {
213  try
214  {
215  this->doRecord();
216  }
217  catch (const rosbag::BagException& ex)
218  {
219  ROS_ERROR_STREAM(ex.what());
220  exit_code_ = 1;
221  }
222  catch (const std::exception& ex)
223  {
224  ROS_ERROR_STREAM(ex.what());
225  exit_code_ = 2;
226  }
227  catch (...)
228  {
229  ROS_ERROR_STREAM("Unknown exception thrown while recording bag, exiting.");
230  exit_code_ = 3;
231  }
232  });
233  }
234 
235 
236 
237  ros::Timer check_master_timer;
238  if (options_.record_all || options_.regex || (options_.node != std::string("")))
239  {
240  // check for master first
242  check_master_timer = nh.createTimer(ros::Duration(1.0), boost::bind(&Recorder::doCheckMaster, this, boost::placeholders::_1, boost::ref(nh)));
243  }
244 
245  ros::AsyncSpinner s(10);
246  s.start();
247 
248  record_thread.join();
249  queue_condition_.notify_all();
250  delete queue_;
251 
252  return exit_code_;
253 }
254 
256  ROS_INFO("Subscribing to %s", topic.c_str());
257 
258  ros::NodeHandle nh;
259  shared_ptr<int> count(boost::make_shared<int>(options_.limit));
260  shared_ptr<ros::Subscriber> sub(boost::make_shared<ros::Subscriber>());
261 
263  ops.topic = topic;
264  ops.queue_size = 100;
265  ops.md5sum = ros::message_traits::md5sum<topic_tools::ShapeShifter>();
266  ops.datatype = ros::message_traits::datatype<topic_tools::ShapeShifter>();
267  ops.helper = boost::make_shared<ros::SubscriptionCallbackHelperT<
269  boost::bind(&Recorder::doQueue, this, boost::placeholders::_1, topic, sub, count));
271  *sub = nh.subscribe(ops);
272 
273  currently_recording_.insert(topic);
275 
276  return sub;
277 }
278 
279 bool Recorder::isSubscribed(string const& topic) const {
280  return currently_recording_.find(topic) != currently_recording_.end();
281 }
282 
283 bool Recorder::shouldSubscribeToTopic(std::string const& topic, bool from_node) {
284  // ignore already known topics
285  if (isSubscribed(topic)) {
286  return false;
287  }
288 
289  // subtract exclusion regex, if any
290  if(options_.do_exclude && boost::regex_match(topic, options_.exclude_regex)) {
291  return false;
292  }
293 
294  if(options_.record_all || from_node) {
295  return true;
296  }
297 
298  if (options_.regex) {
299  // Treat the topics as regular expressions
300  return std::any_of(
301  std::begin(options_.topics), std::end(options_.topics),
302  [&topic] (string const& regex_str){
303  boost::regex e(regex_str);
304  boost::smatch what;
305  return boost::regex_match(topic, what, e, boost::match_extra);
306  });
307  }
308 
309  return std::find(std::begin(options_.topics), std::end(options_.topics), topic)
310  != std::end(options_.topics);
311 }
312 
313 template<class T>
314 std::string Recorder::timeToStr(T ros_t)
315 {
316  (void)ros_t;
317  std::stringstream msg;
318  const boost::posix_time::ptime now=
319  boost::posix_time::second_clock::local_time();
320  boost::posix_time::time_facet *const f=
321  new boost::posix_time::time_facet("%Y-%m-%d-%H-%M-%S");
322  msg.imbue(std::locale(msg.getloc(),f));
323  msg << now;
324  return msg.str();
325 }
326 
329  //void Recorder::doQueue(topic_tools::ShapeShifter::ConstPtr msg, string const& topic, shared_ptr<ros::Subscriber> subscriber, shared_ptr<int> count) {
330  Time rectime = Time::now();
331 
332  if (options_.verbose)
333  cout << "Received message on topic " << subscriber->getTopic() << endl;
334 
335  OutgoingMessage out(topic, msg_event.getMessage(), msg_event.getConnectionHeaderPtr(), rectime);
336 
337  {
338  boost::mutex::scoped_lock lock(queue_mutex_);
339 
340  queue_->push(out);
341  queue_size_ += out.msg->size();
342 
344  {
345  ros::M_string::const_iterator it = out.connection_header->find("latching");
346  if ((it != out.connection_header->end()) && (it->second == "1"))
347  {
348  ros::M_string::const_iterator it2 = out.connection_header->find("callerid");
349  if (it2 != out.connection_header->end())
350  {
351  auto const result = latched_msgs_.insert({{subscriber->getTopic(), it2->second}, out});
352  if (not result.second) // The map::insert function does not update values of existing keys
353  {
354  result.first->second = out;
355  }
356  }
357  }
358  }
359 
360  // Check to see if buffer has been exceeded
362  OutgoingMessage drop = queue_->front();
363  queue_->pop();
364  queue_size_ -= drop.msg->size();
365 
366  if (!options_.snapshot) {
367  Time now = Time::now();
368  if (now > last_buffer_warn_ + ros::Duration(5.0)) {
369  ROS_WARN("rosbag record buffer exceeded. Dropping oldest queued message.");
370  last_buffer_warn_ = now;
371  }
372  }
373  }
374  }
375 
376  if (!options_.snapshot)
377  queue_condition_.notify_all();
378 
379  // If we are book-keeping count, decrement and possibly shutdown
380  if ((*count) > 0) {
381  (*count)--;
382  if ((*count) == 0) {
383  subscriber->shutdown();
384 
386 
387  if (num_subscribers_ == 0)
388  ros::shutdown();
389  }
390  }
391 }
392 
394  vector<string> parts;
395 
396  std::string prefix = options_.prefix;
397  size_t ind = prefix.rfind(".bag");
398 
399  if (ind != std::string::npos && ind == prefix.size() - 4)
400  {
401  prefix.erase(ind);
402  }
403 
404  if (prefix.length() > 0)
405  parts.push_back(prefix);
406  if (options_.append_date)
407  parts.push_back(timeToStr(ros::WallTime::now()));
408  if (options_.split)
409  parts.push_back(boost::lexical_cast<string>(split_count_));
410 
411  if (parts.size() == 0)
412  {
413  throw BagException("Bag filename is empty (neither of these was specified: prefix, append_date, split)");
414  }
415 
416  target_filename_ = parts[0];
417  for (unsigned int i = 1; i < parts.size(); i++)
418  target_filename_ += string("_") + parts[i];
419 
420  target_filename_ += string(".bag");
421  write_filename_ = target_filename_ + string(".active");
422 }
423 
425 void Recorder::snapshotTrigger(std_msgs::Empty::ConstPtr trigger) {
426  (void)trigger;
427  updateFilenames();
428 
429  ROS_INFO("Triggered snapshot recording with name '%s'.", target_filename_.c_str());
430 
431  {
432  boost::mutex::scoped_lock lock(queue_mutex_);
433  queue_queue_.push(OutgoingQueue(target_filename_, queue_, Time::now()));
434  queue_ = new std::queue<OutgoingMessage>;
435  queue_size_ = 0;
436  }
437 
438  queue_condition_.notify_all();
439 }
440 
444 
445  updateFilenames();
446  try {
448  }
449  catch (const rosbag::BagException& e) {
450  ROS_ERROR("Error writing: %s", e.what());
451  exit_code_ = 1;
452  ros::shutdown();
453  }
454  ROS_INFO("Recording to '%s'.", target_filename_.c_str());
455 
457  {
458  // Start each new bag file with copies of all latched messages.
459  ros::Time now = ros::Time::now();
460  for (auto const& out : latched_msgs_)
461  {
462  // Overwrite the original receipt time, otherwise the new bag will
463  // have a gap before the new messages start.
464  bag_.write(out.second.topic, now, *out.second.msg, out.second.connection_header);
465  }
466  }
467 
468  if (options_.publish)
469  {
470  std_msgs::String msg;
471  msg.data = target_filename_.c_str();
473  }
474 }
475 
477  ROS_INFO("Closing '%s'.", target_filename_.c_str());
478  bag_.close();
479  rename(write_filename_.c_str(), target_filename_.c_str());
480 }
481 
483 {
484  if(options_.max_splits>0)
485  {
486  current_files_.push_back(target_filename_);
488  {
489  int err = unlink(current_files_.front().c_str());
490  if(err != 0)
491  {
492  ROS_ERROR("Unable to remove %s: %s", current_files_.front().c_str(), strerror(errno));
493  }
494  current_files_.pop_front();
495  }
496  }
497 }
498 
500 {
501  if (options_.max_size > 0)
502  {
503  if (bag_.getSize() > options_.max_size)
504  {
505  if (options_.split)
506  {
507  stopWriting();
508  split_count_++;
509  checkNumSplits();
510  startWriting();
511  } else {
512  ros::shutdown();
513  return true;
514  }
515  }
516  }
517  return false;
518 }
519 
521 {
523  {
525  {
526  if (options_.split)
527  {
528  while (start_time_ + options_.max_duration < t)
529  {
530  stopWriting();
531  split_count_++;
532  checkNumSplits();
534  startWriting();
535  }
536  } else {
537  ros::shutdown();
538  return true;
539  }
540  }
541  }
542  return false;
543 }
544 
545 
548  // Open bag file for writing
549  startWriting();
550 
551  // Schedule the disk space check
553 
554  try
555  {
556  checkDisk();
557  }
558  catch (const rosbag::BagException& ex)
559  {
560  ROS_ERROR_STREAM(ex.what());
561  exit_code_ = 1;
562  stopWriting();
563  return;
564  }
565 
567 
568  // Technically the queue_mutex_ should be locked while checking empty.
569  // Except it should only get checked if the node is not ok, and thus
570  // it shouldn't be in contention.
571  ros::NodeHandle nh;
572  while (nh.ok() || !queue_->empty()) {
573  boost::unique_lock<boost::mutex> lock(queue_mutex_);
574 
575  bool finished = false;
576  while (queue_->empty()) {
577  if (!nh.ok()) {
578  lock.release()->unlock();
579  finished = true;
580  break;
581  }
582  boost::xtime xt;
583  boost::xtime_get(&xt, boost::TIME_UTC_);
584  xt.nsec += 250000000;
585  queue_condition_.timed_wait(lock, xt);
587  {
588  finished = true;
589  break;
590  }
591  }
592  if (finished)
593  break;
594 
595  OutgoingMessage out = queue_->front();
596  queue_->pop();
597  queue_size_ -= out.msg->size();
598 
599  lock.release()->unlock();
600 
601  if (checkSize())
602  break;
603 
604  if (checkDuration(out.time))
605  break;
606 
607  try
608  {
609  if (scheduledCheckDisk() && checkLogging())
610  bag_.write(out.topic, out.time, *out.msg, out.connection_header);
611  }
612  catch (const rosbag::BagException& ex)
613  {
614  ROS_ERROR_STREAM(ex.what());
615  exit_code_ = 1;
616  break;
617  }
618  }
619 
620  stopWriting();
621 }
622 
624  ros::NodeHandle nh;
625 
626  while (nh.ok() || !queue_queue_.empty()) {
627  boost::unique_lock<boost::mutex> lock(queue_mutex_);
628  while (queue_queue_.empty()) {
629  if (!nh.ok())
630  return;
631  queue_condition_.wait(lock);
632  }
633 
634  OutgoingQueue out_queue = queue_queue_.front();
635  queue_queue_.pop();
636 
637  lock.release()->unlock();
638 
639  string target_filename = out_queue.filename;
640  string write_filename = target_filename + string(".active");
641 
642  try {
643  bag_.open(write_filename, bagmode::Write);
644  }
645  catch (const rosbag::BagException& ex) {
646  ROS_ERROR("Error writing: %s", ex.what());
647  return;
648  }
649 
650  while (!out_queue.queue->empty()) {
651  OutgoingMessage out = out_queue.queue->front();
652  out_queue.queue->pop();
653 
654  bag_.write(out.topic, out.time, *out.msg);
655  }
656 
657  stopWriting();
658  }
659 }
660 
662  (void)e;
663  (void)node_handle;
665  if (ros::master::getTopics(topics)) {
666  for (ros::master::TopicInfo const& t : topics) {
667  if (shouldSubscribeToTopic(t.name))
668  subscribe(t.name);
669  }
670  }
671 
672  if (options_.node != std::string(""))
673  {
674 
676  req[0] = ros::this_node::getName();
677  req[1] = options_.node;
678  XmlRpc::XmlRpcValue resp;
679  XmlRpc::XmlRpcValue payload;
680 
681  if (ros::master::execute("lookupNode", req, resp, payload, true))
682  {
683  std::string peer_host;
684  uint32_t peer_port;
685 
686  if (!ros::network::splitURI(static_cast<std::string>(resp[2]), peer_host, peer_port))
687  {
688  ROS_ERROR("Bad xml-rpc URI trying to inspect node at: [%s]", static_cast<std::string>(resp[2]).c_str());
689  } else {
690 
691  XmlRpc::XmlRpcClient c(peer_host.c_str(), peer_port, "/");
692  XmlRpc::XmlRpcValue req2;
693  XmlRpc::XmlRpcValue resp2;
694  req2[0] = ros::this_node::getName();
695  c.execute("getSubscriptions", req2, resp2);
696 
697  if (!c.isFault() && resp2.valid() && resp2.size() > 0 && static_cast<int>(resp2[0]) == 1)
698  {
699  for(int i = 0; i < resp2[2].size(); i++)
700  {
701  if (shouldSubscribeToTopic(resp2[2][i][0], true))
702  subscribe(resp2[2][i][0]);
703  }
704  } else {
705  ROS_ERROR("Node at: [%s] failed to return subscriptions.", static_cast<std::string>(resp[2]).c_str());
706  }
707  }
708  }
709  }
710 }
711 
713  ros::NodeHandle nh;
714  ros::Publisher pub = nh.advertise<std_msgs::Empty>("snapshot_trigger", 1, true);
715  pub.publish(std_msgs::Empty());
716 
717  ros::Timer terminate_timer = nh.createTimer(ros::Duration(1.0), boost::bind(&ros::shutdown));
718  ros::spin();
719 }
720 
722  boost::mutex::scoped_lock lock(check_disk_mutex_);
723 
725  return true;
726 
728  return checkDisk();
729 }
730 
732 #if BOOST_FILESYSTEM_VERSION < 3
733  struct statvfs fiData;
734  if ((statvfs(bag_.getFileName().c_str(), &fiData)) < 0)
735  {
736  ROS_WARN("Failed to check filesystem stats.");
737  return true;
738  }
739  unsigned long long free_space = 0;
740  free_space = (unsigned long long) (fiData.f_bsize) * (unsigned long long) (fiData.f_bavail);
741  if (free_space < options_.min_space)
742  {
743  ROS_ERROR("Less than %s of space free on disk with '%s'. Disabling recording.", options_.min_space_str.c_str(), bag_.getFileName().c_str());
744  writing_enabled_ = false;
745  return false;
746  }
747  else if (free_space < 5 * options_.min_space)
748  {
749  ROS_WARN("Less than 5 x %s of space free on disk with '%s'.", options_.min_space_str.c_str(), bag_.getFileName().c_str());
750  }
751  else
752  {
753  writing_enabled_ = true;
754  }
755 #else
756  boost::filesystem::path p(boost::filesystem::system_complete(bag_.getFileName().c_str()));
757  p = p.parent_path();
758  boost::filesystem::space_info info;
759  try
760  {
761  info = boost::filesystem::space(p);
762  }
763  catch (const boost::filesystem::filesystem_error& e)
764  {
765  ROS_WARN("Failed to check filesystem stats [%s].", e.what());
766  writing_enabled_ = false;
767  return false;
768  }
769  if ( info.available < options_.min_space)
770  {
771  writing_enabled_ = false;
772  throw BagException("Less than " + options_.min_space_str + " of space free on disk with " + bag_.getFileName() + ". Disabling recording.");
773  }
774  else if (info.available < 5 * options_.min_space)
775  {
776  ROS_WARN("Less than 5 x %s of space free on disk with '%s'.", options_.min_space_str.c_str(), bag_.getFileName().c_str());
777  writing_enabled_ = true;
778  }
779  else
780  {
781  writing_enabled_ = true;
782  }
783 #endif
784  return true;
785 }
786 
788  if (writing_enabled_)
789  return true;
790 
792  if (now >= warn_next_) {
793  warn_next_ = now + ros::WallDuration().fromSec(5.0);
794  ROS_WARN("Not logging message because logging disabled. Most likely cause is a full disk.");
795  }
796  return false;
797 }
798 
799 } // namespace rosbag
rosbag::Recorder::check_disk_next_
ros::WallTime check_disk_next_
Definition: recorder.h:224
rosbag::Recorder::split_count_
uint64_t split_count_
split count
Definition: recorder.h:214
XmlRpc::XmlRpcValue::size
int size() const
rosbag::Recorder::stopWriting
void stopWriting()
Definition: recorder.cpp:476
rosbag::Recorder::doRecord
void doRecord()
Thread that actually does writing to file.
Definition: recorder.cpp:547
rosbag::RecorderOptions::RecorderOptions
RecorderOptions()
Definition: recorder.cpp:90
ros::Publisher
DurationBase< WallDuration >::fromSec
WallDuration & fromSec(double t)
rosbag::Recorder::checkDisk
bool checkDisk()
Definition: recorder.cpp:731
rosbag::Recorder::bag_
Bag bag_
Definition: recorder.h:195
recorder.h
rosbag::Recorder::scheduledCheckDisk
bool scheduledCheckDisk()
Definition: recorder.cpp:721
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr
rosbag::RecorderOptions::publish
bool publish
Definition: recorder.h:132
rosbag::OutgoingMessage::time
ros::Time time
Definition: recorder.h:139
rosbag::OutgoingQueue::OutgoingQueue
OutgoingQueue(std::string const &_filename, std::queue< OutgoingMessage > *_queue, ros::Time _time)
Definition: recorder.cpp:83
rosbag::RecorderOptions::prefix
std::string prefix
Definition: recorder.h:135
s
XmlRpcServer s
rosbag::Recorder::Recorder
Recorder(RecorderOptions const &options)
Definition: recorder.cpp:120
rosbag::RecorderOptions
Definition: recorder.h:120
ros.h
rosbag::RecorderOptions::min_space_str
std::string min_space_str
Definition: recorder.h:147
rosbag::Recorder::queue_size_
uint64_t queue_size_
queue size
Definition: recorder.h:211
rosbag::OutgoingMessage::OutgoingMessage
OutgoingMessage(std::string const &_topic, topic_tools::ShapeShifter::ConstPtr _msg, boost::shared_ptr< ros::M_string > _connection_header, ros::Time _time)
Definition: recorder.cpp:76
rosbag::Recorder::subscribe
boost::shared_ptr< ros::Subscriber > subscribe(std::string const &topic)
Definition: recorder.cpp:255
time.h
rosbag::Recorder::queue_mutex_
boost::mutex queue_mutex_
mutex for queue
Definition: recorder.h:209
ros::SubscribeOptions::topic
std::string topic
ros::SubscribeOptions::transport_hints
TransportHints transport_hints
rosbag::Recorder::checkNumSplits
void checkNumSplits()
Definition: recorder.cpp:482
rosbag::RecorderOptions::max_splits
uint32_t max_splits
Definition: recorder.h:143
ros::AsyncSpinner
XmlRpc::XmlRpcClient::execute
bool execute(const char *method, XmlRpcValue const &params, XmlRpcValue &result)
ros::SubscriptionCallbackHelperT
rosbag::Recorder::updateFilenames
void updateFilenames()
Definition: recorder.cpp:393
ros::shutdown
ROSCPP_DECL void shutdown()
rosbag::OutgoingMessage
Definition: recorder.h:99
rosbag::Recorder::run
int run()
Definition: recorder.cpp:130
network.h
rosbag::RecorderOptions::transport_hints
ros::TransportHints transport_hints
Definition: recorder.h:148
XmlRpc::XmlRpcClient
rosbag::Recorder::warn_next_
ros::WallTime warn_next_
Definition: recorder.h:225
rosbag::Recorder::latched_msgs_
std::map< std::pair< std::string, std::string >, OutgoingMessage > latched_msgs_
Definition: recorder.h:206
rosbag::Bag::close
void close()
rosbag::Recorder::exit_code_
int exit_code_
eventual exit code
Definition: recorder.h:204
rosbag::Recorder::write_filename_
std::string write_filename_
Definition: recorder.h:198
ros::master::getTopics
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
rosbag::RecorderOptions::min_space
unsigned long long min_space
Definition: recorder.h:146
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
f
f
rosbag::RecorderOptions::split
bool split
Definition: recorder.h:141
rosbag::Recorder::queue_condition_
boost::condition_variable_any queue_condition_
conditional variable for queue
Definition: recorder.h:208
rosbag::Recorder::start_time_
ros::Time start_time_
Definition: recorder.h:220
rosbag::RecorderOptions::verbose
bool verbose
Definition: recorder.h:131
rosbag::BagException
rosbag::RecorderOptions::max_size
uint64_t max_size
Definition: recorder.h:142
rosbag::Recorder::num_subscribers_
int num_subscribers_
used for book-keeping of our number of subscribers
Definition: recorder.h:202
rosbag::Recorder::queue_
std::queue< OutgoingMessage > * queue_
queue for storing
Definition: recorder.h:210
rosbag::RecorderOptions::node
std::string node
Definition: recorder.h:145
ros::SubscribeOptions::md5sum
std::string md5sum
rosbag::RecorderOptions::buffer_size
uint32_t buffer_size
Definition: recorder.h:138
rosbag::OutgoingMessage::msg
topic_tools::ShapeShifter::ConstPtr msg
Definition: recorder.h:137
rosbag::OutgoingQueue
Definition: recorder.h:110
xmlrpc_manager.h
rosbag::Recorder::timeToStr
static std::string timeToStr(T ros_t)
Definition: recorder.cpp:314
rosbag::Bag::getSize
uint64_t getSize() const
rosbag::RecorderOptions::snapshot
bool snapshot
Definition: recorder.h:130
rosbag::Bag::setCompression
void setCompression(CompressionType compression)
rosbag::Recorder::doCheckMaster
void doCheckMaster(ros::TimerEvent const &e, ros::NodeHandle &node_handle)
Definition: recorder.cpp:661
rosbag::RecorderOptions::append_date
bool append_date
Definition: recorder.h:129
ros::master::V_TopicInfo
std::vector< TopicInfo > V_TopicInfo
ros::WallTime::now
static WallTime now()
rosbag::RecorderOptions::limit
uint32_t limit
Definition: recorder.h:140
rosbag::Bag::getFileName
std::string getFileName() const
rosbag::Recorder::doQueue
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:328
rosbag::RecorderOptions::compression
CompressionType compression
Definition: recorder.h:134
rosbag::Recorder::writing_enabled_
bool writing_enabled_
Definition: recorder.h:222
rosbag::Recorder::snapshotTrigger
void snapshotTrigger(std_msgs::Empty::ConstPtr trigger)
Callback to be invoked to actually do the recording.
Definition: recorder.cpp:425
rosbag::OutgoingMessage::topic
std::string topic
Definition: recorder.h:136
XmlRpc.h
ROS_WARN
#define ROS_WARN(...)
rosbag::bagmode::Write
Write
rosbag::RecorderOptions::topics
std::vector< std::string > topics
Definition: recorder.h:150
XmlRpc::XmlRpcClient::isFault
bool isFault() const
rosbag::OutgoingQueue::queue
std::queue< OutgoingMessage > * queue
Definition: recorder.h:116
rosbag::Recorder::current_files_
std::list< std::string > current_files_
Definition: recorder.h:199
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::TimerEvent
ros::WallTime
rosbag::RecorderOptions::repeat_latched
bool repeat_latched
Definition: recorder.h:133
ros::master::execute
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
rosbag::OutgoingQueue::filename
std::string filename
Definition: recorder.h:115
shape_shifter.h
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
rosbag::RecorderOptions::regex
bool regex
Definition: recorder.h:126
rosbag::Recorder::doTrigger
void doTrigger()
Definition: recorder.cpp:712
rosbag::RecorderOptions::chunk_size
uint32_t chunk_size
Definition: recorder.h:139
rosbag::RecorderOptions::max_duration
ros::Duration max_duration
Definition: recorder.h:144
ros::NodeHandle::ok
bool ok() const
rosbag::Bag::write
void write(std::string const &topic, ros::MessageEvent< T > const &event)
rosbag::Recorder::doRecordSnapshotter
void doRecordSnapshotter()
Definition: recorder.cpp:623
ros::SubscribeOptions
XmlRpc::XmlRpcValue::valid
bool valid() const
rosbag::Recorder::checkDuration
bool checkDuration(const ros::Time &)
Definition: recorder.cpp:520
ros::Time
rosbag::Recorder::checkLogging
bool checkLogging()
Definition: recorder.cpp:787
rosbag::Recorder::target_filename_
std::string target_filename_
Definition: recorder.h:197
ros::SubscribeOptions::queue_size
uint32_t queue_size
rosbag::Recorder::shouldSubscribeToTopic
bool shouldSubscribeToTopic(std::string const &topic, bool from_node=false)
Definition: recorder.cpp:283
rosbag::Recorder::options_
RecorderOptions options_
Definition: recorder.h:193
ROS_ERROR
#define ROS_ERROR(...)
Uncompressed
Uncompressed
ros::Time::waitForValid
static bool waitForValid()
rosbag::Recorder::queue_queue_
std::queue< OutgoingQueue > queue_queue_
queue of queues to be used by the snapshot recorders
Definition: recorder.h:216
ros::MessageEvent::getConnectionHeaderPtr
const boost::shared_ptr< M_string > & getConnectionHeaderPtr() const
rosbag::Recorder::startWriting
void startWriting()
Definition: recorder.cpp:441
ros::spin
ROSCPP_DECL void spin()
rosbag
rosbag::OutgoingMessage::connection_header
boost::shared_ptr< ros::M_string > connection_header
Definition: recorder.h:138
ros::MessageEvent::getMessage
boost::shared_ptr< M > getMessage() const
rosbag::RecorderOptions::do_exclude
bool do_exclude
Definition: recorder.h:127
ros::SubscribeOptions::datatype
std::string datatype
rosbag::Recorder::check_disk_mutex_
boost::mutex check_disk_mutex_
Definition: recorder.h:223
rosbag::Recorder::pub_begin_write
ros::Publisher pub_begin_write
Definition: recorder.h:227
ros::WallDuration
rosbag::Recorder::last_buffer_warn_
ros::Time last_buffer_warn_
Definition: recorder.h:218
rosbag::Bag::open
void open(std::string const &filename, uint32_t mode=bagmode::Read)
ros::SubscribeOptions::helper
SubscriptionCallbackHelperPtr helper
ROS_INFO
#define ROS_INFO(...)
rosbag::Bag::setChunkThreshold
void setChunkThreshold(uint32_t chunk_threshold)
ros::master::TopicInfo
rosbag::RecorderOptions::trigger
bool trigger
Definition: recorder.h:124
rosbag::RecorderOptions::exclude_regex
boost::regex exclude_regex
Definition: recorder.h:137
rosbag::Recorder::checkSize
bool checkSize()
Definition: recorder.cpp:499
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
rosbag::Recorder::isSubscribed
bool isSubscribed(std::string const &topic) const
Definition: recorder.cpp:279
ros::Duration
ros::network::splitURI
ROSCPP_DECL bool splitURI(const std::string &uri, std::string &host, uint32_t &port)
rosbag::RecorderOptions::record_all
bool record_all
Definition: recorder.h:125
ros::Timer
rosbag::Recorder::currently_recording_
std::set< std::string > currently_recording_
set of currently recording topics
Definition: recorder.h:201
XmlRpc::XmlRpcValue
ros::NodeHandle
ros::MessageEvent
ros::Subscriber
ros::Time::now
static Time now()


rosbag
Author(s): Tim Field, Jeremy Leibs, James Bowman, Dirk Thomas , Jacob Perron
autogenerated on Tue May 20 2025 03:00:39