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
00019
00020
00021 #include "sonar.hpp"
00022
00023 namespace naoqi
00024 {
00025 namespace publisher
00026 {
00027
00028 SonarPublisher::SonarPublisher( const std::vector<std::string>& topics )
00029 : is_initialized_(false),
00030 topics_(topics)
00031 {
00032 }
00033
00034 void SonarPublisher::publish( const std::vector<sensor_msgs::Range>& sonar_msgs )
00035 {
00036 if ( pubs_.size() != sonar_msgs.size() )
00037 {
00038 std::cerr << "Incorrect number of sonar range messages in sonar publisher. " << sonar_msgs.size() << "/" << pubs_.size() << std::endl;
00039 return;
00040 }
00041
00042 for( size_t i=0; i<sonar_msgs.size(); ++i)
00043 {
00044 pubs_[i].publish( sonar_msgs[i] );
00045 }
00046 }
00047
00048 void SonarPublisher::reset( ros::NodeHandle& nh )
00049 {
00050 pubs_ = std::vector<ros::Publisher>();
00051 for( size_t i=0; i<topics_.size(); ++i)
00052 {
00053 pubs_.push_back( nh.advertise<sensor_msgs::Range>(topics_[i], 1) );
00054 }
00055
00056 is_initialized_ = true;
00057 }
00058
00059 }
00060 }