Skip to content

Commit 894ccfd

Browse files
committed
Use BOOST_FOREACH and take publisher by const ref.
1 parent 253b71f commit 894ccfd

File tree

1 file changed

+3
-4
lines changed

1 file changed

+3
-4
lines changed

nodelet_topic_tools/include/nodelet_topic_tools/nodelet_lazy.h

+3-4
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@
4141
#include <ros/ros.h>
4242
#include <nodelet/nodelet.h>
4343
#include <image_transport/image_transport.h>
44+
#include <boost/foreach.hpp>
4445
#include <boost/thread.hpp>
4546
#include <string>
4647
#include <vector>
@@ -145,9 +146,8 @@ class NodeletLazy: public nodelet::Nodelet
145146
if (lazy_)
146147
{
147148
boost::mutex::scoped_lock lock(connection_mutex_);
148-
for (size_t i = 0; i < publishers_.size(); i++)
149+
BOOST_FOREACH (const ros::Publisher& pub, publishers_)
149150
{
150-
ros::Publisher pub = publishers_[i];
151151
if (pub.getNumSubscribers() > 0)
152152
{
153153
if (connection_status_ != SUBSCRIBED)
@@ -166,9 +166,8 @@ class NodeletLazy: public nodelet::Nodelet
166166
return;
167167
}
168168
}
169-
for (size_t i = 0; i < image_transport_publishers_.size(); i++)
169+
BOOST_FOREACH (const image_transport::Publisher& pub, image_transport_publishers_)
170170
{
171-
image_transport::Publisher pub = image_transport_publishers_[i];
172171
if (pub.getNumSubscribers() > 0)
173172
{
174173
if (connection_status_ != SUBSCRIBED)

0 commit comments

Comments
 (0)