advertisement_checker.cpp
Go to the documentation of this file.
00001 #include "image_proc/advertisement_checker.h"
00002 #include <boost/foreach.hpp>
00003 
00004 namespace image_proc {
00005 
00006 AdvertisementChecker::AdvertisementChecker(const ros::NodeHandle& nh,
00007                                            const std::string& name)
00008   : nh_(nh),
00009     name_(name)
00010 {
00011 }
00012 
00013 void AdvertisementChecker::timerCb()
00014 {
00015   ros::master::V_TopicInfo topic_info;
00016   if (!ros::master::getTopics(topic_info)) return;
00017 
00018   ros::V_string::iterator topic_it = topics_.begin();
00019   while (topic_it != topics_.end())
00020   {
00021     // Should use std::find_if
00022     bool found = false;
00023     ros::master::V_TopicInfo::iterator info_it = topic_info.begin();
00024     while (!found && info_it != topic_info.end())
00025     {
00026       found = (*topic_it == info_it->name);
00027       ++info_it;
00028     }
00029     if (found)
00030       topic_it = topics_.erase(topic_it);
00031     else
00032     {
00033       ROS_WARN_NAMED(name_, "The input topic '%s' is not yet advertised", topic_it->c_str());
00034       ++topic_it;
00035     }
00036   }
00037 
00038   if (topics_.empty())
00039     stop();
00040 }
00041 
00042 void AdvertisementChecker::start(const ros::V_string& topics, double duration)
00043 {
00044   topics_.clear();
00045   BOOST_FOREACH(const std::string& topic, topics)
00046     topics_.push_back(nh_.resolveName(topic));
00047 
00048   ros::NodeHandle nh;
00049   timer_ = nh.createWallTimer(ros::WallDuration(duration),
00050                               boost::bind(&AdvertisementChecker::timerCb, this));
00051   timerCb();
00052 }
00053 
00054 void AdvertisementChecker::stop()
00055 {
00056   timer_.stop();
00057 }
00058 
00059 } // namespace image_proc


image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Fri Jan 3 2014 11:24:35