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  ("duration,d", po::value<double>()->default_value(30.0),
74  "Maximum difference between newest and oldest buffered message per topic in seconds. Default: 30")
75  ("output-prefix,o", po::value<std::string>()->default_value(""),
76  "When in trigger write mode, prepend PREFIX to name of writting bag file")
77  ("output-filename,O", po::value<std::string>(), "When in trigger write mode, exact name of written bag file")
78  ("topic", po::value<std::vector<std::string> >(),
79  "Topic to buffer. If triggering write, write only these topics instead of all buffered topics.");
80  // clang-format on
81  po::positional_options_description p;
82  p.add("topic", -1);
83 
84  try
85  {
86  po::store(po::command_line_parser(cleaned_argc, cleaned_argv).options(desc).positional(p).run(), vm);
87  po::notify(vm);
88  }
89  catch (boost::program_options::error const& e)
90  {
91  std::cout << "rosbag_snapshot: " << e.what() << std::endl;
92  return false;
93  }
94 
95  if (vm.count("help"))
96  {
97  std::cout << "Usage: rosrun rosbag_snapshot snapshot [options] [topic1 topic2 ...]" << std::endl
98  << std::endl
99  << "Buffer recent messages until triggered to write or trigger an already running instance." << std::endl
100  << std::endl;
101  std::cout << desc << std::endl;
102  return false;
103  }
104  return true;
105 }
106 
107 bool parseVariablesMap(SnapshotterOptions& opts, po::variables_map const& vm)
108 {
109  if (vm.count("topic"))
110  {
111  std::vector<std::string> topics = vm["topic"].as<std::vector<std::string> >();
112  for (const std::string& str : topics)
113  {
114  opts.addTopic(str);
115  }
116  }
117  opts.default_memory_limit_ = static_cast<int>(MB_TO_BYTES * vm["size"].as<double>());
118  opts.default_duration_limit_ = ros::Duration(vm["duration"].as<double>());
119  opts.all_topics_ = vm.count("all");
120  return true;
121 }
122 
123 bool parseVariablesMapClient(SnapshotterClientOptions& opts, po::variables_map const& vm)
124 {
125  if (vm.count("pause"))
126  opts.action_ = SnapshotterClientOptions::PAUSE;
127  else if (vm.count("resume"))
128  opts.action_ = SnapshotterClientOptions::RESUME;
129  else if (vm.count("trigger-write"))
130  {
131  opts.action_ = SnapshotterClientOptions::TRIGGER_WRITE;
132  if (vm.count("topic"))
133  opts.topics_ = vm["topic"].as<std::vector<std::string> >();
134  if (vm.count("output-prefix"))
135  opts.prefix_ = vm["output-prefix"].as<std::string>();
136  if (vm.count("output-filename"))
137  opts.filename_ = vm["output-filename"].as<std::string>();
138  }
139  return true;
140 }
141 
142 /* Read configured topics and limits from ROS params
143  * TODO: use exceptions instead of asserts to follow style conventions
144  * See snapshot.test for an example
145  */
147 {
148  using XmlRpc::XmlRpcValue;
149  XmlRpcValue topics;
150 
151  // Override program options for default limits if the parameters are set.
152  double tmp;
153  if (nh.getParam("default_memory_limit", tmp))
154  opts.default_memory_limit_ = static_cast<int>(MB_TO_BYTES * tmp);
155  if (nh.getParam("default_duration_limit", tmp))
157  nh.param("record_all_topics", opts.all_topics_, opts.all_topics_);
158 
159  if (!nh.getParam("topics", topics))
160  {
161  return;
162  }
163  ROS_ASSERT_MSG(topics.getType() == XmlRpcValue::TypeArray, "topics param must be an array");
164  // Iterator caused exception, hmmm...
165  size_t size = topics.size();
166  for (size_t i = 0; i < size; ++i)
167  {
168  XmlRpcValue topic_value = topics[i];
169  // If it is just a string, add this topic
170  if (topic_value.getType() == XmlRpcValue::TypeString)
171  {
172  opts.addTopic(topic_value);
173  }
174  else if (topic_value.getType() == XmlRpcValue::TypeStruct)
175  {
176  ROS_ASSERT_MSG(topic_value.size() == 1, "Paramater invalid for topic %lu", i);
177  std::string const& topic = (*topic_value.begin()).first;
178  XmlRpcValue& topic_config = (*topic_value.begin()).second;
179  ROS_ASSERT_MSG(topic_config.getType() == XmlRpcValue::TypeStruct, "Topic limits invalid for: '%s'",
180  topic.c_str());
181 
182  ros::Duration dur = SnapshotterTopicOptions::INHERIT_DURATION_LIMIT;
183  int64_t mem = SnapshotterTopicOptions::INHERIT_MEMORY_LIMIT;
184  std::string duration = "duration";
185  std::string memory = "memory";
186  if (topic_config.hasMember(duration))
187  {
188  XmlRpcValue& dur_limit = topic_config[duration];
189  if (dur_limit.getType() == XmlRpcValue::TypeDouble)
190  {
191  double seconds = dur_limit;
192  dur = ros::Duration(seconds);
193  }
194  else if (dur_limit.getType() == XmlRpcValue::TypeInt)
195  {
196  int seconds = dur_limit;
197  dur = ros::Duration(seconds, 0);
198  }
199  else
200  ROS_FATAL("err");
201  }
202  if (topic_config.hasMember("memory"))
203  {
204  XmlRpcValue& mem_limit = topic_config[memory];
205  if (mem_limit.getType() == XmlRpcValue::TypeDouble)
206  {
207  double mb = mem_limit;
208  mem = static_cast<int>(MB_TO_BYTES * mb);
209  }
210  else if (mem_limit.getType() == XmlRpcValue::TypeInt)
211  {
212  int mb = mem_limit;
213  mem = MB_TO_BYTES * mb;
214  }
215  else
216  ROS_FATAL("err");
217  }
218  opts.addTopic(topic, dur, mem);
219  }
220  else
221  ROS_ASSERT_MSG(false, "Parameter invalid for topic %lu", i);
222  }
223 }
224 
225 int main(int argc, char** argv)
226 {
227  po::variables_map vm;
228  if (!parseOptions(vm, argc, argv))
229  return 1;
230 
231  // If any of the client flags are on, use the client
232  if (vm.count("trigger-write") || vm.count("pause") || vm.count("resume"))
233  {
235  if (!parseVariablesMapClient(opts, vm))
236  return 1;
237  ros::init(argc, argv, "snapshot_client", ros::init_options::AnonymousName);
238  SnapshotterClient client;
239  return client.run(opts);
240  }
241 
242  // Parse the command-line options
243  SnapshotterOptions opts;
244  if (!parseVariablesMap(opts, vm))
245  return 1;
246 
247  ros::init(argc, argv, "snapshot", ros::init_options::AnonymousName);
248  // Get additional topic configurations if they're in ROS params
249  ros::NodeHandle private_nh("~");
250  appendParamOptions(private_nh, opts);
251 
252  // Exit if not topics selected
253  if (!opts.topics_.size() && !opts.all_topics_)
254  {
255  ROS_FATAL("No topics selected. Exiting.");
256  return 1;
257  }
258 
259  // Run the snapshotter
260  rosbag_snapshot::Snapshotter snapshotter(opts);
261  return snapshotter.run();
262 }
#define ROS_FATAL(...)
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:146
bool parseVariablesMapClient(SnapshotterClientOptions &opts, po::variables_map const &vm)
Definition: snapshot.cpp:123
bool parseOptions(po::variables_map &vm, int argc, char **argv)
Definition: snapshot.cpp:53
bool addTopic(std::string const &topic, ros::Duration duration_limit=SnapshotterTopicOptions::INHERIT_DURATION_LIMIT, int32_t memory_limit=SnapshotterTopicOptions::INHERIT_MEMORY_LIMIT)
Definition: snapshotter.cpp:76
int main(int argc, char **argv)
Definition: snapshot.cpp:225
std::vector< std::string > V_string
std::vector< std::string > topics_
Definition: snapshotter.h:252
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define ROS_ASSERT_MSG(cond,...)
bool parseVariablesMap(SnapshotterOptions &opts, po::variables_map const &vm)
Definition: snapshot.cpp:107
bool getParam(const std::string &key, std::string &s) const
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)


rosbag_snapshot
Author(s): Kevin Allen
autogenerated on Mon Jan 18 2021 03:45:11