snapshot.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2018, Open Source Robotics Foundation, 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 Open Source Robotics Foundation, Inc. nor the
18 * names of its contributors may be used to endorse or promote products
19 * derived 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 
36 #include <rosbag/exceptions.h>
37 
38 #include <boost/program_options.hpp>
39 #include <string>
40 #include <sstream>
41 #include <vector>
42 
43 namespace po = boost::program_options;
44 
50 
51 const int MB_TO_BYTES = 1E6;
52 
53 bool parseOptions(po::variables_map& vm, int argc, char** argv)
54 {
55  // Strip ros arguments and reassemble
56  ros::V_string cleaned_args;
57  ros::removeROSArgs(argc, argv, cleaned_args);
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();
62 
63  po::options_description desc("Options");
64  // clang-format off
65  desc.add_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.");
84  // clang-format on
85  po::positional_options_description p;
86  p.add("topic", -1);
87 
88  try
89  {
90  po::store(po::command_line_parser(cleaned_argc, cleaned_argv).options(desc).positional(p).run(), vm);
91  po::notify(vm);
92  }
93  catch (boost::program_options::error const& e)
94  {
95  std::cout << "rosbag_snapshot: " << e.what() << std::endl;
96  return false;
97  }
98 
99  if (vm.count("help"))
100  {
101  std::cout << "Usage: rosrun rosbag_snapshot snapshot [options] [topic1 topic2 ...]" << std::endl
102  << std::endl
103  << "Buffer recent messages until triggered to write or trigger an already running instance." << std::endl
104  << std::endl;
105  std::cout << desc << std::endl;
106  return false;
107  }
108  return true;
109 }
110 
111 bool parseVariablesMap(SnapshotterOptions& opts, po::variables_map const& vm)
112 {
113  if (vm.count("topic"))
114  {
115  std::vector<std::string> topics = vm["topic"].as<std::vector<std::string> >();
116  for (const std::string& str : topics)
117  {
118  opts.addTopic(str);
119  }
120  }
121  opts.default_memory_limit_ = static_cast<int>(MB_TO_BYTES * vm["size"].as<double>());
122  opts.default_duration_limit_ = ros::Duration(vm["duration"].as<double>());
123  opts.default_count_limit_ = vm["count"].as<int32_t>();
124  opts.all_topics_ = vm.count("all");
125  opts.compression_ = vm["compression"].as<std::string>();
126  return true;
127 }
128 
129 bool parseVariablesMapClient(SnapshotterClientOptions& opts, po::variables_map const& vm)
130 {
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"))
136  {
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>();
144  }
145  return true;
146 }
147 
148 /* Read configured topics and limits from ROS params
149  * TODO: use exceptions instead of asserts to follow style conventions
150  * See snapshot.test for an example
151  */
153 {
154  using XmlRpc::XmlRpcValue;
155  XmlRpcValue topics;
156 
157  // Override program options for default limits if the parameters are set.
158  double tmp;
159  int32_t default_count;
160  if (nh.getParam("default_memory_limit", tmp))
161  opts.default_memory_limit_ = static_cast<int>(MB_TO_BYTES * tmp);
162  if (nh.getParam("default_duration_limit", tmp))
164  if (nh.getParam("default_count_limit", default_count))
165  opts.default_count_limit_ = default_count;
166  nh.param("record_all_topics", opts.all_topics_, opts.all_topics_);
167 
168  // Set compression type
169  const std::string default_compression{"uncompressed"};
170  nh.param("compression", opts.compression_, default_compression);
171 
172  if (!nh.getParam("topics", topics))
173  {
174  return;
175  }
176  ROS_ASSERT_MSG(topics.getType() == XmlRpcValue::TypeArray, "topics param must be an array");
177  // Iterator caused exception, hmmm...
178  size_t size = topics.size();
179  for (size_t i = 0; i < size; ++i)
180  {
181  XmlRpcValue topic_value = topics[i];
182  // If it is just a string, add this topic
183  if (topic_value.getType() == XmlRpcValue::TypeString)
184  {
185  opts.addTopic(topic_value);
186  }
187  else if (topic_value.getType() == XmlRpcValue::TypeStruct)
188  {
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'",
193  topic.c_str());
194 
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))
202  {
203  XmlRpcValue& dur_limit = topic_config[duration];
204  if (dur_limit.getType() == XmlRpcValue::TypeDouble)
205  {
206  double seconds = dur_limit;
207  dur = ros::Duration(seconds);
208  }
209  else if (dur_limit.getType() == XmlRpcValue::TypeInt)
210  {
211  int seconds = dur_limit;
212  dur = ros::Duration(seconds, 0);
213  }
214  else
215  ROS_FATAL("err");
216  }
217  if (topic_config.hasMember("memory"))
218  {
219  XmlRpcValue& mem_limit = topic_config[memory];
220  if (mem_limit.getType() == XmlRpcValue::TypeDouble)
221  {
222  double mb = mem_limit;
223  mem = static_cast<int>(MB_TO_BYTES * mb);
224  }
225  else if (mem_limit.getType() == XmlRpcValue::TypeInt)
226  {
227  int mb = mem_limit;
228  mem = MB_TO_BYTES * mb;
229  }
230  else
231  ROS_FATAL("err");
232  }
233  if (topic_config.hasMember("count"))
234  {
235  XmlRpcValue& cnt_limit = topic_config[count];
236  if (cnt_limit.getType() == XmlRpcValue::TypeInt)
237  {
238  cnt = cnt_limit;
239  }
240  else
241  ROS_FATAL("err");
242  }
243  opts.addTopic(topic, dur, mem, cnt);
244  }
245  else
246  ROS_ASSERT_MSG(false, "Parameter invalid for topic %lu", i);
247  }
248 }
249 
250 int main(int argc, char** argv)
251 {
252  po::variables_map vm;
253  if (!parseOptions(vm, argc, argv))
254  return 1;
255 
256  // If any of the client flags are on, use the client
257  if (vm.count("trigger-write") || vm.count("pause") || vm.count("resume"))
258  {
260  if (!parseVariablesMapClient(opts, vm))
261  return 1;
262  ros::init(argc, argv, "snapshot_client", ros::init_options::AnonymousName);
263  SnapshotterClient client;
264  return client.run(opts);
265  }
266 
267  // Parse the command-line options
268  SnapshotterOptions opts;
269  if (!parseVariablesMap(opts, vm))
270  return 1;
271 
272  ros::init(argc, argv, "snapshot", ros::init_options::AnonymousName);
273  // Get additional topic configurations if they're in ROS params
274  ros::NodeHandle private_nh("~");
275  appendParamOptions(private_nh, opts);
276 
277  // Exit if not topics selected
278  if (!opts.topics_.size() && !opts.all_topics_)
279  {
280  ROS_FATAL("No topics selected. Exiting.");
281  return 1;
282  }
283 
284  // Run the snapshotter
285  rosbag_snapshot::Snapshotter snapshotter(opts);
286  return snapshotter.run();
287 }
#define ROS_FATAL(...)
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)
Definition: snapshot.cpp:152
bool parseVariablesMapClient(SnapshotterClientOptions &opts, po::variables_map const &vm)
Definition: snapshot.cpp:129
bool parseOptions(po::variables_map &vm, int argc, char **argv)
Definition: snapshot.cpp:53
int main(int argc, char **argv)
Definition: snapshot.cpp:250
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::vector< std::string > V_string
std::vector< std::string > topics_
Definition: snapshotter.h:266
bool getParam(const std::string &key, std::string &s) const
#define ROS_ASSERT_MSG(cond,...)
bool parseVariablesMap(SnapshotterOptions &opts, po::variables_map const &vm)
Definition: snapshot.cpp:111
ROSCPP_DECL void removeROSArgs(int argc, const char *const *argv, V_string &args_out)
class ROSBAG_DECL Snapshotter
Definition: snapshotter.h:57
const int MB_TO_BYTES
Definition: snapshot.cpp:51
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)
Definition: snapshotter.cpp:81


rosbag_snapshot
Author(s): Kevin Allen
autogenerated on Mon May 22 2023 02:10:47