Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016 #include <ros/ros.h>
00017 #include <heatmap/wifi_signal.h>
00018 #include <heatmap/signal_service.h>
00019 #include <heatmap/iwlib.h>
00020
00021 namespace heatmap
00022 {
00029 class Signal
00030 {
00031 private:
00032 int wifi_skfd;
00033 iwreq wifi_wrq;
00034 wireless_info *wifi_info;
00035 const char *wifi_dev;
00036 heatmap::wifi_signal wifi_sig;
00037 ros::NodeHandle nh;
00038
00043 wifi_signal getSignal()
00044 {
00045 if (iw_get_stats(wifi_skfd, wifi_dev, &(wifi_info->stats), &wifi_info->range, wifi_info->has_range) >= 0)
00046 wifi_info->has_stats = 1;
00047 int quality = wifi_info->stats.qual.qual;
00048
00049 if (iw_get_ext(wifi_skfd, wifi_dev, SIOCGIWRATE, &wifi_wrq) >= 0)
00050 {
00051 wifi_info->has_bitrate = 1;
00052 memcpy(&(wifi_info->bitrate), &(wifi_wrq.u.bitrate), sizeof(wifi_info->bitrate));
00053 }
00054
00055 wifi_sig.link_quality = quality;
00056
00057 return wifi_sig;
00058 }
00059
00064 wifi_signal getSignalAverage()
00065 {
00066 const int measurements = 5;
00067 heatmap::wifi_signal avg_sig, sig;
00068 int qual_sum = 0;
00069
00070 avg_sig = wifi_sig;
00071
00072 for (int i = 0; i < measurements; i++)
00073 {
00074 sig = getSignal();
00075 qual_sum += sig.link_quality;
00076 ros::Duration(0.02).sleep();
00077 }
00078 avg_sig.link_quality = qual_sum / measurements;
00079
00080 return avg_sig;
00081 }
00082
00083 bool srvGetSignal(heatmap::signal_service::Request &req, heatmap::signal_service::Response &res)
00084 {
00085 res.signal = getSignalAverage();
00086
00087 return true;
00088 }
00089
00093 bool openDevice()
00094 {
00095 if ((wifi_skfd = iw_sockets_open()) < 0)
00096 {
00097 ROS_ERROR("socket error");
00098 return false;
00099 }
00100
00101 if (iw_get_basic_config(wifi_skfd, wifi_dev, &(wifi_info->b)) < 0)
00102 {
00103
00104
00105 struct ifreq ifr;
00106
00107 strncpy(ifr.ifr_name, wifi_dev, IFNAMSIZ);
00108 int ret = ioctl(wifi_skfd, SIOCGIFFLAGS, &ifr);
00109 if (ret < 0)
00110 {
00111 ROS_ERROR("device doesn't exist");
00112 return false;
00113 }
00114 else
00115 {
00116 ROS_ERROR("operation not supported");
00117 return false;
00118 }
00119 }
00120
00121 wifi_sig.essid = wifi_info->b.essid;
00122
00123 if (iw_get_range_info(wifi_skfd, wifi_dev, &(wifi_info->range)) >= 0)
00124 wifi_info->has_range = 1;
00125
00126 wifi_sig.link_quality_max = wifi_info->range.max_qual.qual;
00127
00128 return true;
00129
00130 }
00131
00132 public:
00133 Signal(const char* wlan_dev) :
00134 nh()
00135 {
00136 wifi_dev = wlan_dev;
00137 wifi_info = new wireless_info();
00138 ros::Rate loop_rate(10.0);
00139
00140 if(!openDevice())
00141 {
00142 return;
00143 }
00144
00145 ros::Publisher signal_pub = nh.advertise<heatmap::wifi_signal>("signal", 1000);
00146 ros::ServiceServer service = nh.advertiseService("get_wifi_signal", &Signal::srvGetSignal, this);
00147
00148 while(nh.ok())
00149 {
00150 wifi_signal sig = getSignal();
00151 signal_pub.publish(sig);
00152 loop_rate.sleep();
00153 ros::spinOnce();
00154 }
00155 }
00156
00157 ~Signal()
00158 {
00159 delete wifi_info;
00160 }
00161 };
00162 }
00163
00164 int main(int argc, char** argv)
00165 {
00166 if (argc < 2)
00167 {
00168 ROS_ERROR("You must specify the wlan device name. (e.g. wlan0)");
00169 return -1;
00170 }
00171 char* wlan_dev = argv[1];
00172
00173 ros::init(argc, argv, "signal_meter");
00174
00175 heatmap::Signal signal(wlan_dev);
00176
00177 return 0;
00178 }