Go to the documentation of this file.
35 #ifndef MESSAGE_FILTERS_TIME_SEQUENCER_H
36 #define MESSAGE_FILTERS_TIME_SEQUENCER_H
75 class TimeSequencer :
public SimpleFilter<M>
140 if (mt::TimeStamp<M>::value(*evt.getMessage()) <
last_time_)
172 typedef std::multiset<EventType, MessageSort>
S_Message;
173 typedef std::vector<EventType>
V_Message;
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)
TimeSequencer(F &f, ros::Duration delay, ros::Duration update_rate, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle())
Constructor.
ros::SteadyTimer update_timer_
bool operator()(const EventType &lhs, const EventType &rhs) const
void connectInput(F &f)
Connect this filter's input to another filter's output.
ros::MessageEvent< M const > EventType
boost::function< void(const EventType &)> EventCallback
void cb(const EventType &evt)
boost::shared_ptr< M const > MConstPtr
ros::Duration update_rate_
SteadyTimer createSteadyTimer(SteadyTimerOptions &ops) const
Connection incoming_connection_
boost::mutex messages_mutex_
std::multiset< EventType, MessageSort > S_Message
boost::shared_ptr< M > getMessage() const
void update(const ros::SteadyTimerEvent &)
void signalMessage(const MConstPtr &msg)
Call all registered callbacks, passing them the specified message.
std::vector< EventType > V_Message
void add(const EventType &evt)
void disconnect()
disconnects this connection
message_filters
Author(s): Josh Faust, Vijay Pradeep, Dirk Thomas
, Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:54