An abstraction of a series of filters which ensures that only Modbus messages with different timestamps pass the pipeline. More...
#include <filter_pipeline.h>
Public Types | |
using | TCallbackFunc = std::function< void(const ModbusMsgInStampedConstPtr &)> |
Public Member Functions | |
FilterPipeline (ros::NodeHandle &nh, TCallbackFunc callback_func) | |
Private Attributes | |
std::shared_ptr< message_filters::Subscriber< ModbusMsgInStamped > > | modbus_read_sub_ |
std::shared_ptr< message_filters::UpdateFilter< ModbusMsgInStamped > > | update_filter_ |
An abstraction of a series of filters which ensures that only Modbus messages with different timestamps pass the pipeline.
Definition at line 39 of file filter_pipeline.h.
using prbt_hardware_support::FilterPipeline::TCallbackFunc = std::function<void(const ModbusMsgInStampedConstPtr&)> |
Definition at line 42 of file filter_pipeline.h.
|
inline |
Definition at line 57 of file filter_pipeline.h.
|
private |
Subscribes to TOPIC_MODBUS_READ and redirects received messages to the update-filter.
Definition at line 49 of file filter_pipeline.h.
|
private |
Filters consecutive messages with the same timestamp. Passed messages are redirected to the callback_func.
Definition at line 53 of file filter_pipeline.h.