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 #include <ros/ros.h> 00029 #include <ros/publisher.h> 00030 00031 #include <sys/socket.h> 00032 #include <linux/wireless.h> 00033 #include <sys/ioctl.h> 00034 00035 #include <rtabmap_ros/MsgConversion.h> 00036 #include <rtabmap_ros/UserData.h> 00037 00038 // Demo: 00039 // $ roslaunch freenect_launch freenect.launch depth_registration:=true 00040 // $ roslaunch rtabmap_ros rtabmap.launch rtabmap_args:="--delete_db_on_start" user_data_async_topic:=/wifi_signal rtabmapviz:=false rviz:=true 00041 // $ rosrun rtabmap_ros wifi_signal_pub interface:="wlan0" 00042 // $ rosrun rtabmap_ros wifi_signal_sub 00043 // In RVIZ add PointCloud2 "wifi_signals" 00044 00045 // A percentage value that represents the signal quality 00046 // of the network. WLAN_SIGNAL_QUALITY is of type ULONG. 00047 // This member contains a value between 0 and 100. A value 00048 // of 0 implies an actual RSSI signal strength of -100 dbm. 00049 // A value of 100 implies an actual RSSI signal strength of -50 dbm. 00050 // You can calculate the RSSI signal strength value for wlanSignalQuality 00051 // values between 1 and 99 using linear interpolation. 00052 inline int quality2dBm(int quality) 00053 { 00054 // Quality to dBm: 00055 if(quality <= 0) 00056 return -100; 00057 else if(quality >= 100) 00058 return -50; 00059 else 00060 return (quality / 2) - 100; 00061 } 00062 00063 int main(int argc, char** argv) 00064 { 00065 ros::init(argc, argv, "wifi_signal_pub"); 00066 00067 ros::NodeHandle nh; 00068 ros::NodeHandle pnh("~"); 00069 00070 std::string interface = "wlan0"; 00071 double rateHz = 0.5; // Hz 00072 std::string frameId = "base_link"; 00073 00074 pnh.param("interface", interface, interface); 00075 pnh.param("rate", rateHz, rateHz); 00076 pnh.param("frame_id", frameId, frameId); 00077 00078 ros::Rate rate(rateHz); 00079 00080 ros::Publisher wifiPub = nh.advertise<rtabmap_ros::UserData>("wifi_signal", 1); 00081 00082 while(ros::ok()) 00083 { 00084 int dBm = 0; 00085 00086 // Code inspired from http://blog.ajhodges.com/2011/10/using-ioctl-to-gather-wifi-information.html 00087 00088 //have to use a socket for ioctl 00089 int sockfd; 00090 /* Any old socket will do, and a datagram socket is pretty cheap */ 00091 if((sockfd = socket(AF_INET, SOCK_DGRAM, 0)) == -1) { 00092 ROS_ERROR("Could not create simple datagram socket"); 00093 return -1; 00094 } 00095 00096 struct iwreq req; 00097 struct iw_statistics stats; 00098 00099 strncpy(req.ifr_name, interface.c_str(), IFNAMSIZ); 00100 00101 //make room for the iw_statistics object 00102 req.u.data.pointer = (caddr_t) &stats; 00103 req.u.data.length = sizeof(stats); 00104 // clear updated flag 00105 req.u.data.flags = 1; 00106 00107 //this will gather the signal strength 00108 if(ioctl(sockfd, SIOCGIWSTATS, &req) == -1) 00109 { 00110 //die with error, invalid interface 00111 ROS_ERROR("Invalid interface (\"%s\"). Tip: Try with sudo!", interface.c_str()); 00112 } 00113 else if(((iw_statistics *)req.u.data.pointer)->qual.updated & IW_QUAL_DBM) 00114 { 00115 //signal is measured in dBm and is valid for us to use 00116 dBm = ((iw_statistics *)req.u.data.pointer)->qual.level - 256; 00117 } 00118 else 00119 { 00120 ROS_ERROR("Could not get signal level."); 00121 } 00122 00123 close(sockfd); 00124 00125 if(dBm != 0) 00126 { 00127 ros::Time stamp = ros::Time::now(); 00128 00129 // Create user data [level] with the value 00130 cv::Mat data(1, 2, CV_64FC1); 00131 data.at<double>(0) = double(dBm); 00132 00133 // we should set stamp in data to be able to 00134 // retrieve it from rtabmap map data to get precise 00135 // position in the graph afterward 00136 data.at<double>(1) = stamp.toSec(); 00137 00138 rtabmap_ros::UserData dataMsg; 00139 dataMsg.header.frame_id = frameId; 00140 dataMsg.header.stamp = stamp; 00141 rtabmap_ros::userDataToROS(data, dataMsg, false); 00142 wifiPub.publish<rtabmap_ros::UserData>(dataMsg); 00143 } 00144 ros::spinOnce(); 00145 rate.sleep(); 00146 } 00147 00148 return 0; 00149 }