Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef PUBLISHER_SONAR_HPP
00019 #define PUBLISHER_SONAR_HPP
00020
00021
00022
00023
00024 #include <ros/ros.h>
00025 #include <sensor_msgs/Range.h>
00026
00027 namespace naoqi
00028 {
00029 namespace publisher
00030 {
00031
00032 class SonarPublisher
00033 {
00034 public:
00035 SonarPublisher( const std::vector<std::string>& topics );
00036
00037 inline std::string topic() const
00038 {
00039 return "sonar";
00040 }
00041
00042 inline bool isInitialized() const
00043 {
00044 return is_initialized_;
00045 }
00046
00047 void publish( const std::vector<sensor_msgs::Range>& sonar_msgs );
00048
00049 void reset( ros::NodeHandle& nh );
00050
00051 inline bool isSubscribed() const
00052 {
00053 if (is_initialized_ == false) return false;
00054 for(std::vector<ros::Publisher>::const_iterator it = pubs_.begin(); it != pubs_.end(); ++it)
00055 if (it->getNumSubscribers())
00056 return true;
00057 return false;
00058 }
00059
00060 private:
00061 std::vector<std::string> topics_;
00062 std::vector<ros::Publisher> pubs_;
00063 bool is_initialized_;
00064
00065 };
00066
00067 }
00068 }
00069
00070 #endif