$search
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/player.h" 00036 #include "boost/program_options.hpp" 00037 00038 namespace po = boost::program_options; 00039 00040 rosbag::PlayerOptions parseOptions(int argc, char** argv) { 00041 rosbag::PlayerOptions opts; 00042 00043 po::options_description desc("Allowed options"); 00044 00045 desc.add_options() 00046 ("help,h", "produce help message") 00047 ("quiet,q", "suppress console output") 00048 ("immediate,i", "play back all messages without waiting") 00049 ("pause", "start in paused mode") 00050 ("queue", po::value<int>()->default_value(100), "use an outgoing queue of size SIZE") 00051 ("clock", "publish the clock time") 00052 ("hz", po::value<float>()->default_value(100.0), "use a frequency of HZ when publishing clock time") 00053 ("delay,d", po::value<float>()->default_value(0.2), "sleep SEC seconds after every advertise call") 00054 ("rate,r", po::value<float>()->default_value(1.0), "multiply the publish rate by FACTOR") 00055 ("start,s", po::value<float>()->default_value(0.0), "start SEC seconds into the bag files") 00056 ("loop,l", "loop playback") 00057 ("keep-alive,k", "keep alive past end of bag") 00058 ("try-future-version", "still try to open a bag file, even if the version is not known to the player") 00059 ("skip-empty", po::value<float>(), "skip regions in the bag with no messages for more than SEC seconds") 00060 ("topics", po::value< std::vector<std::string> >()->multitoken(), "topics to play back") 00061 ("bags", po::value< std::vector<std::string> >(), "bag files to play back from"); 00062 00063 po::positional_options_description p; 00064 p.add("bags", -1); 00065 00066 po::variables_map vm; 00067 00068 try 00069 { 00070 po::store(po::command_line_parser(argc, argv).options(desc).positional(p).run(), vm); 00071 } catch (boost::program_options::invalid_command_line_syntax& e) 00072 { 00073 throw ros::Exception(e.what()); 00074 } catch (boost::program_options::unknown_option& e) 00075 { 00076 throw ros::Exception(e.what()); 00077 } 00078 00079 if (vm.count("help")) { 00080 std::cout << desc << std::endl; 00081 exit(0); 00082 } 00083 00084 if (vm.count("quiet")) 00085 opts.quiet = true; 00086 if (vm.count("immediate")) 00087 opts.at_once = true; 00088 if (vm.count("pause")) 00089 opts.start_paused = true; 00090 if (vm.count("queue")) 00091 opts.queue_size = vm["queue"].as<int>(); 00092 if (vm.count("hz")) 00093 opts.bag_time_frequency = vm["hz"].as<float>(); 00094 if (vm.count("clock")) 00095 opts.bag_time = true; 00096 if (vm.count("delay")) 00097 opts.advertise_sleep = ros::WallDuration(vm["delay"].as<float>()); 00098 if (vm.count("rate")) 00099 opts.time_scale = vm["rate"].as<float>(); 00100 if (vm.count("start")) 00101 { 00102 opts.time = vm["start"].as<float>(); 00103 opts.has_time = true; 00104 } 00105 if (vm.count("skip-empty")) 00106 opts.skip_empty = ros::Duration(vm["skip-empty"].as<float>()); 00107 if (vm.count("loop")) 00108 opts.loop = true; 00109 if (vm.count("keep-alive")) 00110 opts.keep_alive = true; 00111 00112 if (vm.count("topics")) 00113 { 00114 std::vector<std::string> topics = vm["topics"].as< std::vector<std::string> >(); 00115 for (std::vector<std::string>::iterator i = topics.begin(); 00116 i != topics.end(); 00117 i++) 00118 opts.topics.push_back(*i); 00119 } 00120 00121 if (vm.count("bags")) 00122 { 00123 std::vector<std::string> bags = vm["bags"].as< std::vector<std::string> >(); 00124 for (std::vector<std::string>::iterator i = bags.begin(); 00125 i != bags.end(); 00126 i++) 00127 opts.bags.push_back(*i); 00128 } else { 00129 if (vm.count("topics")) 00130 throw ros::Exception("When using --topics, --bags should be specified to list bags."); 00131 throw ros::Exception("You must specify at least one bag to play back."); 00132 } 00133 00134 return opts; 00135 } 00136 00137 int main(int argc, char** argv) { 00138 ros::init(argc, argv, "play", ros::init_options::AnonymousName); 00139 00140 // Parse the command-line options 00141 rosbag::PlayerOptions opts; 00142 try { 00143 opts = parseOptions(argc, argv); 00144 } 00145 catch (ros::Exception const& ex) { 00146 ROS_ERROR("Error reading options: %s", ex.what()); 00147 return 1; 00148 } 00149 00150 rosbag::Player player(opts); 00151 00152 try { 00153 player.publish(); 00154 } 00155 catch (std::runtime_error& e) { 00156 ROS_FATAL("%s", e.what()); 00157 return 1; 00158 } 00159 00160 return 0; 00161 }