query.cpp
Go to the documentation of this file.
00001 // Copyright (c) 2009, Willow Garage, Inc.
00002 // All rights reserved.
00003 // 
00004 // Redistribution and use in source and binary forms, with or without
00005 // modification, are permitted provided that the following conditions are met:
00006 // 
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of Willow Garage, Inc. nor the names of its
00013 //       contributors may be used to endorse or promote products derived from
00014 //       this software without specific prior written permission.
00015 // 
00016 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00017 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00018 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00019 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00020 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00021 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00022 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00023 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00024 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00025 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00026 // POSSIBILITY OF SUCH DAMAGE.
00027 
00028 #include "rosbag/query.h"
00029 #include "rosbag/bag.h"
00030 
00031 #include <boost/foreach.hpp>
00032 
00033 #define foreach BOOST_FOREACH
00034 
00035 using std::map;
00036 using std::string;
00037 using std::vector;
00038 using std::multiset;
00039 
00040 namespace rosbag {
00041 
00042 // Query
00043 
00044 Query::Query(boost::function<bool(ConnectionInfo const*)>& query, ros::Time const& start_time, ros::Time const& end_time)
00045         : query_(query), start_time_(start_time), end_time_(end_time)
00046 {
00047 }
00048 
00049 boost::function<bool(ConnectionInfo const*)> const& Query::getQuery() const {
00050         return query_;
00051 }
00052 
00053 ros::Time const& Query::getStartTime() const { return start_time_; }
00054 ros::Time const& Query::getEndTime()   const { return end_time_;   }
00055 
00056 // TopicQuery
00057 
00058 TopicQuery::TopicQuery(std::string const& topic) {
00059     topics_.push_back(topic);
00060 }
00061 
00062 TopicQuery::TopicQuery(std::vector<std::string> const& topics) : topics_(topics) { }
00063 
00064 bool TopicQuery::operator()(ConnectionInfo const* info) const {
00065     foreach(string const& topic, topics_)
00066         if (topic == info->topic)
00067             return true;
00068 
00069     return false;
00070 }
00071 
00072 // TypeQuery
00073 
00074 TypeQuery::TypeQuery(std::string const& type) {
00075     types_.push_back(type);
00076 }
00077 
00078 TypeQuery::TypeQuery(std::vector<std::string> const& types) : types_(types) { }
00079 
00080 bool TypeQuery::operator()(ConnectionInfo const* info) const {
00081     foreach(string const& type, types_)
00082         if (type == info->datatype)
00083             return true;
00084 
00085     return false;
00086 }
00087 
00088 // BagQuery
00089 
00090 BagQuery::BagQuery(Bag const* _bag, Query const& _query, uint32_t _bag_revision) : bag(_bag), query(_query), bag_revision(_bag_revision) {
00091 }
00092 
00093 // MessageRange
00094 
00095 MessageRange::MessageRange(std::multiset<IndexEntry>::const_iterator const& _begin,
00096                            std::multiset<IndexEntry>::const_iterator const& _end,
00097                            ConnectionInfo const* _connection_info,
00098                            BagQuery const* _bag_query)
00099         : begin(_begin), end(_end), connection_info(_connection_info), bag_query(_bag_query)
00100 {
00101 }
00102 
00103 // ViewIterHelper
00104 
00105 ViewIterHelper::ViewIterHelper(std::multiset<IndexEntry>::const_iterator _iter, MessageRange const* _range)
00106         : iter(_iter), range(_range)
00107 {
00108 }
00109 
00110 bool ViewIterHelperCompare::operator()(ViewIterHelper const& a, ViewIterHelper const& b) {
00111         return (a.iter)->time > (b.iter)->time;
00112 }
00113 
00114 } // namespace rosbag


rosbag_storage
Author(s):
autogenerated on Fri Aug 28 2015 12:33:40