18 #ifndef FILTER_PIPELINE_H 19 #define FILTER_PIPELINE_H 29 #include <prbt_hardware_support/ModbusMsgInStamped.h> 42 using TCallbackFunc = std::function<void(const ModbusMsgInStampedConstPtr&)>;
53 std::shared_ptr<message_filters::UpdateFilter<ModbusMsgInStamped> >
update_filter_;
61 throw std::invalid_argument(
"Argument \"callback_func\" must not be empty");
64 update_filter_ = std::make_shared<message_filters::UpdateFilter<ModbusMsgInStamped> >(*modbus_read_sub_);
65 update_filter_->registerCallback(callback_func);
70 #endif // FILTER_PIPELINE_H
std::shared_ptr< message_filters::Subscriber< ModbusMsgInStamped > > modbus_read_sub_
std::function< void(const ModbusMsgInStampedConstPtr &)> TCallbackFunc
static const std::string TOPIC_MODBUS_READ
FilterPipeline(ros::NodeHandle &nh, TCallbackFunc callback_func)
An abstraction of a series of filters which ensures that only Modbus messages with different timestam...
std::shared_ptr< message_filters::UpdateFilter< ModbusMsgInStamped > > update_filter_