WifiThread.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef WIFITHREAD_H_
00029 #define WIFITHREAD_H_
00030 
00031 #ifdef _WIN32
00032         #ifndef UNICODE
00033         #define UNICODE
00034         #endif
00035 
00036         #include <windows.h>
00037         #include <wlanapi.h>
00038         #include <Windot11.h>           // for DOT11_SSID struct
00039         #include <objbase.h>
00040         #include <wtypes.h>
00041 
00042         #include <stdio.h>
00043         #include <stdlib.h>
00044 
00045         // Need to link with Wlanapi.lib and Ole32.lib
00046         #pragma comment(lib, "wlanapi.lib")
00047         #pragma comment(lib, "ole32.lib")
00048 #elif __APPLE__
00049 #include "WifiOSX.h"
00050 #else
00051         #include <sys/socket.h>
00052         #include <linux/wireless.h>
00053         #include <sys/ioctl.h>
00054 #endif
00055 #include <rtabmap/core/UserDataEvent.h>
00056 #include <rtabmap/utilite/UTimer.h>
00057 
00058 // A percentage value that represents the signal quality
00059 // of the network. WLAN_SIGNAL_QUALITY is of type ULONG.
00060 // This member contains a value between 0 and 100. A value
00061 // of 0 implies an actual RSSI signal strength of -100 dbm.
00062 // A value of 100 implies an actual RSSI signal strength of -50 dbm.
00063 // You can calculate the RSSI signal strength value for wlanSignalQuality
00064 // values between 1 and 99 using linear interpolation.
00065 inline int quality2dBm(int quality)
00066 {
00067         // Quality to dBm:
00068         if(quality <= 0)
00069                 return -100;
00070         else if(quality >= 100)
00071                 return -50;
00072         else
00073                 return (quality / 2) - 100;
00074 }
00075 
00076 
00077 class WifiThread : public UThread, public UEventsSender
00078 {
00079 public:
00080         WifiThread(const std::string & interfaceName, float rate = 0.5) :
00081                 interfaceName_(interfaceName),
00082                 rate_(rate)
00083         {}
00084         virtual ~WifiThread() {}
00085 
00086 private:
00087         virtual void mainLoop()
00088         {
00089                 uSleep(1000/rate_);
00090                 if(!this->isKilled())
00091                 {
00092                         int dBm = 0;
00093 #ifdef _WIN32
00094                         //From https://msdn.microsoft.com/en-us/library/windows/desktop/ms706765(v=vs.85).aspx
00095                         // Declare and initialize variables.
00096                         HANDLE hClient = NULL;
00097                         DWORD dwMaxClient = 2;      //
00098                         DWORD dwCurVersion = 0;
00099                         DWORD dwResult = 0;
00100 
00101                         // variables used for WlanEnumInterfaces
00102                         PWLAN_INTERFACE_INFO_LIST pIfList = NULL;
00103                         PWLAN_INTERFACE_INFO pIfInfo = NULL;
00104 
00105                         // variables used for WlanQueryInterfaces for opcode = wlan_intf_opcode_current_connection
00106                         PWLAN_CONNECTION_ATTRIBUTES pConnectInfo = NULL;
00107                         DWORD connectInfoSize = sizeof(WLAN_CONNECTION_ATTRIBUTES);
00108                         WLAN_OPCODE_VALUE_TYPE opCode = wlan_opcode_value_type_invalid;
00109 
00110                         dwResult = WlanOpenHandle(dwMaxClient, NULL, &dwCurVersion, &hClient);
00111                         if (dwResult != ERROR_SUCCESS)
00112                         {
00113                                 UERROR("WlanOpenHandle failed with error: %u\n", dwResult);
00114                         }
00115                         else
00116                         {
00117                                 dwResult = WlanEnumInterfaces(hClient, NULL, &pIfList);
00118                                 if (dwResult != ERROR_SUCCESS)
00119                                 {
00120                                         UERROR("WlanEnumInterfaces failed with error: %u\n", dwResult);
00121                                 }
00122                                 else
00123                                 {
00124                                         // take the first interface found
00125                                         int i = 0;
00126                                         pIfInfo = (WLAN_INTERFACE_INFO *) & pIfList->InterfaceInfo[i];
00127                                         if(pIfInfo->isState == wlan_interface_state_connected)
00128                                         {
00129                                                 dwResult = WlanQueryInterface(hClient,
00130                                                                                                           &pIfInfo->InterfaceGuid,
00131                                                                                                           wlan_intf_opcode_current_connection,
00132                                                                                                           NULL,
00133                                                                                                           &connectInfoSize,
00134                                                                                                           (PVOID *) &pConnectInfo,
00135                                                                                                           &opCode);
00136 
00137                                                 if (dwResult != ERROR_SUCCESS)
00138                                                 {
00139                                                         UERROR("WlanQueryInterface failed with error: %u\n", dwResult);
00140                                                 }
00141                                                 else
00142                                                 {
00143                                                         int quality = pConnectInfo->wlanAssociationAttributes.wlanSignalQuality;
00144                                                         dBm = quality2dBm(quality);
00145                                                 }
00146                                         }
00147                                         else
00148                                         {
00149                                                 UERROR("Interface not connected!");
00150                                         }
00151                                 }
00152                         }
00153                         if (pConnectInfo != NULL)
00154                         {
00155                                 WlanFreeMemory(pConnectInfo);
00156                                 pConnectInfo = NULL;
00157                         }
00158 
00159                         if (pIfList != NULL)
00160                         {
00161                                 WlanFreeMemory(pIfList);
00162                                 pIfList = NULL;
00163                         }
00164 #elif __APPLE__
00165                         dBm = getRssi(interfaceName_);
00166 #else
00167                         // Code inspired from http://blog.ajhodges.com/2011/10/using-ioctl-to-gather-wifi-information.html
00168 
00169                         //have to use a socket for ioctl
00170                         int sockfd;
00171                         /* Any old socket will do, and a datagram socket is pretty cheap */
00172                         if((sockfd = socket(AF_INET, SOCK_DGRAM, 0)) == -1) {
00173                                 UERROR("Could not create simple datagram socket");
00174                                 return;
00175                         }
00176 
00177                         struct iwreq req;
00178                         struct iw_statistics stats;
00179 
00180                         strncpy(req.ifr_name, interfaceName_.c_str(), IFNAMSIZ);
00181 
00182                         //make room for the iw_statistics object
00183                         req.u.data.pointer = (caddr_t) &stats;
00184                         req.u.data.length = sizeof(stats);
00185                         // clear updated flag
00186                         req.u.data.flags = 1;
00187 
00188                         //this will gather the signal strength
00189                         if(ioctl(sockfd, SIOCGIWSTATS, &req) == -1)
00190                         {
00191                                 //die with error, invalid interface
00192                                 UERROR("Invalid interface (\"%s\"). Tip: Try with sudo!", interfaceName_.c_str());
00193                         }
00194                         else if(((iw_statistics *)req.u.data.pointer)->qual.updated & IW_QUAL_DBM)
00195                         {
00196                                 //signal is measured in dBm and is valid for us to use
00197                                 dBm = ((iw_statistics *)req.u.data.pointer)->qual.level - 256;
00198                         }
00199                         else
00200                         {
00201                                 UERROR("Could not get signal level.");
00202                         }
00203 
00204                         close(sockfd);
00205 #endif
00206                         if(dBm != 0)
00207                         {
00208                                 double stamp = UTimer::now();
00209 
00210                                 // Create user data [level, stamp] with the value and a timestamp
00211                                 cv::Mat data(1, 2, CV_64FC1);
00212                                 data.at<double>(0) = double(dBm);
00213                                 data.at<double>(1) = stamp;
00214                                 this->post(new UserDataEvent(data));
00215                                 //UWARN("posting level %d dBm", dBm);
00216                         }
00217                 }
00218         }
00219 
00220 private:
00221         std::string interfaceName_;
00222         float rate_;
00223 };
00224 
00225 #endif /* WIFITHREAD_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:28