38 #include "boost/program_options.hpp" 43 namespace po = boost::program_options;
49 po::options_description desc(
"Allowed 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.");
75 po::positional_options_description p;
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)
86 }
catch (boost::program_options::unknown_option& e)
91 if (vm.count(
"help")) {
92 std::cout << desc << std::endl;
98 if (vm.count(
"regex"))
100 if (vm.count(
"exclude"))
105 if (vm.count(
"quiet"))
107 if (vm.count(
"output-prefix"))
109 opts.
prefix = vm[
"output-prefix"].as<std::string>();
112 if (vm.count(
"output-name"))
114 opts.
prefix = vm[
"output-name"].as<std::string>();
117 if (vm.count(
"split"))
121 int S = vm[
"split"].as<
int>();
124 ROS_WARN(
"Use of \"--split <MAX_SIZE>\" has been deprecated. Please use --split --size <MAX_SIZE> or --split --duration <MAX_DURATION>");
127 opts.
max_size = 1048576 *
static_cast<uint64_t
>(S);
130 if(vm.count(
"max-splits"))
134 ROS_WARN(
"--max-splits is ignored without --split");
141 if (vm.count(
"buffsize"))
143 int m = vm[
"buffsize"].as<
int>();
148 if (vm.count(
"chunksize"))
150 int chnk_sz = vm[
"chunksize"].as<
int>();
155 if (vm.count(
"limit"))
157 opts.
limit = vm[
"limit"].as<
int>();
159 if (vm.count(
"min-space"))
161 std::string ms = vm[
"min-space"].as<std::string>();
162 long long int value = 1073741824ull;
167 if (sscanf(ms.c_str(),
" %lld%c", &value, &mul) > 0) {
189 if (vm.count(
"bz2") && vm.count(
"lz4"))
201 if (vm.count(
"duration"))
203 std::string duration_str = vm[
"duration"].as<std::string>();
206 double multiplier = 1.0;
207 std::string unit(
"");
209 std::istringstream iss(duration_str);
210 if ((iss >> duration).fail())
211 throw ros::Exception(
"Duration must start with a floating point number.");
213 if ( (!iss.eof() && ((iss >> unit).fail())) )
217 if (unit == std::string(
""))
219 else if (unit == std::string(
"s"))
221 else if (unit == std::string(
"m"))
223 else if (unit == std::string(
"h"))
233 if (vm.count(
"size"))
235 opts.
max_size = vm[
"size"].as<uint64_t>() * 1048576;
239 if (vm.count(
"node"))
241 opts.
node = vm[
"node"].as<std::string>();
242 std::cout <<
"Recording from: " << opts.
node << std::endl;
244 if (vm.count(
"tcpnodelay"))
254 if (vm.count(
"topic"))
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();
262 opts.
topics.push_back(*i);
269 fprintf(stderr,
"Warning: Exclusion regex given, but no topics to subscribe to.\n" 270 "Adding implicit 'record all'.");
287 int main(
int argc,
char** argv) {
299 ROS_ERROR(
"Error reading options: %s", ex.what());
302 catch(boost::regex_error
const& ex) {
303 ROS_ERROR(
"Error reading options: %s\n", ex.what());
309 int result = recorder.
run();
ros::TransportHints transport_hints
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::regex exclude_regex
ros::Duration max_duration
TransportHints & tcpNoDelay(bool nodelay=true)
rosbag::RecorderOptions parseOptions(int argc, char **argv)
Parse the command-line arguments for recorder options.
unsigned long long min_space
ROSCPP_DECL void requestShutdown()
int main(int argc, char **argv)
void signal_handler(int signal)
CompressionType compression
std::vector< std::string > topics
std::string min_space_str