WifiSignalSubNode.cpp
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 #include <ros/ros.h>
00029 #include <ros/publisher.h>
00030 #include <ros/subscriber.h>
00031 
00032 #include <rtabmap/utilite/UStl.h>
00033 #include <rtabmap/utilite/ULogger.h>
00034 #include <rtabmap/core/util3d_transforms.h>
00035 
00036 #include <rtabmap_ros/MapData.h>
00037 #include <rtabmap_ros/MsgConversion.h>
00038 
00039 #include <sensor_msgs/PointCloud2.h>
00040 
00041 #include <pcl/point_cloud.h>
00042 #include <pcl/point_types.h>
00043 #include <pcl_conversions/pcl_conversions.h>
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 dBm2Quality(int dBm)
00053 {
00054         // dBm to Quality:
00055     if(dBm <= -100)
00056         return 0;
00057     else if(dBm >= -50)
00058         return 100;
00059     else
00060         return 2 * (dBm + 100);
00061 }
00062 
00063 ros::Publisher wifiSignalCloudPub;
00064 std::map<double, int> wifiLevels;
00065 
00066 void mapDataCallback(const rtabmap_ros::MapDataConstPtr & mapDataMsg)
00067 {
00068         ROS_INFO("Received map data!");
00069 
00070         rtabmap::Transform mapToOdom;
00071         std::map<int, rtabmap::Transform> poses;
00072         std::multimap<int, rtabmap::Link> links;
00073         std::map<int, rtabmap::Signature> signatures;
00074         rtabmap_ros::mapDataFromROS(*mapDataMsg, poses, links, signatures, mapToOdom);
00075 
00076         std::map<double, int> nodeStamps; // <stamp, id>
00077         for(std::map<int, rtabmap::Signature>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
00078         {
00079                 cv::Mat data;
00080                 iter->second.sensorData().uncompressDataConst(0 ,0, 0, &data);
00081 
00082                 if(data.type() == CV_64FC1 && data.rows == 1 && data.cols == 2)
00083                 {
00084                         // format [int level, double stamp], see wifi_signal_pub_node.cpp
00085                         int level = data.at<double>(0);
00086                         double stamp = data.at<double>(1);
00087                         wifiLevels.insert(std::make_pair(stamp, level));
00088                 }
00089                 else if(!data.empty())
00090                 {
00091                         ROS_ERROR("Wrong user data format for wifi signal.");
00092                 }
00093 
00094                 // Sort stamps by stamps->id
00095                 nodeStamps.insert(std::make_pair(iter->second.getStamp(), iter->first));
00096         }
00097 
00098         if(wifiLevels.size() == 0)
00099         {
00100                 ROS_WARN("No wifi signal detected yet in user data of map data");
00101         }
00102 
00103         //============================
00104         // Add WIFI symbols
00105         //============================
00106 
00107         pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledWifiSignals(new pcl::PointCloud<pcl::PointXYZRGB>);
00108         int id = 0;
00109         for(std::map<double, int>::iterator iter=wifiLevels.begin(); iter!=wifiLevels.end(); ++iter, ++id)
00110         {
00111                 // The Wifi value may be taken between two nodes, interpolate its position.
00112                 double stampWifi = iter->first;
00113                 std::map<double, int>::iterator previousNode = nodeStamps.lower_bound(stampWifi); // lower bound of the stamp
00114                 if(previousNode!=nodeStamps.end() && previousNode->first > stampWifi && previousNode != nodeStamps.begin())
00115                 {
00116                         --previousNode;
00117                 }
00118                 std::map<double, int>::iterator nextNode = nodeStamps.upper_bound(stampWifi); // upper bound of the stamp
00119 
00120                 if(previousNode != nodeStamps.end() &&
00121                    nextNode != nodeStamps.end() &&
00122                    previousNode->second != nextNode->second &&
00123                    uContains(poses, previousNode->second) && uContains(poses, nextNode->second))
00124                 {
00125                         rtabmap::Transform poseA = poses.at(previousNode->second);
00126                         rtabmap::Transform poseB = poses.at(nextNode->second);
00127                         double stampA = previousNode->first;
00128                         double stampB = nextNode->first;
00129                         UASSERT(stampWifi>=stampA && stampWifi <=stampB);
00130 
00131                         rtabmap::Transform v = poseA.inverse() * poseB;
00132                         double ratio = (stampWifi-stampA)/(stampB-stampA);
00133 
00134                         v.x()*=ratio;
00135                         v.y()*=ratio;
00136                         v.z()*=ratio;
00137 
00138                         rtabmap::Transform wifiPose = (poseA*v).translation(); // rip off the rotation
00139 
00140                         // Make a line with points
00141                         int quality = dBm2Quality(iter->second)/10;
00142                         pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
00143                         for(int i=0; i<10; ++i)
00144                         {
00145                                 // 2 cm between each points
00146                                 // the number of points depends on the dBm (which varies from -30 (near) to -80 (far))
00147                                 pcl::PointXYZRGB pt;
00148                                 pt.z = float(i+1)*0.02f;
00149                                 if(i<quality)
00150                                 {
00151                                         // green
00152                                         pt.g = 255;
00153                                         if(i<7)
00154                                         {
00155                                                 // yellow
00156                                                 pt.r = 255;
00157                                         }
00158                                 }
00159                                 else
00160                                 {
00161                                         // gray
00162                                         pt.r = pt.g = pt.b = 100;
00163                                 }
00164                                 cloud->push_back(pt);
00165                         }
00166                         pcl::PointXYZRGB anchor(255, 0, 0);
00167                         cloud->push_back(anchor);
00168 
00169                         cloud = rtabmap::util3d::transformPointCloud(cloud, wifiPose);
00170 
00171                         if(assembledWifiSignals->size() == 0)
00172                         {
00173                                 *assembledWifiSignals = *cloud;
00174                         }
00175                         else
00176                         {
00177                                 *assembledWifiSignals += *cloud;
00178                         }
00179                 }
00180         }
00181 
00182         if(assembledWifiSignals->size())
00183         {
00184                 sensor_msgs::PointCloud2 cloudMsg;
00185                 pcl::toROSMsg(*assembledWifiSignals, cloudMsg);
00186                 cloudMsg.header = mapDataMsg->header;
00187                 wifiSignalCloudPub.publish(cloudMsg);
00188         }
00189 }
00190 
00191 int main(int argc, char** argv)
00192 {
00193         ros::init(argc, argv, "wifi_signal_sub");
00194 
00195         ros::NodeHandle nh;
00196         ros::NodeHandle pnh("~");
00197 
00198         std::string interface = "wlan0";
00199         double rateHz = 0.5; // Hz
00200         std::string frameId = "base_link";
00201 
00202         wifiSignalCloudPub = nh.advertise<sensor_msgs::PointCloud2>("wifi_signals", 1);
00203         ros::Subscriber mapDataSub = nh.subscribe("/rtabmap/mapData", 1, mapDataCallback);
00204 
00205         ros::spin();
00206 
00207         return 0;
00208 }


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:30:49