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);
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_ */
fkie_message_filters
Definition: buffer.h:33
fkie_message_filters::Buffer::~Buffer
virtual ~Buffer()
Definition: buffer_impl.h:138
node_handle.h
filter.h
fkie_message_filters::Buffer::QueueElement
std::tuple< Inputs... > QueueElement
Definition: buffer.h:267
fkie_message_filters::Buffer::cbq_
ros::CallbackQueueInterface * cbq_
Definition: buffer.h:271
fkie_message_filters::Buffer::wait
bool wait() noexcept
Wait for pending data.
Definition: buffer_impl.h:216
fkie_message_filters::Buffer::spin
void spin()
Process all data indefinitely.
Definition: buffer_impl.h:283
buffer_impl.h
fkie_message_filters::Buffer::impl_
std::shared_ptr< Impl > impl_
Definition: buffer.h:270
fkie_message_filters::BufferPolicy
BufferPolicy
Buffer policy.
Definition: buffer.h:58
callback_queue_interface.h
fkie_message_filters::BufferPolicy::Discard
@ Discard
Discard all data.
fkie_message_filters::Buffer::process_one
bool process_one()
Wait for and process one data item.
Definition: buffer_impl.h:231
fkie_message_filters::Buffer::Buffer
Buffer(const ros::NodeHandle &nh, std::size_t max_queue_size) noexcept
Constructor.
Definition: buffer_impl.h:131
fkie_message_filters::Buffer
Store and forward data.
Definition: buffer.h:121
fkie_message_filters::BufferPolicy::Passthru
@ Passthru
Forward data immediately.
fkie_message_filters::Buffer::receive
virtual void receive(const Inputs &... in) override
Process incoming data.
Definition: buffer_impl.h:262
fkie_message_filters::Buffer::spin_once
void spin_once()
Process pending data.
Definition: buffer_impl.h:178
fkie_message_filters::Buffer::set_callback_queue
void set_callback_queue(ros::CallbackQueueInterface *cbq) noexcept
Process data with a ROS callback queue.
Definition: buffer_impl.h:171
fkie_message_filters::Filter
Typed base class for filters.
Definition: filter.h:53
fkie_message_filters::Buffer::send_queue_element
void send_queue_element(const QueueElement &e)
Definition: buffer_impl.h:297
fkie_message_filters::Buffer::has_some
bool has_some() const noexcept
Check if the buffer has pending data.
Definition: buffer_impl.h:209
fkie_message_filters::BufferPolicy::Queue
@ Queue
Queue for later use.
fkie_message_filters::Buffer::wait_for
bool wait_for(const std::chrono::duration< Rep, Period > &timeout) noexcept
Wait for pending data until timeout expires.
Definition: buffer_impl.h:224
ros::CallbackQueueInterface
ros::NodeHandle
fkie_message_filters::Buffer::set_policy
void set_policy(BufferPolicy policy, std::size_t max_queue_size=0)
Modify the buffer policy.
Definition: buffer_impl.h:144
fkie_message_filters::Buffer::reset
void reset() noexcept override
Reset filter.
Definition: buffer_impl.h:185
fkie_message_filters::Buffer::process_some
void process_some(std::unique_lock< std::mutex > &)
Definition: buffer_impl.h:194


fkie_message_filters
Author(s): Timo Röhling
autogenerated on Wed Mar 2 2022 00:18:57