play.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage, Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 ********************************************************************/
34 
35 #include "rosbag/player.h"
36 #include "boost/program_options.hpp"
37 
38 namespace po = boost::program_options;
39 
40 rosbag::PlayerOptions parseOptions(int argc, char** argv) {
42 
43  po::options_description desc("Allowed options");
44 
45  desc.add_options()
46  ("help,h", "produce help message")
47  ("prefix,p", po::value<std::string>()->default_value(""), "prefixes all output topics in replay")
48  ("quiet,q", "suppress console output")
49  ("immediate,i", "play back all messages without waiting")
50  ("pause", "start in paused mode")
51  ("queue", po::value<int>()->default_value(100), "use an outgoing queue of size SIZE")
52  ("clock", "publish the clock time")
53  ("hz", po::value<float>()->default_value(100.0f), "use a frequency of HZ when publishing clock time")
54  ("delay,d", po::value<float>()->default_value(0.2f), "sleep SEC seconds after every advertise call (to allow subscribers to connect)")
55  ("rate,r", po::value<float>()->default_value(1.0f), "multiply the publish rate by FACTOR")
56  ("start,s", po::value<float>()->default_value(0.0f), "start SEC seconds into the bag files")
57  ("duration,u", po::value<float>(), "play only SEC seconds from the bag files")
58  ("skip-empty", po::value<float>(), "skip regions in the bag with no messages for more than SEC seconds")
59  ("loop,l", "loop playback")
60  ("keep-alive,k", "keep alive past end of bag (useful for publishing latched topics)")
61  ("try-future-version", "still try to open a bag file, even if the version is not known to the player")
62  ("topics", po::value< std::vector<std::string> >()->multitoken(), "topics to play back")
63  ("pause-topics", po::value< std::vector<std::string> >()->multitoken(), "topics to pause playback on")
64  ("bags", po::value< std::vector<std::string> >(), "bag files to play back from")
65  ("wait-for-subscribers", "wait for at least one subscriber on each topic before publishing")
66  ("rate-control-topic", po::value<std::string>(), "watch the given topic, and if the last publish was more than <rate-control-max-delay> ago, wait until the topic publishes again to continue playback")
67  ("rate-control-max-delay", po::value<float>()->default_value(1.0f), "maximum time difference from <rate-control-topic> before pausing")
68  ;
69 
70  po::positional_options_description p;
71  p.add("bags", -1);
72 
73  po::variables_map vm;
74 
75  try
76  {
77  po::store(po::command_line_parser(argc, argv).options(desc).positional(p).run(), vm);
78  } catch (const boost::program_options::invalid_command_line_syntax& e)
79  {
80  throw ros::Exception(e.what());
81  } catch (const boost::program_options::unknown_option& e)
82  {
83  throw ros::Exception(e.what());
84  }
85 
86  if (vm.count("help")) {
87  std::cout << desc << std::endl;
88  exit(0);
89  }
90 
91  if (vm.count("prefix"))
92  opts.prefix = vm["prefix"].as<std::string>();
93  if (vm.count("quiet"))
94  opts.quiet = true;
95  if (vm.count("immediate"))
96  opts.at_once = true;
97  if (vm.count("pause"))
98  opts.start_paused = true;
99  if (vm.count("queue"))
100  opts.queue_size = vm["queue"].as<int>();
101  if (vm.count("hz"))
102  opts.bag_time_frequency = vm["hz"].as<float>();
103  if (vm.count("clock"))
104  opts.bag_time = true;
105  if (vm.count("delay"))
106  opts.advertise_sleep = ros::WallDuration(vm["delay"].as<float>());
107  if (vm.count("rate"))
108  opts.time_scale = vm["rate"].as<float>();
109  if (vm.count("start"))
110  {
111  opts.time = vm["start"].as<float>();
112  opts.has_time = true;
113  }
114  if (vm.count("duration"))
115  {
116  opts.duration = vm["duration"].as<float>();
117  opts.has_duration = true;
118  }
119  if (vm.count("skip-empty"))
120  opts.skip_empty = ros::Duration(vm["skip-empty"].as<float>());
121  if (vm.count("loop"))
122  opts.loop = true;
123  if (vm.count("keep-alive"))
124  opts.keep_alive = true;
125  if (vm.count("wait-for-subscribers"))
126  opts.wait_for_subscribers = true;
127 
128  if (vm.count("topics"))
129  {
130  std::vector<std::string> topics = vm["topics"].as< std::vector<std::string> >();
131  for (std::vector<std::string>::iterator i = topics.begin();
132  i != topics.end();
133  i++)
134  opts.topics.push_back(*i);
135  }
136 
137  if (vm.count("pause-topics"))
138  {
139  std::vector<std::string> pause_topics = vm["pause-topics"].as< std::vector<std::string> >();
140  for (std::vector<std::string>::iterator i = pause_topics.begin();
141  i != pause_topics.end();
142  i++)
143  opts.pause_topics.push_back(*i);
144  }
145 
146  if (vm.count("rate-control-topic"))
147  opts.rate_control_topic = vm["rate-control-topic"].as<std::string>();
148 
149  if (vm.count("rate-control-max-delay"))
150  opts.rate_control_max_delay = vm["rate-control-max-delay"].as<float>();
151 
152  if (vm.count("bags"))
153  {
154  std::vector<std::string> bags = vm["bags"].as< std::vector<std::string> >();
155  for (std::vector<std::string>::iterator i = bags.begin();
156  i != bags.end();
157  i++)
158  opts.bags.push_back(*i);
159  } else {
160  if (vm.count("topics") || vm.count("pause-topics"))
161  throw ros::Exception("When using --topics or --pause-topics, --bags "
162  "should be specified to list bags.");
163  throw ros::Exception("You must specify at least one bag to play back.");
164  }
165 
166  return opts;
167 }
168 
169 int main(int argc, char** argv) {
170  ros::init(argc, argv, "play", ros::init_options::AnonymousName);
171 
172  // Parse the command-line options
174  try {
175  opts = parseOptions(argc, argv);
176  }
177  catch (const ros::Exception& ex) {
178  ROS_ERROR("Error reading options: %s", ex.what());
179  return 1;
180  }
181 
182  rosbag::Player player(opts);
183 
184  try {
185  player.publish();
186  }
187  catch (const std::runtime_error& e) {
188  ROS_FATAL("%s", e.what());
189  return 1;
190  }
191 
192  return 0;
193 }
void publish()
Definition: player.cpp:131
int main(int argc, char **argv)
Definition: play.cpp:169
#define ROS_FATAL(...)
bool wait_for_subscribers
Definition: player.h:96
std::string rate_control_topic
Definition: player.h:97
void run(class_loader::ClassLoader *loader)
f
std::vector< std::string > topics
Definition: player.h:102
std::vector< std::string > pause_topics
Definition: player.h:103
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string prefix
Definition: player.h:80
std::vector< std::string > bags
Definition: player.h:101
def default_value(type_)
float rate_control_max_delay
Definition: player.h:98
ros::WallDuration advertise_sleep
Definition: player.h:88
double bag_time_frequency
Definition: player.h:85
PRIVATE. Player class to abstract the interface to the player.
Definition: player.h:169
rosbag::PlayerOptions parseOptions(int argc, char **argv)
Definition: play.cpp:40
ros::Duration skip_empty
Definition: player.h:99
#define ROS_ERROR(...)


rosbag
Author(s): Tim Field, Jeremy Leibs, James Bowman, Dirk Thomas
autogenerated on Mon Feb 28 2022 23:34:21