Go to the documentation of this file.
18 #ifndef ROS_PUBQUEUE_H
19 #define ROS_PUBQUEUE_H
21 #include <boost/thread.hpp>
22 #include <boost/bind.hpp>
66 boost::function<
void()> notify_func) :
88 els.push_back(
queue_->front());
117 std::vector<boost::shared_ptr<PubMessagePair<T> > > els;
123 (*it)->pub_.publish((*it)->msg_);
148 boost::function<void()>
f = boost::bind(&PubMultiQueue::serviceFunc<T>,
this, pq);
160 for(std::list<boost::function<
void()> >::iterator it =
service_funcs_.begin();
void push(T &msg, ros::Publisher &pub)
Push a new message onto the queue.
boost::mutex service_funcs_lock_
Mutex to lock access to service_funcs_.
boost::shared_ptr< boost::mutex > queue_lock_
Mutex to control access to the queue.
void notifyServiceThread()
Wake up the queue serive thread (e.g., after having pushed a message onto one of the queues).
boost::thread service_thread_
If started, the thread that will call the service functions.
void spin()
Service all queues indefinitely, waiting on a condition variable in between cycles.
void serviceFunc(boost::shared_ptr< PubQueue< T > > pq)
Service a given queue by popping outgoing message off it and publishing them.
bool service_thread_running_
Boolean flag to shutdown the service thread if PubMultiQueue is destructed.
QueuePtr queue_
Our queue of outgoing messages.
PubQueue(QueuePtr queue, boost::shared_ptr< boost::mutex > queue_lock, boost::function< void()> notify_func)
PubMessagePair(T &msg, ros::Publisher &pub)
ros::Publisher pub_
The publisher to use to publish the message.
void pop(std::vector< boost::shared_ptr< PubMessagePair< T > > > &els)
Pop all waiting messages off the queue.
boost::shared_ptr< PubQueue< T > > addPub()
Add a new queue. Call this once for each published topic (or at least each type of publish message).
boost::shared_ptr< std::deque< boost::shared_ptr< PubMessagePair< T > > > > QueuePtr
Container for a (ROS publisher, outgoing message) pair. We'll have queues of these....
void startServiceThread()
Start a thread to call spin().
A collection of PubQueue objects, potentially of different types. This class is the programmer's inte...
boost::function< void()> notify_func_
Function that will be called when a new message is pushed on.
boost::shared_ptr< PubQueue< T > > Ptr
boost::condition_variable service_cond_var_
Condition variable used to block and resume service_thread_.
std::list< boost::function< void()> > service_funcs_
List of functions to be called to service our queues.
boost::mutex service_cond_var_lock_
Mutex to accompany service_cond_var_.
A queue of outgoing messages. Instead of calling publish() directly, you can push() messages here to ...
void spinOnce()
Service each queue one time.
T msg_
The outgoing message.
gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55