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


rosbag
Author(s): Tim Field, Jeremy Leibs, James Bowman, Dirk Thomas , Jacob Perron
autogenerated on Sat Sep 14 2024 03:00:07