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