query.cpp
Go to the documentation of this file.
1 // Copyright (c) 2009, Willow Garage, Inc.
2 // All rights reserved.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 //
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of Willow Garage, Inc. nor the names of its
13 // contributors may be used to endorse or promote products derived from
14 // this software without specific prior written permission.
15 //
16 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 // POSSIBILITY OF SUCH DAMAGE.
27 
28 #include "rosbag/query.h"
29 #include "rosbag/bag.h"
30 
31 using std::map;
32 using std::string;
33 using std::vector;
34 using std::multiset;
35 
36 namespace rosbag {
37 
38 // Query
39 
40 Query::Query(boost::function<bool(ConnectionInfo const*)>& query, ros::Time const& start_time, ros::Time const& end_time)
41  : query_(query), start_time_(start_time), end_time_(end_time)
42 {
43 }
44 
45 boost::function<bool(ConnectionInfo const*)> const& Query::getQuery() const {
46  return query_;
47 }
48 
49 ros::Time const& Query::getStartTime() const { return start_time_; }
50 ros::Time const& Query::getEndTime() const { return end_time_; }
51 
52 // TopicQuery
53 
54 TopicQuery::TopicQuery(std::string const& topic) {
55  topics_.push_back(topic);
56 }
57 
58 TopicQuery::TopicQuery(std::vector<std::string> const& topics) : topics_(topics) { }
59 
60 bool TopicQuery::operator()(ConnectionInfo const* info) const {
61  return std::find(std::begin(topics_), std::end(topics_), info->topic) != std::end(topics_);
62 }
63 
64 // TypeQuery
65 
66 TypeQuery::TypeQuery(std::string const& type) {
67  types_.push_back(type);
68 }
69 
70 TypeQuery::TypeQuery(std::vector<std::string> const& types) : types_(types) { }
71 
72 bool TypeQuery::operator()(ConnectionInfo const* info) const {
73  return std::find(std::begin(types_), std::end(types_), info->datatype) != std::end(types_);
74 }
75 
76 // BagQuery
77 
78 BagQuery::BagQuery(Bag const* _bag, Query const& _query, uint32_t _bag_revision) : bag(_bag), query(_query), bag_revision(_bag_revision) {
79 }
80 
81 // MessageRange
82 
83 MessageRange::MessageRange(std::multiset<IndexEntry>::const_iterator const& _begin,
84  std::multiset<IndexEntry>::const_iterator const& _end,
85  ConnectionInfo const* _connection_info,
86  BagQuery const* _bag_query)
87  : begin(_begin), end(_end), connection_info(_connection_info), bag_query(_bag_query)
88 {
89 }
90 
91 // ViewIterHelper
92 
93 ViewIterHelper::ViewIterHelper(std::multiset<IndexEntry>::const_iterator _iter, MessageRange const* _range)
94  : iter(_iter), range(_range)
95 {
96 }
97 
99  return (a.iter)->time > (b.iter)->time;
100 }
101 
102 } // namespace rosbag
TypeQuery(std::string const &type)
Definition: query.cpp:66
bool operator()(ViewIterHelper const &a, ViewIterHelper const &b)
Definition: query.cpp:98
boost::function< bool(ConnectionInfo const *)> query_
Definition: query.h:70
The actual iterator data structure.
Definition: query.h:123
std::vector< std::string > topics_
Definition: query.h:84
ViewIterHelper(std::multiset< IndexEntry >::const_iterator _iter, MessageRange const *_range)
Definition: query.cpp:93
std::vector< std::string > types_
Definition: query.h:96
MessageRange(std::multiset< IndexEntry >::const_iterator const &_begin, std::multiset< IndexEntry >::const_iterator const &_end, ConnectionInfo const *_connection_info, BagQuery const *_bag_query)
Definition: query.cpp:83
ros::Time start_time_
Definition: query.h:71
ros::Time const & getEndTime() const
Get the end-time.
Definition: query.cpp:50
BagQuery(Bag const *_bag, Query const &_query, uint32_t _bag_revision)
Definition: query.cpp:78
std::multiset< IndexEntry >::const_iterator iter
Definition: query.h:127
bool operator()(ConnectionInfo const *) const
Definition: query.cpp:60
ros::Time end_time_
Definition: query.h:72
Pairs of queries and the bags they come from (used internally by View)
Definition: query.h:100
std::string datatype
Definition: structures.h:53
ros::Time const & getStartTime() const
Get the start-time.
Definition: query.cpp:49
Query(boost::function< bool(ConnectionInfo const *)> &query, ros::Time const &start_time=ros::TIME_MIN, ros::Time const &end_time=ros::TIME_MAX)
The base query takes an optional time-range.
Definition: query.cpp:40
bool operator()(ConnectionInfo const *) const
Definition: query.cpp:72
boost::function< bool(ConnectionInfo const *)> const & getQuery() const
Get the query functor.
Definition: query.cpp:45
TopicQuery(std::string const &topic)
Definition: query.cpp:54


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