WifiSignalSubNode.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 #include <ros/subscriber.h>
31 
32 #include <rtabmap/utilite/UStl.h>
35 
36 #include <rtabmap_ros/MapData.h>
38 
39 #include <sensor_msgs/PointCloud2.h>
40 
41 #include <pcl/point_cloud.h>
42 #include <pcl/point_types.h>
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 dBm2Quality(int dBm)
53 {
54  // dBm to Quality:
55  if(dBm <= -100)
56  return 0;
57  else if(dBm >= -50)
58  return 100;
59  else
60  return 2 * (dBm + 100);
61 }
62 
64 std::map<double, int> wifiLevels;
65 
66 void mapDataCallback(const rtabmap_ros::MapDataConstPtr & mapDataMsg)
67 {
68  ROS_INFO("Received map data!");
69 
70  rtabmap::Transform mapToOdom;
71  std::map<int, rtabmap::Transform> poses;
72  std::multimap<int, rtabmap::Link> links;
73  std::map<int, rtabmap::Signature> signatures;
74  rtabmap_ros::mapDataFromROS(*mapDataMsg, poses, links, signatures, mapToOdom);
75 
76  std::map<double, int> nodeStamps; // <stamp, id>
77  for(std::map<int, rtabmap::Signature>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
78  {
79  cv::Mat data;
80  iter->second.sensorData().uncompressDataConst(0 ,0, 0, &data);
81 
82  if(data.type() == CV_64FC1 && data.rows == 1 && data.cols == 2)
83  {
84  // format [int level, double stamp], see wifi_signal_pub_node.cpp
85  int level = data.at<double>(0);
86  double stamp = data.at<double>(1);
87  wifiLevels.insert(std::make_pair(stamp, level));
88  }
89  else if(!data.empty())
90  {
91  ROS_ERROR("Wrong user data format for wifi signal.");
92  }
93 
94  // Sort stamps by stamps->id
95  nodeStamps.insert(std::make_pair(iter->second.getStamp(), iter->first));
96  }
97 
98  if(wifiLevels.size() == 0)
99  {
100  ROS_WARN("No wifi signal detected yet in user data of map data");
101  }
102 
103  //============================
104  // Add WIFI symbols
105  //============================
106 
107  pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledWifiSignals(new pcl::PointCloud<pcl::PointXYZRGB>);
108  int id = 0;
109  for(std::map<double, int>::iterator iter=wifiLevels.begin(); iter!=wifiLevels.end(); ++iter, ++id)
110  {
111  // The Wifi value may be taken between two nodes, interpolate its position.
112  double stampWifi = iter->first;
113  std::map<double, int>::iterator previousNode = nodeStamps.lower_bound(stampWifi); // lower bound of the stamp
114  if(previousNode!=nodeStamps.end() && previousNode->first > stampWifi && previousNode != nodeStamps.begin())
115  {
116  --previousNode;
117  }
118  std::map<double, int>::iterator nextNode = nodeStamps.upper_bound(stampWifi); // upper bound of the stamp
119 
120  if(previousNode != nodeStamps.end() &&
121  nextNode != nodeStamps.end() &&
122  previousNode->second != nextNode->second &&
123  uContains(poses, previousNode->second) && uContains(poses, nextNode->second))
124  {
125  rtabmap::Transform poseA = poses.at(previousNode->second);
126  rtabmap::Transform poseB = poses.at(nextNode->second);
127  double stampA = previousNode->first;
128  double stampB = nextNode->first;
129  UASSERT(stampWifi>=stampA && stampWifi <=stampB);
130 
131  rtabmap::Transform v = poseA.inverse() * poseB;
132  double ratio = (stampWifi-stampA)/(stampB-stampA);
133 
134  v.x()*=ratio;
135  v.y()*=ratio;
136  v.z()*=ratio;
137 
138  rtabmap::Transform wifiPose = (poseA*v).translation(); // rip off the rotation
139 
140  // Make a line with points
141  int quality = dBm2Quality(iter->second)/10;
142  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
143  for(int i=0; i<10; ++i)
144  {
145  // 2 cm between each points
146  // the number of points depends on the dBm (which varies from -30 (near) to -80 (far))
147  pcl::PointXYZRGB pt;
148  pt.z = float(i+1)*0.02f;
149  if(i<quality)
150  {
151  // green
152  pt.g = 255;
153  if(i<7)
154  {
155  // yellow
156  pt.r = 255;
157  }
158  }
159  else
160  {
161  // gray
162  pt.r = pt.g = pt.b = 100;
163  }
164  cloud->push_back(pt);
165  }
166  pcl::PointXYZRGB anchor(255, 0, 0);
167  cloud->push_back(anchor);
168 
169  cloud = rtabmap::util3d::transformPointCloud(cloud, wifiPose);
170 
171  if(assembledWifiSignals->size() == 0)
172  {
173  *assembledWifiSignals = *cloud;
174  }
175  else
176  {
177  *assembledWifiSignals += *cloud;
178  }
179  }
180  }
181 
182  if(assembledWifiSignals->size())
183  {
184  sensor_msgs::PointCloud2 cloudMsg;
185  pcl::toROSMsg(*assembledWifiSignals, cloudMsg);
186  cloudMsg.header = mapDataMsg->header;
187  wifiSignalCloudPub.publish(cloudMsg);
188  }
189 }
190 
191 int main(int argc, char** argv)
192 {
193  ros::init(argc, argv, "wifi_signal_sub");
194 
195  ros::NodeHandle nh;
196  ros::NodeHandle pnh("~");
197 
198  std::string interface = "wlan0";
199  double rateHz = 0.5; // Hz
200  std::string frameId = "base_link";
201 
202  wifiSignalCloudPub = nh.advertise<sensor_msgs::PointCloud2>("wifi_signals", 1);
203  ros::Subscriber mapDataSub = nh.subscribe("/rtabmap/mapData", 1, mapDataCallback);
204 
205  ros::spin();
206 
207  return 0;
208 }
void publish(const boost::shared_ptr< M > &message) const
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
std::map< double, int > wifiLevels
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void mapDataCallback(const rtabmap_ros::MapDataConstPtr &mapDataMsg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN(...)
ROSCPP_DECL void spin(Spinner &spinner)
#define UASSERT(condition)
void mapDataFromROS(const rtabmap_ros::MapData &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, std::map< int, rtabmap::Signature > &signatures, rtabmap::Transform &mapToOdom)
#define ROS_INFO(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool uContains(const std::list< V > &list, const V &value)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
int main(int argc, char **argv)
ros::Publisher wifiSignalCloudPub
int dBm2Quality(int dBm)
Transform inverse() const
#define ROS_ERROR(...)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:04