include
warehouse_ros
query_results.h
Go to the documentation of this file.
1
/*
2
* Copyright (c) 2008, Willow Garage, Inc.
3
* All rights reserved.
4
*
5
* Redistribution and use in source and binary forms, with or without
6
* modification, are permitted provided that the following conditions are met:
7
*
8
* * Redistributions of source code must retain the above copyright
9
* notice, this list of conditions and the following disclaimer.
10
* * Redistributions in binary form must reproduce the above copyright
11
* notice, this list of conditions and the following disclaimer in the
12
* documentation and/or other materials provided with the distribution.
13
* * Neither the name of the Willow Garage, Inc. nor the names of its
14
* contributors may be used to endorse or promote products derived from
15
* this software without specific prior written permission.
16
*
17
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27
* POSSIBILITY OF SUCH DAMAGE.
28
*
29
*/
30
39
#ifndef WAREHOUSE_ROS_QUERY_RESULTS_H
40
#define WAREHOUSE_ROS_QUERY_RESULTS_H
41
42
#include <
warehouse_ros/message_with_metadata.h
>
43
#include <
warehouse_ros/exceptions.h
>
44
#include <boost/iterator/iterator_facade.hpp>
45
46
namespace
warehouse_ros
47
{
48
class
ResultIteratorHelper
49
{
50
public
:
51
virtual
bool
next
() = 0;
52
virtual
bool
hasData
()
const
= 0;
53
virtual
Metadata::ConstPtr
metadata
()
const
= 0;
54
virtual
std::string
message
()
const
= 0;
55
virtual
~ResultIteratorHelper
() =
default
;
56
57
typedef
boost::shared_ptr<ResultIteratorHelper>
Ptr
;
58
};
59
60
template
<
class
M>
61
class
ResultIterator
62
:
public
boost::iterator_facade<ResultIterator<M>, typename MessageWithMetadata<M>::ConstPtr,
63
boost::single_pass_traversal_tag, typename MessageWithMetadata<M>::ConstPtr>
64
{
65
public
:
67
ResultIterator
(
ResultIteratorHelper::Ptr
results,
bool
metadata_only);
68
70
ResultIterator
() =
default
;
71
72
private
:
73
friend
class
boost::iterator_core_access
;
74
75
// Member functions needed to be an iterator
76
void
increment
();
77
typename
MessageWithMetadata<M>::ConstPtr
dereference
()
const
;
78
bool
equal
(
const
ResultIterator<M>
& other)
const
;
79
80
ResultIteratorHelper::Ptr
results_
;
81
bool
metadata_only_
=
false
;
82
};
83
84
template
<
class
M>
85
struct
QueryResults
86
{
87
typedef
std::pair<ResultIterator<M>,
ResultIterator<M>
>
range_t
;
88
};
89
90
}
// namespace warehouse_ros
91
92
#include "
impl/query_results_impl.hpp
"
93
94
#endif // include guard
exceptions.h
warehouse_ros::ResultIterator::iterator_core_access
friend class boost::iterator_core_access
Definition:
query_results.h:73
query_results_impl.hpp
boost::shared_ptr< const Metadata >
warehouse_ros::QueryResults
Definition:
query_results.h:85
warehouse_ros::ResultIteratorHelper::message
virtual std::string message() const =0
warehouse_ros::ResultIterator
Definition:
query_results.h:61
warehouse_ros::ResultIteratorHelper
Definition:
query_results.h:48
warehouse_ros::ResultIterator::metadata_only_
bool metadata_only_
Definition:
query_results.h:81
warehouse_ros::ResultIteratorHelper::Ptr
boost::shared_ptr< ResultIteratorHelper > Ptr
Definition:
query_results.h:57
warehouse_ros::ResultIteratorHelper::~ResultIteratorHelper
virtual ~ResultIteratorHelper()=default
warehouse_ros::ResultIteratorHelper::hasData
virtual bool hasData() const =0
warehouse_ros::QueryResults::range_t
std::pair< ResultIterator< M >, ResultIterator< M > > range_t
Definition:
query_results.h:87
message_with_metadata.h
warehouse_ros::ResultIteratorHelper::next
virtual bool next()=0
warehouse_ros::ResultIterator::increment
void increment()
Definition:
query_results_impl.hpp:51
warehouse_ros::ResultIterator::ResultIterator
ResultIterator()=default
Default constructor.
warehouse_ros::ResultIterator::equal
bool equal(const ResultIterator< M > &other) const
Definition:
query_results_impl.hpp:76
warehouse_ros
Definition:
database_connection.h:44
warehouse_ros::ResultIterator::results_
ResultIteratorHelper::Ptr results_
Definition:
query_results.h:80
warehouse_ros::ResultIterator::dereference
MessageWithMetadata< M >::ConstPtr dereference() const
Definition:
query_results_impl.hpp:60
warehouse_ros::ResultIteratorHelper::metadata
virtual Metadata::ConstPtr metadata() const =0
warehouse_ros
Author(s): Bhaskara Marthi
, Connor Brew
autogenerated on Wed Oct 16 2024 02:42:07