18 #ifndef PUBLISHER_SONAR_HPP 19 #define PUBLISHER_SONAR_HPP 25 #include <sensor_msgs/Range.h> 37 inline std::string
topic()
const 47 void publish(
const std::vector<sensor_msgs::Range>& sonar_msgs );
54 for(std::vector<ros::Publisher>::const_iterator it =
pubs_.begin(); it !=
pubs_.end(); ++it)
55 if (it->getNumSubscribers())
62 std::vector<ros::Publisher>
pubs_;
bool isSubscribed() const
std::vector< ros::Publisher > pubs_
void reset(ros::NodeHandle &nh)
bool isInitialized() const
std::string topic() const
SonarPublisher(const std::vector< std::string > &topics)
void publish(const std::vector< sensor_msgs::Range > &sonar_msgs)
std::vector< std::string > topics_