35 #ifndef MESSAGE_FILTERS_TIME_SEQUENCER_H 36 #define MESSAGE_FILTERS_TIME_SEQUENCER_H 135 void add(
const EventType& evt)
156 void add(
const MConstPtr& msg)
166 bool operator()(
const EventType& lhs,
const EventType& rhs)
const 172 typedef std::multiset<EventType, MessageSort>
S_Message;
175 void cb(
const EventType& evt)
196 to_call.push_back(e);
207 typename V_Message::iterator it = to_call.begin();
208 typename V_Message::iterator end = to_call.end();
209 for (; it != end; ++it)
Sequences messages based on the timestamp of their header.
std::vector< EventType > V_Message
void signalMessage(const MConstPtr &msg)
Call all registered callbacks, passing them the specified message.
void cb(const EventType &evt)
TimeSequencer(F &f, ros::Duration delay, ros::Duration update_rate, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle())
Constructor.
bool operator()(const EventType &lhs, const EventType &rhs) const
TimeSequencer(ros::Duration delay, ros::Duration update_rate, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle())
Constructor.
void add(const EventType &evt)
void disconnect()
disconnects this connection
boost::shared_ptr< M const > MConstPtr
void add(const MConstPtr &msg)
Manually add a message to the cache.
boost::mutex messages_mutex_
ros::Duration update_rate_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
std::multiset< EventType, MessageSort > S_Message
void update(const ros::TimerEvent &)
Convenience base-class for simple filters which output a single message.
boost::function< void(const EventType &)> EventCallback
void connectInput(F &f)
Connect this filter's input to another filter's output.
Encapsulates a connection from one filter to another (or to a user-specified callback) ...
Connection incoming_connection_
ros::MessageEvent< M const > EventType
boost::shared_ptr< M > getMessage() const