35 #ifndef MESSAGE_FILTERS_SIMPLE_FILTER_H 36 #define MESSAGE_FILTERS_SIMPLE_FILTER_H 38 #include <boost/noncopyable.hpp> 45 #include <boost/bind.hpp> 64 typedef boost::function<void(const MConstPtr&)>
Callback;
104 template<
typename T,
typename P>
Connection registerCallback(void(*callback)(P))
Register a callback to be called when this filter has passed.
void removeCallback(const CallbackHelper1Ptr &helper)
void signalMessage(const MConstPtr &msg)
Call all registered callbacks, passing them the specified message.
void signalMessage(const ros::MessageEvent< M const > &event)
Call all registered callbacks, passing them the specified message.
void call(const ros::MessageEvent< M const > &event)
ros::MessageEvent< M const > EventType
const std::string & getName()
Get the name of this filter. For debugging use.
void setName(const std::string &name)
Set the name of this filter. For debugging use.
boost::function< void(const MConstPtr &)> Callback
CallbackHelper1Ptr addCallback(const boost::function< void(P)> &callback)
Connection registerCallback(const boost::function< void(P)> &callback)
Register a callback to be called when this filter has passed.
Convenience base-class for simple filters which output a single message.
boost::function< void(const EventType &)> EventCallback
boost::shared_ptr< M const > MConstPtr
Connection registerCallback(void(T::*callback)(P), T *t)
Register a callback to be called when this filter has passed.
Encapsulates a connection from one filter to another (or to a user-specified callback) ...
Connection registerCallback(const C &callback)
Register a callback to be called when this filter has passed.