Go to the documentation of this file.
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>
103 class Buffer :
public Filter<IO<Inputs...>, IO<Inputs...>>
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;
252 std::shared_ptr<Impl>
impl_;
256 template<
class... Inputs>
257 class Buffer<IO<Inputs...>> :
public Buffer<Inputs...> {};
std::tuple< Inputs... > QueueElement
ros::CallbackQueueInterface * cbq_
bool wait() noexcept
Wait for pending data.
void spin()
Process all data indefinitely.
std::shared_ptr< Impl > impl_
BufferPolicy
Buffer policy.
@ Discard
Discard all data.
bool process_one()
Wait for and process one data item.
Buffer(const ros::NodeHandle &nh, std::size_t max_queue_size) noexcept
Constructor.
@ Passthru
Forward data immediately.
virtual void receive(const Inputs &... in) override
Process incoming data.
void spin_once()
Process pending data.
void set_callback_queue(ros::CallbackQueueInterface *cbq) noexcept
Process data with a ROS callback queue.
Typed base class for filters.
void send_queue_element(const QueueElement &e)
bool has_some() const noexcept
Check if the buffer has pending data.
@ Queue
Queue for later use.
bool wait_for(const std::chrono::duration< Rep, Period > &timeout) noexcept
Wait for pending data until timeout expires.
void set_policy(BufferPolicy policy, std::size_t max_queue_size=0)
Modify the buffer policy.
void reset() noexcept override
Reset filter.
void process_some(std::unique_lock< std::mutex > &)