20 #ifndef INCLUDE_FKIE_MESSAGE_FILTERS_BUFFER_H_ 21 #define INCLUDE_FKIE_MESSAGE_FILTERS_BUFFER_H_ 25 #include <boost/circular_buffer.hpp> 28 #include <condition_variable> 102 template<
class... Inputs>
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;
213 template<
class Rep,
class Period>
214 bool process_one(
const std::chrono::duration<Rep, Period>& timeout);
243 void reset() noexcept
override;
245 virtual void receive(
const Inputs&... in)
override;
250 void process_some(std::unique_lock<std::mutex>&);
256 template<
class... Inputs>
Group multiple data types as filter input or output.
Forward data immediately.
Typed base class for filters.
ros::CallbackQueueInterface * cbq_
BufferPolicy
Buffer policy.
std::shared_ptr< Impl > impl_
std::tuple< Inputs... > QueueElement