buffer.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * fkie_message_filters
4  * Copyright © 2018-2020 Fraunhofer FKIE
5  * Author: Timo Röhling
6  *
7  * Licensed under the Apache License, Version 2.0 (the "License");
8  * you may not use this file except in compliance with the License.
9  * You may obtain a copy of the License at
10  *
11  * http://www.apache.org/licenses/LICENSE-2.0
12  *
13  * Unless required by applicable law or agreed to in writing, software
14  * distributed under the License is distributed on an "AS IS" BASIS,
15  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
16  * See the License for the specific language governing permissions and
17  * limitations under the License.
18  *
19  ****************************************************************************/
20 #ifndef INCLUDE_FKIE_MESSAGE_FILTERS_BUFFER_H_
21 #define INCLUDE_FKIE_MESSAGE_FILTERS_BUFFER_H_
22 
23 
24 #include "filter.h"
25 #include <boost/circular_buffer.hpp>
26 #include <tuple>
27 #include <mutex>
28 #include <condition_variable>
30 #include <ros/node_handle.h>
31 
32 
34 {
35 
40 enum class BufferPolicy
41 {
46  Discard,
51  Queue,
56  Passthru
57 };
58 
102 template<class... Inputs>
103 class Buffer : public Filter<IO<Inputs...>, IO<Inputs...>>
104 {
105 public:
115  Buffer (const ros::NodeHandle& nh, std::size_t max_queue_size) noexcept;
124  Buffer (BufferPolicy policy = BufferPolicy::Discard, std::size_t max_queue_size = 1, ros::CallbackQueueInterface* cbq = nullptr) noexcept;
125  virtual ~Buffer();
143  void set_policy (BufferPolicy policy, std::size_t max_queue_size = 0);
162  void set_callback_queue(ros::CallbackQueueInterface* cbq) noexcept;
170  bool has_some() const noexcept;
179  bool wait() noexcept;
191  template<class Rep, class Period>
192  bool wait_for(const std::chrono::duration<Rep, Period>& timeout) noexcept;
201  bool process_one();
213  template<class Rep, class Period>
214  bool process_one(const std::chrono::duration<Rep, Period>& timeout);
223  void spin_once();
235  void spin();
243  void reset() noexcept override;
244 protected:
245  virtual void receive(const Inputs&... in) override;
246 private:
247  struct Impl;
248  class RosCB;
249  using QueueElement = std::tuple<Inputs...>;
250  void process_some(std::unique_lock<std::mutex>&);
251  void send_queue_element(const QueueElement& e);
252  std::shared_ptr<Impl> impl_;
254 };
255 
256 template<class... Inputs>
257 class Buffer<IO<Inputs...>> : public Buffer<Inputs...> {};
258 
259 } // namespace fkie_message_filters
260 
261 #include "buffer_impl.h"
262 
263 #endif /* INCLUDE_FKIE_MESSAGE_FILTERS_BUFFER_H_ */
Store and forward data.
Definition: buffer.h:103
void wait(int seconds)
Group multiple data types as filter input or output.
Definition: io.h:27
Typed base class for filters.
Definition: filter.h:35
ros::CallbackQueueInterface * cbq_
Definition: buffer.h:253
BufferPolicy
Buffer policy.
Definition: buffer.h:40
Primary namespace.
Definition: buffer.h:33
ROSCPP_DECL void spin()
std::shared_ptr< Impl > impl_
Definition: buffer.h:252
std::tuple< Inputs... > QueueElement
Definition: buffer.h:249


fkie_message_filters
Author(s): Timo Röhling
autogenerated on Mon Feb 28 2022 22:21:43