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


rosbag
Author(s): Tim Field (tfield@willowgarage.com), Jeremy Leibs (leibs@willowgarage.com), and James Bowman (jamesb@willowgarage.com)
autogenerated on Sat Dec 28 2013 17:43:05