36 #include "boost/program_options.hpp" 38 namespace po = boost::program_options;
43 po::options_description desc(
"Allowed 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.0
f),
"use a frequency of HZ when publishing clock time")
54 (
"delay,d", po::value<float>()->default_value(0.2
f),
"sleep SEC seconds after every advertise call (to allow subscribers to connect)")
55 (
"rate,r", po::value<float>()->default_value(1.0
f),
"multiply the publish rate by FACTOR")
56 (
"start,s", po::value<float>()->default_value(0.0
f),
"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.0
f),
"maximum time difference from <rate-control-topic> before pausing")
70 po::positional_options_description p;
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)
81 }
catch (
const boost::program_options::unknown_option& e)
86 if (vm.count(
"help")) {
87 std::cout << desc << std::endl;
91 if (vm.count(
"prefix"))
92 opts.
prefix = vm[
"prefix"].as<std::string>();
93 if (vm.count(
"quiet"))
95 if (vm.count(
"immediate"))
97 if (vm.count(
"pause"))
99 if (vm.count(
"queue"))
103 if (vm.count(
"clock"))
105 if (vm.count(
"delay"))
107 if (vm.count(
"rate"))
109 if (vm.count(
"start"))
111 opts.
time = vm[
"start"].as<
float>();
114 if (vm.count(
"duration"))
116 opts.
duration = vm[
"duration"].as<
float>();
119 if (vm.count(
"skip-empty"))
121 if (vm.count(
"loop"))
123 if (vm.count(
"keep-alive"))
125 if (vm.count(
"wait-for-subscribers"))
128 if (vm.count(
"topics"))
130 std::vector<std::string> topics = vm[
"topics"].as< std::vector<std::string> >();
131 for (std::vector<std::string>::iterator i = topics.begin();
134 opts.
topics.push_back(*i);
137 if (vm.count(
"pause-topics"))
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();
146 if (vm.count(
"rate-control-topic"))
149 if (vm.count(
"rate-control-max-delay"))
152 if (vm.count(
"bags"))
154 std::vector<std::string> bags = vm[
"bags"].as< std::vector<std::string> >();
155 for (std::vector<std::string>::iterator i = bags.begin();
158 opts.
bags.push_back(*i);
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.");
169 int main(
int argc,
char** argv) {
178 ROS_ERROR(
"Error reading options: %s", ex.what());
187 catch (
const std::runtime_error& e) {
int main(int argc, char **argv)
bool wait_for_subscribers
std::string rate_control_topic
void run(class_loader::ClassLoader *loader)
std::vector< std::string > topics
std::vector< std::string > pause_topics
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< std::string > bags
float rate_control_max_delay
ros::WallDuration advertise_sleep
double bag_time_frequency
PRIVATE. Player class to abstract the interface to the player.
rosbag::PlayerOptions parseOptions(int argc, char **argv)