38 #include <boost/program_options.hpp>
43 namespace po = boost::program_options;
58 int cleaned_argc = cleaned_args.size();
59 char const* cleaned_argv[cleaned_argc];
60 for (
int i = 0; i < cleaned_argc; ++i)
61 cleaned_argv[i] = cleaned_args[i].c_str();
63 po::options_description desc(
"Options");
66 (
"help,h",
"produce help message")
67 (
"trigger-write,t",
"Write buffer of selected topcis to a bag file")
68 (
"pause,p",
"Stop buffering new messages until resumed or write is triggered")
69 (
"resume,r",
"Resume buffering new messages, writing over older messages as needed")
70 (
"all,a",
"Record all topics")
71 (
"no-clear,n",
"Flag to explicitly NOT clear the buffer after writing to a bag.")
72 (
"size,s", po::value<double>()->default_value(-1),
73 "Maximum memory per topic to use in buffering in MB. Default: no limit")
74 (
"count,c", po::value<int32_t>()->default_value(-1),
75 "Maximum number of messages per topic to use when buffering. Default: no limit")
76 (
"duration,d", po::value<double>()->default_value(30.0),
77 "Maximum difference between newest and oldest buffered message per topic in seconds. Default: 30")
78 (
"output-prefix,o", po::value<std::string>()->default_value(
""),
79 "When in trigger write mode, prepend PREFIX to name of writting bag file")
80 (
"output-filename,O", po::value<std::string>(),
"When in trigger write mode, exact name of written bag file")
81 (
"topic", po::value<std::vector<std::string> >(),
82 "Topic to buffer. If triggering write, write only these topics instead of all buffered topics.")
83 (
"compression,c", po::value<std::string>()->default_value(
"uncompressed"),
84 "Bag compression type. Default: uncompressed. Other options are: BZ2, LZ4.")
85 (
"queue-size", po::value<int32_t>()->default_value(10),
86 "Queue size when subscribing to topics. Default: 10");
88 po::positional_options_description p;
93 po::store(po::command_line_parser(cleaned_argc, cleaned_argv).options(desc).positional(p).
run(), vm);
96 catch (boost::program_options::error
const& e)
98 std::cout <<
"rosbag_snapshot: " << e.what() << std::endl;
102 if (vm.count(
"help"))
104 std::cout <<
"Usage: rosrun rosbag_snapshot snapshot [options] [topic1 topic2 ...]" << std::endl
106 <<
"Buffer recent messages until triggered to write or trigger an already running instance." << std::endl
108 std::cout << desc << std::endl;
116 if (vm.count(
"topic"))
118 std::vector<std::string> topics = vm[
"topic"].as<std::vector<std::string> >();
119 for (
const std::string& str : topics)
127 if (vm.count(
"no-clear"))
133 opts.
compression_ = vm[
"compression"].as<std::string>();
134 if (vm.count(
"queue-size"))
147 if (vm.count(
"pause"))
148 opts.
action_ = SnapshotterClientOptions::PAUSE;
149 else if (vm.count(
"resume"))
150 opts.
action_ = SnapshotterClientOptions::RESUME;
151 else if (vm.count(
"trigger-write"))
153 opts.
action_ = SnapshotterClientOptions::TRIGGER_WRITE;
154 if (vm.count(
"topic"))
155 opts.
topics_ = vm[
"topic"].as<std::vector<std::string> >();
156 if (vm.count(
"output-prefix"))
157 opts.
prefix_ = vm[
"output-prefix"].as<std::string>();
158 if (vm.count(
"output-filename"))
159 opts.
filename_ = vm[
"output-filename"].as<std::string>();
175 int32_t default_count;
177 if (nh.
getParam(
"default_memory_limit", tmp))
179 if (nh.
getParam(
"default_duration_limit", tmp))
181 if (nh.
getParam(
"default_count_limit", default_count))
183 if (nh.
getParam(
"clear_buffer", clear_buffer))
188 const std::string default_compression{
"uncompressed"};
197 ROS_ASSERT_MSG(topics.getType() == XmlRpcValue::TypeArray,
"topics param must be an array");
199 size_t size = topics.size();
200 for (
size_t i = 0; i < size; ++i)
202 XmlRpcValue topic_value = topics[i];
204 if (topic_value.getType() == XmlRpcValue::TypeString)
208 else if (topic_value.getType() == XmlRpcValue::TypeStruct)
210 ROS_ASSERT_MSG(topic_value.size() == 1,
"Paramater invalid for topic %lu", i);
211 std::string
const& topic = (*topic_value.begin()).first;
212 XmlRpcValue& topic_config = (*topic_value.begin()).second;
213 ROS_ASSERT_MSG(topic_config.getType() == XmlRpcValue::TypeStruct,
"Topic limits invalid for: '%s'",
216 ros::Duration dur = SnapshotterTopicOptions::INHERIT_DURATION_LIMIT;
217 int64_t mem = SnapshotterTopicOptions::INHERIT_MEMORY_LIMIT;
218 int32_t cnt = SnapshotterTopicOptions::INHERIT_COUNT_LIMIT;
219 std::string duration =
"duration";
220 std::string memory =
"memory";
221 std::string count =
"count";
222 if (topic_config.hasMember(duration))
224 XmlRpcValue& dur_limit = topic_config[duration];
225 if (dur_limit.getType() == XmlRpcValue::TypeDouble)
227 double seconds = dur_limit;
230 else if (dur_limit.getType() == XmlRpcValue::TypeInt)
232 int seconds = dur_limit;
238 if (topic_config.hasMember(
"memory"))
240 XmlRpcValue& mem_limit = topic_config[memory];
241 if (mem_limit.getType() == XmlRpcValue::TypeDouble)
243 double mb = mem_limit;
246 else if (mem_limit.getType() == XmlRpcValue::TypeInt)
254 if (topic_config.hasMember(
"count"))
256 XmlRpcValue& cnt_limit = topic_config[count];
257 if (cnt_limit.getType() == XmlRpcValue::TypeInt)
264 opts.
addTopic(topic, dur, mem, cnt);
271 int main(
int argc,
char** argv)
273 po::variables_map vm;
278 if (vm.count(
"trigger-write") || vm.count(
"pause") || vm.count(
"resume"))
285 return client.
run(opts);
301 ROS_FATAL(
"No topics selected. Exiting.");
307 return snapshotter.
run();