record.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of Willow Garage, Inc. nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 ********************************************************************/
00034 
00035 #include "rosbag/recorder.h"
00036 #include "rosbag/exceptions.h"
00037 
00038 #include "boost/program_options.hpp"
00039 #include <string>
00040 #include <sstream>
00041 
00042 namespace po = boost::program_options;
00043 
00045 rosbag::RecorderOptions parseOptions(int argc, char** argv) {
00046     rosbag::RecorderOptions opts;
00047 
00048     po::options_description desc("Allowed options");
00049 
00050     desc.add_options()
00051       ("help,h", "produce help message")
00052       ("all,a", "record all topics")
00053       ("regex,e", "match topics using regular expressions")
00054       ("exclude,x", po::value<std::string>(), "exclude topics matching regular expressions")
00055       ("quiet,q", "suppress console output")
00056       ("output-prefix,o", po::value<std::string>(), "prepend PREFIX to beginning of bag name")
00057       ("output-name,O", po::value<std::string>(), "record bagnamed NAME.bag")
00058       ("buffsize,b", po::value<int>()->default_value(256), "Use an internal buffer of SIZE MB (Default: 256)")
00059       ("chunksize", po::value<int>()->default_value(768), "Set chunk size of message data, in KB (Default: 768. Advanced)")
00060       ("limit,l", po::value<int>()->default_value(0), "Only record NUM messages on each topic")
00061       ("min-space,L", po::value<std::string>()->default_value("1G"), "Minimum allowed space on recording device (use G,M,k multipliers)")
00062       ("bz2,j", "use BZ2 compression")
00063       ("lz4", "use LZ4 compression")
00064       ("split", po::value<int>()->implicit_value(0), "Split the bag file and continue recording when maximum size or maximum duration reached.")
00065       ("topic", po::value< std::vector<std::string> >(), "topic to record")
00066       ("size", po::value<int>(), "The maximum size of the bag to record in MB.")
00067       ("duration", po::value<std::string>(), "Record a bag of maximum duration in seconds, unless 'm', or 'h' is appended.")
00068       ("node", po::value<std::string>(), "Record all topics subscribed to by a specific node.");
00069 
00070   
00071     po::positional_options_description p;
00072     p.add("topic", -1);
00073     
00074     po::variables_map vm;
00075     
00076     try 
00077     {
00078       po::store(po::command_line_parser(argc, argv).options(desc).positional(p).run(), vm);
00079     } catch (boost::program_options::invalid_command_line_syntax& e)
00080     {
00081       throw ros::Exception(e.what());
00082     }  catch (boost::program_options::unknown_option& e)
00083     {
00084       throw ros::Exception(e.what());
00085     }
00086 
00087     if (vm.count("help")) {
00088       std::cout << desc << std::endl;
00089       exit(0);
00090     }
00091 
00092     if (vm.count("all"))
00093       opts.record_all = true;
00094     if (vm.count("regex"))
00095       opts.regex = true;
00096     if (vm.count("exclude"))
00097     {
00098       opts.do_exclude = true;
00099       opts.exclude_regex = vm["exclude"].as<std::string>();
00100     }
00101     if (vm.count("quiet"))
00102       opts.quiet = true;
00103     if (vm.count("output-prefix"))
00104     {
00105       opts.prefix = vm["output-prefix"].as<std::string>();
00106       opts.append_date = true;
00107     }
00108     if (vm.count("output-name"))
00109     {
00110       opts.prefix = vm["output-name"].as<std::string>();
00111       opts.append_date = false;
00112     }
00113     if (vm.count("split"))
00114     {
00115       opts.split = true;
00116 
00117       int S = vm["split"].as<int>();
00118       if (S != 0)
00119       {
00120         ROS_WARN("Use of \"--split <MAX_SIZE>\" has been deprecated.  Please use --split --size <MAX_SIZE> or --split --duration <MAX_DURATION>");
00121         if (S < 0)
00122           throw ros::Exception("Split size must be 0 or positive");
00123         opts.max_size = 1048576 * S;
00124       }
00125     }
00126     if (vm.count("buffsize"))
00127     {
00128       int m = vm["buffsize"].as<int>();
00129       if (m < 0)
00130         throw ros::Exception("Buffer size must be 0 or positive");
00131       opts.buffer_size = 1048576 * m;
00132     }
00133     if (vm.count("chunksize"))
00134     {
00135       int chnk_sz = vm["chunksize"].as<int>();
00136       if (chnk_sz < 0)
00137         throw ros::Exception("Chunk size must be 0 or positive");
00138       opts.chunk_size = 1024 * chnk_sz;
00139     }
00140     if (vm.count("limit"))
00141     {
00142       opts.limit = vm["limit"].as<int>();
00143     }
00144     if (vm.count("min-space"))
00145     {
00146         std::string ms = vm["min-space"].as<std::string>();
00147         long long int value = 1073741824ull;
00148         char mul = 0;
00149         // Sane default values, just in case
00150         opts.min_space_str = "1G";
00151         opts.min_space = value;
00152         if (sscanf(ms.c_str(), " %lld%c", &value, &mul) > 0) {
00153             opts.min_space_str = ms;
00154             switch (mul) {
00155                 case 'G':
00156                 case 'g':
00157                     opts.min_space = value * 1073741824ull;
00158                     break;
00159                 case 'M':
00160                 case 'm':
00161                     opts.min_space = value * 1048576ull;
00162                     break;
00163                 case 'K':
00164                 case 'k':
00165                     opts.min_space = value * 1024ull;
00166                     break;
00167                 default:
00168                     opts.min_space = value;
00169                     break;
00170             }
00171         }
00172         ROS_DEBUG("Rosbag using minimum space of %lld bytes, or %s", opts.min_space, opts.min_space_str.c_str());
00173     }
00174     if (vm.count("bz2") && vm.count("lz4"))
00175     {
00176       throw ros::Exception("Can only use one type of compression");
00177     }
00178     if (vm.count("bz2"))
00179     {
00180       opts.compression = rosbag::compression::BZ2;
00181     }
00182     if (vm.count("lz4"))
00183     {
00184       opts.compression = rosbag::compression::LZ4;
00185     }
00186     if (vm.count("duration"))
00187     {
00188       std::string duration_str = vm["duration"].as<std::string>();
00189 
00190       double duration;
00191       double multiplier = 1.0;
00192       std::string unit("");
00193 
00194       std::istringstream iss(duration_str);
00195       if ((iss >> duration).fail())
00196         throw ros::Exception("Duration must start with a floating point number.");
00197 
00198       if ( (!iss.eof() && ((iss >> unit).fail())) )
00199       {
00200         throw ros::Exception("Duration unit must be s, m, or h");
00201       }
00202       if (unit == std::string(""))
00203         multiplier = 1.0;
00204       else if (unit == std::string("s"))
00205         multiplier = 1.0;
00206       else if (unit == std::string("m"))
00207         multiplier = 60.0;
00208       else if (unit == std::string("h"))
00209         multiplier = 3600.0;
00210       else
00211         throw ros::Exception("Duration unit must be s, m, or h");
00212 
00213       
00214       opts.max_duration = ros::Duration(duration * multiplier);
00215       if (opts.max_duration <= ros::Duration(0))
00216         throw ros::Exception("Duration must be positive.");
00217     }
00218     if (vm.count("size"))
00219     {
00220       opts.max_size = vm["size"].as<int>() * 1048576;
00221       if (opts.max_size <= 0)
00222         throw ros::Exception("Split size must be 0 or positive");
00223     }
00224     if (vm.count("node"))
00225     {
00226       opts.node = vm["node"].as<std::string>();
00227       std::cout << "Recording from: " << opts.node << std::endl;
00228     }
00229 
00230     // Every non-option argument is assumed to be a topic
00231     if (vm.count("topic"))
00232     {
00233       std::vector<std::string> bags = vm["topic"].as< std::vector<std::string> >();
00234       std::sort(bags.begin(), bags.end());
00235       bags.erase(std::unique(bags.begin(), bags.end()), bags.end());
00236       for (std::vector<std::string>::iterator i = bags.begin();
00237            i != bags.end();
00238            i++)
00239         opts.topics.push_back(*i);
00240     }
00241 
00242 
00243     // check that argument combinations make sense
00244     if(opts.exclude_regex.size() > 0 &&
00245             !(opts.record_all || opts.regex)) {
00246         fprintf(stderr, "Warning: Exclusion regex given, but no topics to subscribe to.\n"
00247                 "Adding implicit 'record all'.");
00248         opts.record_all = true;
00249     }
00250 
00251     return opts;
00252 }
00253 
00254 int main(int argc, char** argv) {
00255     ros::init(argc, argv, "record", ros::init_options::AnonymousName);
00256 
00257     // Parse the command-line options
00258     rosbag::RecorderOptions opts;
00259     try {
00260         opts = parseOptions(argc, argv);
00261     }
00262     catch (ros::Exception const& ex) {
00263         ROS_ERROR("Error reading options: %s", ex.what());
00264         return 1;
00265     }
00266     catch(boost::regex_error const& ex) {
00267         ROS_ERROR("Error reading options: %s\n", ex.what());
00268         return 1;
00269     }
00270 
00271     // Run the recorder
00272     rosbag::Recorder recorder(opts);
00273     int result = recorder.run();
00274     
00275     return result;
00276 }


rosbag
Author(s): Tim Field, Jeremy Leibs, James Bowman
autogenerated on Thu Jun 6 2019 21:11:02