view.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, 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 Willow Garage, Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * 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 
35 #ifndef ROSBAG_VIEW_H
36 #define ROSBAG_VIEW_H
37 
38 #include <boost/function.hpp>
39 #include <boost/iterator/iterator_facade.hpp>
40 
42 #include "rosbag/query.h"
43 #include "rosbag/macros.h"
44 #include "rosbag/structures.h"
45 
46 namespace rosbag {
47 
49 {
50  friend class Bag;
51 
52 public:
54 
60  class iterator : public boost::iterator_facade<iterator,
61  MessageInstance,
62  boost::forward_traversal_tag>
63  {
64  public:
65  iterator(iterator const& i);
66  iterator &operator=(iterator const& i);
67  iterator();
68  ~iterator();
69 
70  protected:
71  iterator(View* view, bool end = false);
72 
73  private:
74  friend class View;
75  friend class boost::iterator_core_access;
76 
77  void populate();
78  void populateSeek(std::multiset<IndexEntry>::const_iterator iter);
79 
80  bool equal(iterator const& other) const;
81 
82  void increment();
83 
84  MessageInstance& dereference() const;
85 
86  private:
88  std::vector<ViewIterHelper> iters_;
89  uint32_t view_revision_;
91  };
92 
94 
95  struct TrueQuery {
96  bool operator()(ConnectionInfo const*) const { return true; };
97  };
98 
100 
103  View(bool const& reduce_overlap = false);
104 
106 
112  View(Bag const& bag, ros::Time const& start_time = ros::TIME_MIN, ros::Time const& end_time = ros::TIME_MAX, bool const& reduce_overlap = false);
113 
115 
122  View(Bag const& bag, boost::function<bool(ConnectionInfo const*)> query,
123  ros::Time const& start_time = ros::TIME_MIN, ros::Time const& end_time = ros::TIME_MAX, bool const& reduce_overlap = false);
124 
125  ~View();
126 
127  iterator begin();
128  iterator end();
129  uint32_t size();
130 
132 
137  void addQuery(Bag const& bag, ros::Time const& start_time = ros::TIME_MIN, ros::Time const& end_time = ros::TIME_MAX);
138 
140 
146  void addQuery(Bag const& bag, boost::function<bool(ConnectionInfo const*)> query,
147  ros::Time const& start_time = ros::TIME_MIN, ros::Time const& end_time = ros::TIME_MAX);
148 
149  std::vector<const ConnectionInfo*> getConnections();
150 
151  ros::Time getBeginTime();
152  ros::Time getEndTime();
153 
154 protected:
155  friend class iterator;
156 
157  void updateQueries(BagQuery* q);
158  void update();
159 
160  MessageInstance* newMessageInstance(ConnectionInfo const* connection_info, IndexEntry const& index, Bag const& bag);
161 
162 private:
163  View(View const& view);
164  View& operator=(View const& view);
165 
166 protected:
167  std::vector<MessageRange*> ranges_;
168  std::vector<BagQuery*> queries_;
169  uint32_t view_revision_;
170 
171  uint32_t size_cache_;
172  uint32_t size_revision_;
173 
175 };
176 
177 } // namespace rosbag
178 
179 #endif
uint32_t size_revision_
Definition: view.h:172
uint32_t view_revision_
Definition: view.h:169
bool operator()(ConnectionInfo const *) const
Definition: view.h:96
uint32_t view_revision_
Definition: view.h:89
An iterator that points to a MessageInstance from a bag.
Definition: view.h:60
uint32_t size_cache_
Definition: view.h:171
MessageInstance * message_instance_
Definition: view.h:90
A class pointing into a bag file.
#define ROSBAG_DECL
Definition: macros.h:42
ROSTIME_DECL const Time TIME_MAX
std::vector< ViewIterHelper > iters_
Definition: view.h:88
Pairs of queries and the bags they come from (used internally by View)
Definition: query.h:100
iterator const_iterator
Definition: view.h:93
std::vector< MessageRange * > ranges_
Definition: view.h:167
ROSTIME_DECL const Time TIME_MIN
Definition: bag.h:68
bool reduce_overlap_
Definition: view.h:174
std::vector< BagQuery * > queries_
Definition: view.h:168


rosbag_storage
Author(s): Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:19