WifiSignalPubNode.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <ros/ros.h>
29 #include <ros/publisher.h>
30 
31 #include <sys/socket.h>
32 #include <linux/wireless.h>
33 #include <sys/ioctl.h>
34 
36 #include <rtabmap_ros/UserData.h>
37 
38 // Demo:
39 // $ roslaunch freenect_launch freenect.launch depth_registration:=true
40 // $ roslaunch rtabmap_ros rtabmap.launch rtabmap_args:="--delete_db_on_start" user_data_async_topic:=/wifi_signal rtabmapviz:=false rviz:=true
41 // $ rosrun rtabmap_ros wifi_signal_pub interface:="wlan0"
42 // $ rosrun rtabmap_ros wifi_signal_sub
43 // In RVIZ add PointCloud2 "wifi_signals"
44 
45 // A percentage value that represents the signal quality
46 // of the network. WLAN_SIGNAL_QUALITY is of type ULONG.
47 // This member contains a value between 0 and 100. A value
48 // of 0 implies an actual RSSI signal strength of -100 dbm.
49 // A value of 100 implies an actual RSSI signal strength of -50 dbm.
50 // You can calculate the RSSI signal strength value for wlanSignalQuality
51 // values between 1 and 99 using linear interpolation.
52 inline int quality2dBm(int quality)
53 {
54  // Quality to dBm:
55  if(quality <= 0)
56  return -100;
57  else if(quality >= 100)
58  return -50;
59  else
60  return (quality / 2) - 100;
61 }
62 
63 int main(int argc, char** argv)
64 {
65  ros::init(argc, argv, "wifi_signal_pub");
66 
67  ros::NodeHandle nh;
68  ros::NodeHandle pnh("~");
69 
70  std::string interface = "wlan0";
71  double rateHz = 0.5; // Hz
72  std::string frameId = "base_link";
73 
74  pnh.param("interface", interface, interface);
75  pnh.param("rate", rateHz, rateHz);
76  pnh.param("frame_id", frameId, frameId);
77 
78  ros::Rate rate(rateHz);
79 
80  ros::Publisher wifiPub = nh.advertise<rtabmap_ros::UserData>("wifi_signal", 1);
81 
82  while(ros::ok())
83  {
84  int dBm = 0;
85 
86  // Code inspired from http://blog.ajhodges.com/2011/10/using-ioctl-to-gather-wifi-information.html
87 
88  //have to use a socket for ioctl
89  int sockfd;
90  /* Any old socket will do, and a datagram socket is pretty cheap */
91  if((sockfd = socket(AF_INET, SOCK_DGRAM, 0)) == -1) {
92  ROS_ERROR("Could not create simple datagram socket");
93  return -1;
94  }
95 
96  struct iwreq req;
97  struct iw_statistics stats;
98 
99  strncpy(req.ifr_name, interface.c_str(), IFNAMSIZ);
100 
101  //make room for the iw_statistics object
102  req.u.data.pointer = (caddr_t) &stats;
103  req.u.data.length = sizeof(stats);
104  // clear updated flag
105  req.u.data.flags = 1;
106 
107  //this will gather the signal strength
108  if(ioctl(sockfd, SIOCGIWSTATS, &req) == -1)
109  {
110  //die with error, invalid interface
111  ROS_ERROR("Invalid interface (\"%s\"). Tip: Try with sudo!", interface.c_str());
112  }
113  else if(((iw_statistics *)req.u.data.pointer)->qual.updated & IW_QUAL_DBM)
114  {
115  //signal is measured in dBm and is valid for us to use
116  dBm = ((iw_statistics *)req.u.data.pointer)->qual.level - 256;
117  }
118  else
119  {
120  ROS_ERROR("Could not get signal level.");
121  }
122 
123  close(sockfd);
124 
125  if(dBm != 0)
126  {
128 
129  // Create user data [level] with the value
130  cv::Mat data(1, 2, CV_64FC1);
131  data.at<double>(0) = double(dBm);
132 
133  // we should set stamp in data to be able to
134  // retrieve it from rtabmap map data to get precise
135  // position in the graph afterward
136  data.at<double>(1) = stamp.toSec();
137 
138  rtabmap_ros::UserData dataMsg;
139  dataMsg.header.frame_id = frameId;
140  dataMsg.header.stamp = stamp;
141  rtabmap_ros::userDataToROS(data, dataMsg, false);
142  wifiPub.publish<rtabmap_ros::UserData>(dataMsg);
143  }
144  ros::spinOnce();
145  rate.sleep();
146  }
147 
148  return 0;
149 }
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int quality2dBm(int quality)
bool sleep()
string frameId
Definition: patrol.py:11
static Time now()
void userDataToROS(const cv::Mat &data, rtabmap_ros::UserData &dataMsg, bool compress)
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19