record.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 #include "rosbag/exceptions.h"
37 
38 #include "boost/program_options.hpp"
39 #include <signal.h>
40 #include <string>
41 #include <sstream>
42 
43 namespace po = boost::program_options;
44 
46 rosbag::RecorderOptions parseOptions(int argc, char** argv) {
48 
49  po::options_description desc("Allowed options");
50 
51  desc.add_options()
52  ("help,h", "produce help message")
53  ("all,a", "record all topics")
54  ("regex,e", "match topics using regular expressions")
55  ("exclude,x", po::value<std::string>(), "exclude topics matching regular expressions")
56  ("quiet,q", "suppress console output")
57  ("publish,p", "Publish a msg when the record begin")
58  ("output-prefix,o", po::value<std::string>(), "prepend PREFIX to beginning of bag name")
59  ("output-name,O", po::value<std::string>(), "record bagnamed NAME.bag")
60  ("buffsize,b", po::value<int>()->default_value(256), "Use an internal buffer of SIZE MB (Default: 256)")
61  ("chunksize", po::value<int>()->default_value(768), "Set chunk size of message data, in KB (Default: 768. Advanced)")
62  ("limit,l", po::value<int>()->default_value(0), "Only record NUM messages on each topic")
63  ("min-space,L", po::value<std::string>()->default_value("1G"), "Minimum allowed space on recording device (use G,M,k multipliers)")
64  ("bz2,j", "use BZ2 compression")
65  ("lz4", "use LZ4 compression")
66  ("split", po::value<int>()->implicit_value(0), "Split the bag file and continue recording when maximum size or maximum duration reached.")
67  ("max-splits", po::value<int>(), "Keep a maximum of N bag files, when reaching the maximum erase the oldest one to keep a constant number of files.")
68  ("topic", po::value< std::vector<std::string> >(), "topic to record")
69  ("size", po::value<uint64_t>(), "The maximum size of the bag to record in MB.")
70  ("duration", po::value<std::string>(), "Record a bag of maximum duration in seconds, unless 'm', or 'h' is appended.")
71  ("node", po::value<std::string>(), "Record all topics subscribed to by a specific node.")
72  ("tcpnodelay", "Use the TCP_NODELAY transport hint when subscribing to topics.")
73  ("udp", "Use the UDP transport hint when subscribing to topics.");
74 
75 
76  po::positional_options_description p;
77  p.add("topic", -1);
78 
79  po::variables_map vm;
80 
81  try
82  {
83  po::store(po::command_line_parser(argc, argv).options(desc).positional(p).run(), vm);
84  } catch (const boost::program_options::invalid_command_line_syntax& e)
85  {
86  throw ros::Exception(e.what());
87  } catch (const boost::program_options::unknown_option& e)
88  {
89  throw ros::Exception(e.what());
90  }
91 
92  if (vm.count("help")) {
93  std::cout << desc << std::endl;
94  exit(0);
95  }
96 
97  if (vm.count("all"))
98  opts.record_all = true;
99  if (vm.count("regex"))
100  opts.regex = true;
101  if (vm.count("exclude"))
102  {
103  opts.do_exclude = true;
104  opts.exclude_regex = vm["exclude"].as<std::string>();
105  }
106  if (vm.count("quiet"))
107  opts.quiet = true;
108  if (vm.count("publish"))
109  opts.publish = true;
110  if (vm.count("output-prefix"))
111  {
112  opts.prefix = vm["output-prefix"].as<std::string>();
113  opts.append_date = true;
114  }
115  if (vm.count("output-name"))
116  {
117  opts.prefix = vm["output-name"].as<std::string>();
118  opts.append_date = false;
119  }
120  if (vm.count("split"))
121  {
122  opts.split = true;
123 
124  int S = vm["split"].as<int>();
125  if (S != 0)
126  {
127  ROS_WARN("Use of \"--split <MAX_SIZE>\" has been deprecated. Please use --split --size <MAX_SIZE> or --split --duration <MAX_DURATION>");
128  if (S < 0)
129  throw ros::Exception("Split size must be 0 or positive");
130  opts.max_size = 1048576 * static_cast<uint64_t>(S);
131  }
132  }
133  if(vm.count("max-splits"))
134  {
135  if(!opts.split)
136  {
137  ROS_WARN("--max-splits is ignored without --split");
138  }
139  else
140  {
141  opts.max_splits = vm["max-splits"].as<int>();
142  }
143  }
144  if (vm.count("buffsize"))
145  {
146  int m = vm["buffsize"].as<int>();
147  if (m < 0)
148  throw ros::Exception("Buffer size must be 0 or positive");
149  opts.buffer_size = 1048576 * m;
150  }
151  if (vm.count("chunksize"))
152  {
153  int chnk_sz = vm["chunksize"].as<int>();
154  if (chnk_sz < 0)
155  throw ros::Exception("Chunk size must be 0 or positive");
156  opts.chunk_size = 1024 * chnk_sz;
157  }
158  if (vm.count("limit"))
159  {
160  opts.limit = vm["limit"].as<int>();
161  }
162  if (vm.count("min-space"))
163  {
164  std::string ms = vm["min-space"].as<std::string>();
165  long long int value = 1073741824ull;
166  char mul = 0;
167  // Sane default values, just in case
168  opts.min_space_str = "1G";
169  opts.min_space = value;
170  if (sscanf(ms.c_str(), " %lld%c", &value, &mul) > 0) {
171  opts.min_space_str = ms;
172  switch (mul) {
173  case 'G':
174  case 'g':
175  opts.min_space = value * 1073741824ull;
176  break;
177  case 'M':
178  case 'm':
179  opts.min_space = value * 1048576ull;
180  break;
181  case 'K':
182  case 'k':
183  opts.min_space = value * 1024ull;
184  break;
185  default:
186  opts.min_space = value;
187  break;
188  }
189  }
190  ROS_DEBUG("Rosbag using minimum space of %lld bytes, or %s", opts.min_space, opts.min_space_str.c_str());
191  }
192  if (vm.count("bz2") && vm.count("lz4"))
193  {
194  throw ros::Exception("Can only use one type of compression");
195  }
196  if (vm.count("bz2"))
197  {
199  }
200  if (vm.count("lz4"))
201  {
203  }
204  if (vm.count("duration"))
205  {
206  std::string duration_str = vm["duration"].as<std::string>();
207 
208  double duration;
209  double multiplier = 1.0;
210  std::string unit("");
211 
212  std::istringstream iss(duration_str);
213  if ((iss >> duration).fail())
214  throw ros::Exception("Duration must start with a floating point number.");
215 
216  if ( (!iss.eof() && ((iss >> unit).fail())) )
217  {
218  throw ros::Exception("Duration unit must be s, m, or h");
219  }
220  if (unit == std::string(""))
221  multiplier = 1.0;
222  else if (unit == std::string("s"))
223  multiplier = 1.0;
224  else if (unit == std::string("m"))
225  multiplier = 60.0;
226  else if (unit == std::string("h"))
227  multiplier = 3600.0;
228  else
229  throw ros::Exception("Duration unit must be s, m, or h");
230 
231 
232  opts.max_duration = ros::Duration(duration * multiplier);
233  if (opts.max_duration <= ros::Duration(0))
234  throw ros::Exception("Duration must be positive.");
235  }
236  if (vm.count("size"))
237  {
238  opts.max_size = vm["size"].as<uint64_t>() * 1048576;
239  if (opts.max_size <= 0)
240  throw ros::Exception("Split size must be 0 or positive");
241  }
242  if (vm.count("node"))
243  {
244  opts.node = vm["node"].as<std::string>();
245  std::cout << "Recording from: " << opts.node << std::endl;
246  }
247  if (vm.count("tcpnodelay"))
248  {
250  }
251  if (vm.count("udp"))
252  {
253  opts.transport_hints.udp();
254  }
255 
256  // Every non-option argument is assumed to be a topic
257  if (vm.count("topic"))
258  {
259  std::vector<std::string> bags = vm["topic"].as< std::vector<std::string> >();
260  std::sort(bags.begin(), bags.end());
261  bags.erase(std::unique(bags.begin(), bags.end()), bags.end());
262  for (std::vector<std::string>::iterator i = bags.begin();
263  i != bags.end();
264  i++)
265  opts.topics.push_back(*i);
266  }
267 
268 
269  // check that argument combinations make sense
270  if(opts.exclude_regex.size() > 0 &&
271  !(opts.record_all || opts.regex)) {
272  fprintf(stderr, "Warning: Exclusion regex given, but no topics to subscribe to.\n"
273  "Adding implicit 'record all'.");
274  opts.record_all = true;
275  }
276 
277  return opts;
278 }
279 
284 void signal_handler(int signal)
285 {
286  (void) signal;
288 }
289 
290 int main(int argc, char** argv) {
291  ros::init(argc, argv, "record", ros::init_options::AnonymousName);
292 
293  // handle SIGTERM signals
294  signal(SIGTERM, signal_handler);
295 
296  // Parse the command-line options
298  try {
299  opts = parseOptions(argc, argv);
300  }
301  catch (const ros::Exception& ex) {
302  ROS_ERROR("Error reading options: %s", ex.what());
303  return 1;
304  }
305  catch(const boost::regex_error& ex) {
306  ROS_ERROR("Error reading options: %s\n", ex.what());
307  return 1;
308  }
309 
310  // Run the recorder
311  rosbag::Recorder recorder(opts);
312  int result = recorder.run();
313 
314  return result;
315 }
ros::TransportHints transport_hints
Definition: recorder.h:115
void run(class_loader::ClassLoader *loader)
TransportHints & udp()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::regex exclude_regex
Definition: recorder.h:104
#define ROS_WARN(...)
ros::Duration max_duration
Definition: recorder.h:111
TransportHints & tcpNoDelay(bool nodelay=true)
std::string prefix
Definition: recorder.h:102
rosbag::RecorderOptions parseOptions(int argc, char **argv)
Parse the command-line arguments for recorder options.
Definition: record.cpp:46
unsigned long long min_space
Definition: recorder.h:113
ROSCPP_DECL void requestShutdown()
int main(int argc, char **argv)
Definition: record.cpp:290
void signal_handler(int signal)
Definition: record.cpp:284
CompressionType compression
Definition: recorder.h:101
std::vector< std::string > topics
Definition: recorder.h:117
#define ROS_ERROR(...)
std::string min_space_str
Definition: recorder.h:114
#define ROS_DEBUG(...)


rosbag
Author(s): Tim Field, Jeremy Leibs, James Bowman, Dirk Thomas
autogenerated on Mon Feb 28 2022 23:34:21