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       ("bz2,j", "use BZ2 compression")
00062       ("split", po::value<int>()->implicit_value(0), "Split the bag file and continue recording when maximum size or maximum duration reached.")
00063       ("topic", po::value< std::vector<std::string> >(), "topic to record")
00064       ("size", po::value<int>(), "The maximum size of the bag to record in MB.")
00065       ("duration", po::value<std::string>(), "Record a bag of maximum duration in seconds, unless 'm', or 'h' is appended.")
00066       ("node", po::value<std::string>(), "Record all topics subscribed to by a specific node.");
00067 
00068   
00069     po::positional_options_description p;
00070     p.add("topic", -1);
00071     
00072     po::variables_map vm;
00073     
00074     try 
00075     {
00076       po::store(po::command_line_parser(argc, argv).options(desc).positional(p).run(), vm);
00077     } catch (boost::program_options::invalid_command_line_syntax& e)
00078     {
00079       throw ros::Exception(e.what());
00080     }  catch (boost::program_options::unknown_option& e)
00081     {
00082       throw ros::Exception(e.what());
00083     }
00084 
00085     if (vm.count("help")) {
00086       std::cout << desc << std::endl;
00087       exit(0);
00088     }
00089 
00090     if (vm.count("all"))
00091       opts.record_all = true;
00092     if (vm.count("regex"))
00093       opts.regex = true;
00094     if (vm.count("exclude"))
00095     {
00096       opts.do_exclude = true;
00097       opts.exclude_regex = vm["exclude"].as<std::string>();
00098     }
00099     if (vm.count("quiet"))
00100       opts.quiet = true;
00101     if (vm.count("output-prefix"))
00102     {
00103       opts.prefix = vm["output-prefix"].as<std::string>();
00104       opts.append_date = true;
00105     }
00106     if (vm.count("output-name"))
00107     {
00108       opts.prefix = vm["output-name"].as<std::string>();
00109       opts.append_date = false;
00110     }
00111     if (vm.count("split"))
00112     {
00113       opts.split = true;
00114 
00115       int S = vm["split"].as<int>();
00116       if (S != 0)
00117       {
00118         ROS_WARN("Use of \"--split <MAX_SIZE>\" has been deprecated.  Please use --split --size <MAX_SIZE> or --split --duration <MAX_DURATION>");
00119         if (S < 0)
00120           throw ros::Exception("Split size must be 0 or positive");
00121         opts.max_size = 1048576 * S;
00122       }
00123     }
00124     if (vm.count("buffsize"))
00125     {
00126       int m = vm["buffsize"].as<int>();
00127       if (m < 0)
00128         throw ros::Exception("Buffer size must be 0 or positive");
00129       opts.buffer_size = 1048576 * m;
00130     }
00131     if (vm.count("chunksize"))
00132     {
00133       int chnk_sz = vm["chunksize"].as<int>();
00134       if (chnk_sz < 0)
00135         throw ros::Exception("Chunk size must be 0 or positive");
00136       opts.chunk_size = 1024 * chnk_sz;
00137     }
00138     if (vm.count("limit"))
00139     {
00140       opts.limit = vm["limit"].as<int>();
00141     }
00142     if (vm.count("bz2"))
00143     {
00144       opts.compression = rosbag::compression::BZ2;
00145     }
00146     if (vm.count("duration"))
00147     {
00148       std::string duration_str = vm["duration"].as<std::string>();
00149 
00150       double duration;
00151       double multiplier = 1.0;
00152       std::string unit("");
00153 
00154       std::istringstream iss(duration_str);
00155       if ((iss >> duration).fail())
00156         throw ros::Exception("Duration must start with a floating point number.");
00157 
00158       if ( (!iss.eof() && ((iss >> unit).fail())) )
00159       {
00160         throw ros::Exception("Duration unit must be s, m, or h");
00161       }
00162       if (unit == std::string(""))
00163         multiplier = 1.0;
00164       else if (unit == std::string("s"))
00165         multiplier = 1.0;
00166       else if (unit == std::string("m"))
00167         multiplier = 60.0;
00168       else if (unit == std::string("h"))
00169         multiplier = 3600.0;
00170       else
00171         throw ros::Exception("Duration unit must be s, m, or h");
00172 
00173       
00174       opts.max_duration = ros::Duration(duration * multiplier);
00175       if (opts.max_duration <= ros::Duration(0))
00176         throw ros::Exception("Duration must be positive.");
00177     }
00178     if (vm.count("size"))
00179     {
00180       opts.max_size = vm["size"].as<int>() * 1048576;
00181       if (opts.max_size <= 0)
00182         throw ros::Exception("Split size must be 0 or positive");
00183     }
00184     if (vm.count("node"))
00185     {
00186       opts.node = vm["node"].as<std::string>();
00187       std::cout << "Recording from: " << opts.node << std::endl;
00188     }
00189 
00190     // Every non-option argument is assumed to be a topic
00191     if (vm.count("topic"))
00192     {
00193       std::vector<std::string> bags = vm["topic"].as< std::vector<std::string> >();
00194       for (std::vector<std::string>::iterator i = bags.begin();
00195            i != bags.end();
00196            i++)
00197         opts.topics.push_back(*i);
00198     }
00199 
00200 
00201     // check that argument combinations make sense
00202     if(opts.exclude_regex.size() > 0 &&
00203             !(opts.record_all || opts.regex)) {
00204         fprintf(stderr, "Warning: Exclusion regex given, but no topics to subscribe to.\n"
00205                 "Adding implicit 'record all'.");
00206         opts.record_all = true;
00207     }
00208 
00209     return opts;
00210 }
00211 
00212 int main(int argc, char** argv) {
00213     ros::init(argc, argv, "record", ros::init_options::AnonymousName);
00214 
00215     // Parse the command-line options
00216     rosbag::RecorderOptions opts;
00217     try {
00218         opts = parseOptions(argc, argv);
00219     }
00220     catch (ros::Exception const& ex) {
00221         ROS_ERROR("Error reading options: %s", ex.what());
00222         return 1;
00223     }
00224     catch(boost::regex_error const& ex) {
00225         ROS_ERROR("Error reading options: %s\n", ex.what());
00226         return 1;
00227     }
00228 
00229     // Run the recorder
00230     rosbag::Recorder recorder(opts);
00231     int result = recorder.run();
00232     
00233     return result;
00234 }


rosbag
Author(s): Tim Field, Jeremy Leibs, James Bowman
autogenerated on Mon Oct 6 2014 11:47:09