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 (
"size,s", po::value<double>()->default_value(-1),
72 "Maximum memory per topic to use in buffering in MB. Default: no limit")
73 (
"count,c", po::value<int32_t>()->default_value(-1),
74 "Maximum number of messages per topic to use when buffering. Default: no limit")
75 (
"duration,d", po::value<double>()->default_value(30.0),
76 "Maximum difference between newest and oldest buffered message per topic in seconds. Default: 30")
77 (
"output-prefix,o", po::value<std::string>()->default_value(
""),
78 "When in trigger write mode, prepend PREFIX to name of writting bag file")
79 (
"output-filename,O", po::value<std::string>(),
"When in trigger write mode, exact name of written bag file")
80 (
"topic", po::value<std::vector<std::string> >(),
81 "Topic to buffer. If triggering write, write only these topics instead of all buffered topics.")
82 (
"compression,c", po::value<std::string>()->default_value(
"uncompressed"),
83 "Bag compression type. Default: uncompressed. Other options are: BZ2, LZ4.");
85 po::positional_options_description p;
90 po::store(po::command_line_parser(cleaned_argc, cleaned_argv).options(desc).positional(p).
run(), vm);
93 catch (boost::program_options::error
const& e)
95 std::cout <<
"rosbag_snapshot: " << e.what() << std::endl;
101 std::cout <<
"Usage: rosrun rosbag_snapshot snapshot [options] [topic1 topic2 ...]" << std::endl
103 <<
"Buffer recent messages until triggered to write or trigger an already running instance." << std::endl
105 std::cout << desc << std::endl;
113 if (vm.count(
"topic"))
115 std::vector<std::string> topics = vm[
"topic"].as<std::vector<std::string> >();
116 for (
const std::string& str : topics)
125 opts.
compression_ = vm[
"compression"].as<std::string>();
131 if (vm.count(
"pause"))
132 opts.
action_ = SnapshotterClientOptions::PAUSE;
133 else if (vm.count(
"resume"))
134 opts.
action_ = SnapshotterClientOptions::RESUME;
135 else if (vm.count(
"trigger-write"))
137 opts.
action_ = SnapshotterClientOptions::TRIGGER_WRITE;
138 if (vm.count(
"topic"))
139 opts.
topics_ = vm[
"topic"].as<std::vector<std::string> >();
140 if (vm.count(
"output-prefix"))
141 opts.
prefix_ = vm[
"output-prefix"].as<std::string>();
142 if (vm.count(
"output-filename"))
143 opts.
filename_ = vm[
"output-filename"].as<std::string>();
159 int32_t default_count;
160 if (nh.
getParam(
"default_memory_limit", tmp))
162 if (nh.
getParam(
"default_duration_limit", tmp))
164 if (nh.
getParam(
"default_count_limit", default_count))
169 const std::string default_compression{
"uncompressed"};
176 ROS_ASSERT_MSG(topics.getType() == XmlRpcValue::TypeArray,
"topics param must be an array");
178 size_t size = topics.size();
179 for (
size_t i = 0; i < size; ++i)
181 XmlRpcValue topic_value = topics[i];
183 if (topic_value.getType() == XmlRpcValue::TypeString)
187 else if (topic_value.getType() == XmlRpcValue::TypeStruct)
189 ROS_ASSERT_MSG(topic_value.size() == 1,
"Paramater invalid for topic %lu", i);
190 std::string
const& topic = (*topic_value.begin()).first;
191 XmlRpcValue& topic_config = (*topic_value.begin()).second;
192 ROS_ASSERT_MSG(topic_config.getType() == XmlRpcValue::TypeStruct,
"Topic limits invalid for: '%s'",
195 ros::Duration dur = SnapshotterTopicOptions::INHERIT_DURATION_LIMIT;
196 int64_t mem = SnapshotterTopicOptions::INHERIT_MEMORY_LIMIT;
197 int32_t cnt = SnapshotterTopicOptions::INHERIT_COUNT_LIMIT;
198 std::string duration =
"duration";
199 std::string memory =
"memory";
200 std::string count =
"count";
201 if (topic_config.hasMember(duration))
203 XmlRpcValue& dur_limit = topic_config[duration];
204 if (dur_limit.getType() == XmlRpcValue::TypeDouble)
206 double seconds = dur_limit;
209 else if (dur_limit.getType() == XmlRpcValue::TypeInt)
211 int seconds = dur_limit;
217 if (topic_config.hasMember(
"memory"))
219 XmlRpcValue& mem_limit = topic_config[memory];
220 if (mem_limit.getType() == XmlRpcValue::TypeDouble)
222 double mb = mem_limit;
225 else if (mem_limit.getType() == XmlRpcValue::TypeInt)
233 if (topic_config.hasMember(
"count"))
235 XmlRpcValue& cnt_limit = topic_config[count];
236 if (cnt_limit.getType() == XmlRpcValue::TypeInt)
243 opts.
addTopic(topic, dur, mem, cnt);
250 int main(
int argc,
char** argv)
252 po::variables_map vm;
257 if (vm.count(
"trigger-write") || vm.count(
"pause") || vm.count(
"resume"))
264 return client.
run(opts);
280 ROS_FATAL(
"No topics selected. Exiting.");
286 return snapshotter.
run();
int32_t default_memory_limit_
void run(class_loader::ClassLoader *loader)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void appendParamOptions(ros::NodeHandle &nh, SnapshotterOptions &opts)
bool parseVariablesMapClient(SnapshotterClientOptions &opts, po::variables_map const &vm)
bool parseOptions(po::variables_map &vm, int argc, char **argv)
int main(int argc, char **argv)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::vector< std::string > V_string
std::vector< std::string > topics_
bool getParam(const std::string &key, std::string &s) const
#define ROS_ASSERT_MSG(cond,...)
ros::Duration default_duration_limit_
bool parseVariablesMap(SnapshotterOptions &opts, po::variables_map const &vm)
int32_t default_count_limit_
ROSCPP_DECL void removeROSArgs(int argc, const char *const *argv, V_string &args_out)
class ROSBAG_DECL Snapshotter
int run(SnapshotterClientOptions const &opts)
bool addTopic(std::string const &topic, ros::Duration duration_limit=SnapshotterTopicOptions::INHERIT_DURATION_LIMIT, int32_t memory_limit=SnapshotterTopicOptions::INHERIT_MEMORY_LIMIT, int32_t count_limit=SnapshotterTopicOptions::INHERIT_COUNT_LIMIT)