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  ("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");
87  // clang-format on
88  po::positional_options_description p;
89  p.add("topic", -1);
90 
91  try
92  {
93  po::store(po::command_line_parser(cleaned_argc, cleaned_argv).options(desc).positional(p).run(), vm);
94  po::notify(vm);
95  }
96  catch (boost::program_options::error const& e)
97  {
98  std::cout << "rosbag_snapshot: " << e.what() << std::endl;
99  return false;
100  }
101 
102  if (vm.count("help"))
103  {
104  std::cout << "Usage: rosrun rosbag_snapshot snapshot [options] [topic1 topic2 ...]" << std::endl
105  << std::endl
106  << "Buffer recent messages until triggered to write or trigger an already running instance." << std::endl
107  << std::endl;
108  std::cout << desc << std::endl;
109  return false;
110  }
111  return true;
112 }
113 
114 bool parseVariablesMap(SnapshotterOptions& opts, po::variables_map const& vm)
115 {
116  if (vm.count("topic"))
117  {
118  std::vector<std::string> topics = vm["topic"].as<std::vector<std::string> >();
119  for (const std::string& str : topics)
120  {
121  opts.addTopic(str);
122  }
123  }
124  opts.default_memory_limit_ = static_cast<int>(MB_TO_BYTES * vm["size"].as<double>());
125  opts.default_duration_limit_ = ros::Duration(vm["duration"].as<double>());
126  opts.default_count_limit_ = vm["count"].as<int32_t>();
127  if (vm.count("no-clear"))
128  {
129  opts.clear_buffer_ = false;
130  }
131  else opts.clear_buffer_ = true;
132  opts.all_topics_ = vm.count("all");
133  opts.compression_ = vm["compression"].as<std::string>();
134  if (vm.count("queue-size"))
135  {
136  opts.queue_size_ = vm["queue-size"].as<int32_t>();
137  }
138  else
139  {
140  opts.queue_size_ = 10;
141  }
142  return true;
143 }
144 
145 bool parseVariablesMapClient(SnapshotterClientOptions& opts, po::variables_map const& vm)
146 {
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"))
152  {
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>();
160  }
161  return true;
162 }
163 
164 /* Read configured topics and limits from ROS params
165  * TODO: use exceptions instead of asserts to follow style conventions
166  * See snapshot.test for an example
167  */
169 {
170  using XmlRpc::XmlRpcValue;
171  XmlRpcValue topics;
172 
173  // Override program options for default limits if the parameters are set.
174  double tmp;
175  int32_t default_count;
176  bool clear_buffer;
177  if (nh.getParam("default_memory_limit", tmp))
178  opts.default_memory_limit_ = static_cast<int>(MB_TO_BYTES * tmp);
179  if (nh.getParam("default_duration_limit", tmp))
181  if (nh.getParam("default_count_limit", default_count))
182  opts.default_count_limit_ = default_count;
183  if (nh.getParam("clear_buffer", clear_buffer))
184  opts.clear_buffer_ = clear_buffer;
185  nh.param("record_all_topics", opts.all_topics_, opts.all_topics_);
186 
187  // Set compression type
188  const std::string default_compression{"uncompressed"};
189  nh.param("compression", opts.compression_, default_compression);
190 
191  nh.param("queue_size", opts.queue_size_, 10);
192 
193  if (!nh.getParam("topics", topics))
194  {
195  return;
196  }
197  ROS_ASSERT_MSG(topics.getType() == XmlRpcValue::TypeArray, "topics param must be an array");
198  // Iterator caused exception, hmmm...
199  size_t size = topics.size();
200  for (size_t i = 0; i < size; ++i)
201  {
202  XmlRpcValue topic_value = topics[i];
203  // If it is just a string, add this topic
204  if (topic_value.getType() == XmlRpcValue::TypeString)
205  {
206  opts.addTopic(topic_value);
207  }
208  else if (topic_value.getType() == XmlRpcValue::TypeStruct)
209  {
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'",
214  topic.c_str());
215 
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))
223  {
224  XmlRpcValue& dur_limit = topic_config[duration];
225  if (dur_limit.getType() == XmlRpcValue::TypeDouble)
226  {
227  double seconds = dur_limit;
228  dur = ros::Duration(seconds);
229  }
230  else if (dur_limit.getType() == XmlRpcValue::TypeInt)
231  {
232  int seconds = dur_limit;
233  dur = ros::Duration(seconds, 0);
234  }
235  else
236  ROS_FATAL("err");
237  }
238  if (topic_config.hasMember("memory"))
239  {
240  XmlRpcValue& mem_limit = topic_config[memory];
241  if (mem_limit.getType() == XmlRpcValue::TypeDouble)
242  {
243  double mb = mem_limit;
244  mem = static_cast<int>(MB_TO_BYTES * mb);
245  }
246  else if (mem_limit.getType() == XmlRpcValue::TypeInt)
247  {
248  int mb = mem_limit;
249  mem = MB_TO_BYTES * mb;
250  }
251  else
252  ROS_FATAL("err");
253  }
254  if (topic_config.hasMember("count"))
255  {
256  XmlRpcValue& cnt_limit = topic_config[count];
257  if (cnt_limit.getType() == XmlRpcValue::TypeInt)
258  {
259  cnt = cnt_limit;
260  }
261  else
262  ROS_FATAL("err");
263  }
264  opts.addTopic(topic, dur, mem, cnt);
265  }
266  else
267  ROS_ASSERT_MSG(false, "Parameter invalid for topic %lu", i);
268  }
269 }
270 
271 int main(int argc, char** argv)
272 {
273  po::variables_map vm;
274  if (!parseOptions(vm, argc, argv))
275  return 1;
276 
277  // If any of the client flags are on, use the client
278  if (vm.count("trigger-write") || vm.count("pause") || vm.count("resume"))
279  {
281  if (!parseVariablesMapClient(opts, vm))
282  return 1;
283  ros::init(argc, argv, "snapshot_client", ros::init_options::AnonymousName);
284  SnapshotterClient client;
285  return client.run(opts);
286  }
287 
288  // Parse the command-line options
289  SnapshotterOptions opts;
290  if (!parseVariablesMap(opts, vm))
291  return 1;
292 
293  ros::init(argc, argv, "snapshot", ros::init_options::AnonymousName);
294  // Get additional topic configurations if they're in ROS params
295  ros::NodeHandle private_nh("~");
296  appendParamOptions(private_nh, opts);
297 
298  // Exit if not topics selected
299  if (!opts.topics_.size() && !opts.all_topics_)
300  {
301  ROS_FATAL("No topics selected. Exiting.");
302  return 1;
303  }
304 
305  // Run the snapshotter
306  rosbag_snapshot::Snapshotter snapshotter(opts);
307  return snapshotter.run();
308 }
ros::init_options::AnonymousName
AnonymousName
parseVariablesMapClient
bool parseVariablesMapClient(SnapshotterClientOptions &opts, po::variables_map const &vm)
Definition: snapshot.cpp:145
rosbag_snapshot::SnapshotterClientOptions::filename_
std::string filename_
Definition: snapshotter.h:304
snapshotter.h
rosbag_snapshot::SnapshotterOptions::topics_
topics_t topics_
Definition: snapshotter.h:146
rosbag_snapshot::SnapshotterClient::run
int run(SnapshotterClientOptions const &opts)
Definition: snapshotter.cpp:622
rosbag_snapshot::SnapshotterOptions::all_topics_
bool all_topics_
Definition: snapshotter.h:135
run
void run(class_loader::ClassLoader *loader)
rosbag_snapshot::SnapshotterTopicOptions
Definition: snapshotter.h:95
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
appendParamOptions
void appendParamOptions(ros::NodeHandle &nh, SnapshotterOptions &opts)
Definition: snapshot.cpp:168
rosbag_snapshot::SnapshotterClient
Definition: snapshotter.h:310
rosbag_snapshot::SnapshotterOptions
Definition: snapshotter.h:124
rosbag_snapshot::SnapshotterClientOptions
Definition: snapshotter.h:290
rosbag_snapshot::SnapshotterClientOptions::topics_
std::vector< std::string > topics_
Definition: snapshotter.h:302
rosbag_snapshot::SnapshotterOptions::default_count_limit_
int32_t default_count_limit_
Definition: snapshotter.h:131
rosbag_snapshot::SnapshotterOptions::addTopic
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:82
rosbag_snapshot::SnapshotterOptions::default_duration_limit_
ros::Duration default_duration_limit_
Definition: snapshotter.h:127
rosbag_snapshot::SnapshotterOptions::queue_size_
int queue_size_
Definition: snapshotter.h:141
MB_TO_BYTES
const int MB_TO_BYTES
Definition: snapshot.cpp:51
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
rosbag_snapshot::Snapshotter::run
int run()
Definition: snapshotter.cpp:581
rosbag_snapshot::SnapshotterClientOptions::action_
Action action_
Definition: snapshotter.h:300
ROS_FATAL
#define ROS_FATAL(...)
exceptions.h
parseVariablesMap
bool parseVariablesMap(SnapshotterOptions &opts, po::variables_map const &vm)
Definition: snapshot.cpp:114
parseOptions
bool parseOptions(po::variables_map &vm, int argc, char **argv)
Definition: snapshot.cpp:53
rosbag_snapshot::SnapshotterOptions::clear_buffer_
bool clear_buffer_
Definition: snapshotter.h:137
rosbag_snapshot::SnapshotterClientOptions::prefix_
std::string prefix_
Definition: snapshotter.h:306
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
rosbag_snapshot::SnapshotterOptions::compression_
std::string compression_
Definition: snapshotter.h:139
rosbag_snapshot::Snapshotter
class ROSBAG_DECL Snapshotter
Definition: snapshotter.h:89
main
int main(int argc, char **argv)
Definition: snapshot.cpp:271
ros::V_string
std::vector< std::string > V_string
ros::removeROSArgs
ROSCPP_DECL void removeROSArgs(int argc, const char *const *argv, V_string &args_out)
ros::Duration
rosbag_snapshot::SnapshotterOptions::default_memory_limit_
int32_t default_memory_limit_
Definition: snapshotter.h:129
XmlRpc::XmlRpcValue
ros::NodeHandle
rosbag_snapshot::Snapshotter
Definition: snapshotter.h:230


rosbag_snapshot
Author(s): Kevin Allen
autogenerated on Wed May 14 2025 02:13:18