query.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_QUERY_H
36 #define ROSBAG_QUERY_H
37 
38 #include "ros/time.h"
39 
40 #include <vector>
41 #include <map>
42 #include <set>
43 
44 #include <boost/function.hpp>
45 #include "rosbag/macros.h"
46 #include "rosbag/structures.h"
47 
48 namespace rosbag {
49 
50 class Bag;
51 
53 {
54 public:
56 
60  Query(boost::function<bool(ConnectionInfo const*)>& query,
61  ros::Time const& start_time = ros::TIME_MIN,
62  ros::Time const& end_time = ros::TIME_MAX);
63 
64  boost::function<bool(ConnectionInfo const*)> const& getQuery() const;
65 
66  ros::Time const& getStartTime() const;
67  ros::Time const& getEndTime() const;
68 
69 private:
70  boost::function<bool(ConnectionInfo const*)> query_;
73 };
74 
76 {
77 public:
78  TopicQuery(std::string const& topic);
79  TopicQuery(std::vector<std::string> const& topics);
80 
81  bool operator()(ConnectionInfo const*) const;
82 
83 private:
84  std::vector<std::string> topics_;
85 };
86 
88 {
89 public:
90  TypeQuery(std::string const& type);
91  TypeQuery(std::vector<std::string> const& types);
92 
93  bool operator()(ConnectionInfo const*) const;
94 
95 private:
96  std::vector<std::string> types_;
97 };
98 
101 {
102  BagQuery(Bag const* _bag, Query const& _query, uint32_t _bag_revision);
103 
104  Bag const* bag;
106  uint32_t bag_revision;
107 };
108 
110 {
111  MessageRange(std::multiset<IndexEntry>::const_iterator const& _begin,
112  std::multiset<IndexEntry>::const_iterator const& _end,
113  ConnectionInfo const* _connection_info,
114  BagQuery const* _bag_query);
115 
116  std::multiset<IndexEntry>::const_iterator begin;
117  std::multiset<IndexEntry>::const_iterator end;
120 };
121 
124 {
125  ViewIterHelper(std::multiset<IndexEntry>::const_iterator _iter, MessageRange const* _range);
126 
127  std::multiset<IndexEntry>::const_iterator iter;
129 };
130 
132 {
133  bool operator()(ViewIterHelper const& a, ViewIterHelper const& b);
134 };
135 
136 } // namespace rosbag
137 
138 #endif
#define ROSBAG_STORAGE_DECL
Definition: macros.h:50
Query query
Definition: query.h:105
boost::function< bool(ConnectionInfo const *)> query_
Definition: query.h:70
const Time TIME_MIN(0, 1)
The actual iterator data structure.
Definition: query.h:123
std::vector< std::string > topics_
Definition: query.h:84
std::vector< std::string > types_
Definition: query.h:96
ros::Time start_time_
Definition: query.h:71
uint32_t bag_revision
Definition: query.h:106
std::multiset< IndexEntry >::const_iterator iter
Definition: query.h:127
ConnectionInfo const * connection_info
Definition: query.h:118
BagQuery const * bag_query
pointer to vector of queries in View
Definition: query.h:119
ROSTIME_DECL const Time TIME_MAX
MessageRange const * range
pointer to vector of ranges in View
Definition: query.h:128
ros::Time end_time_
Definition: query.h:72
std::multiset< IndexEntry >::const_iterator begin
Definition: query.h:116
Pairs of queries and the bags they come from (used internally by View)
Definition: query.h:100
Bag const * bag
Definition: query.h:104
std::multiset< IndexEntry >::const_iterator end
Definition: query.h:117


rosbag_storage
Author(s): Dirk Thomas
autogenerated on Mon Feb 28 2022 23:33:55