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


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