MapBuilderWifi.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 MAPBUILDERWIFI_H_
00029 #define MAPBUILDERWIFI_H_
00030 
00031 #include "MapBuilder.h"
00032 #include "rtabmap/core/UserDataEvent.h"
00033 
00034 using namespace rtabmap;
00035 
00036 // A percentage value that represents the signal quality
00037 // of the network. WLAN_SIGNAL_QUALITY is of type ULONG.
00038 // This member contains a value between 0 and 100. A value
00039 // of 0 implies an actual RSSI signal strength of -100 dbm.
00040 // A value of 100 implies an actual RSSI signal strength of -50 dbm.
00041 // You can calculate the RSSI signal strength value for wlanSignalQuality
00042 // values between 1 and 99 using linear interpolation.
00043 inline int dBm2Quality(int dBm)
00044 {
00045         // dBm to Quality:
00046     if(dBm <= -100)
00047         return 0;
00048     else if(dBm >= -50)
00049         return 100;
00050     else
00051         return 2 * (dBm + 100);
00052 }
00053 
00054 class MapBuilderWifi : public MapBuilder
00055 {
00056         Q_OBJECT
00057 public:
00058         // Camera ownership is not transferred!
00059         MapBuilderWifi(CameraThread * camera = 0) :
00060                 MapBuilder(camera)
00061         {}
00062 
00063         virtual ~MapBuilderWifi()
00064         {
00065                 this->unregisterFromEventsManager();
00066         }
00067 
00068 protected Q_SLOTS:
00069         virtual void processStatistics(const rtabmap::Statistics & stats)
00070         {
00071                 processingStatistics_ = true;
00072 
00073                 const std::map<int, Transform> & poses = stats.poses();
00074                 QMap<std::string, Transform> clouds = cloudViewer_->getAddedClouds();
00075 
00076                 //============================
00077                 // Add WIFI symbols
00078                 //============================
00079                 std::map<double, int> nodeStamps; // <stamp, id>
00080 
00081                 for(std::map<int, Signature>::const_iterator iter=stats.getSignatures().begin();
00082                         iter!=stats.getSignatures().end();
00083                         ++iter)
00084                 {
00085                         // Sort stamps by stamps->id
00086                         nodeStamps.insert(std::make_pair(iter->second.getStamp(), iter->first));
00087 
00088                         if(!iter->second.sensorData().userDataRaw().empty())
00089                         {
00090                                 UASSERT(iter->second.sensorData().userDataRaw().type() == CV_64FC1 &&
00091                                                 iter->second.sensorData().userDataRaw().cols == 2 &&
00092                                                 iter->second.sensorData().userDataRaw().rows == 1);
00093 
00094                                 // format [int level, double stamp]
00095                                 int level = iter->second.sensorData().userDataRaw().at<double>(0);
00096                                 double stamp = iter->second.sensorData().userDataRaw().at<double>(1);
00097                                 wifiLevels_.insert(std::make_pair(stamp, level));
00098                         }
00099                 }
00100 
00101                 int id = 0;
00102                 for(std::map<double, int>::iterator iter=wifiLevels_.begin(); iter!=wifiLevels_.end(); ++iter, ++id)
00103                 {
00104                         // The Wifi value may be taken between two nodes, interpolate its position.
00105                         double stampWifi = iter->first;
00106                         std::map<double, int>::iterator previousNode = nodeStamps.lower_bound(stampWifi); // lower bound of the stamp
00107                         if(previousNode!=nodeStamps.end() && previousNode->first > stampWifi && previousNode != nodeStamps.begin())
00108                         {
00109                                 --previousNode;
00110                         }
00111                         std::map<double, int>::iterator nextNode = nodeStamps.upper_bound(stampWifi); // upper bound of the stamp
00112 
00113                         if(previousNode != nodeStamps.end() &&
00114                            nextNode != nodeStamps.end() &&
00115                            previousNode->second != nextNode->second &&
00116                            uContains(poses, previousNode->second) && uContains(poses, nextNode->second))
00117                         {
00118                                 Transform poseA = poses.at(previousNode->second);
00119                                 Transform poseB = poses.at(nextNode->second);
00120                                 double stampA = previousNode->first;
00121                                 double stampB = nextNode->first;
00122                                 UASSERT(stampWifi>=stampA && stampWifi <=stampB);
00123 
00124                                 Transform v = poseA.inverse() * poseB;
00125                                 double ratio = (stampWifi-stampA)/(stampB-stampA);
00126 
00127                                 v.x()*=ratio;
00128                                 v.y()*=ratio;
00129                                 v.z()*=ratio;
00130 
00131                                 Transform wifiPose = (poseA*v).translation(); // rip off the rotation
00132 
00133                                 std::string cloudName = uFormat("level%d", id);
00134                                 if(clouds.contains(cloudName))
00135                                 {
00136                                         if(!cloudViewer_->updateCloudPose(cloudName, wifiPose))
00137                                         {
00138                                                 UERROR("Updating pose cloud %d failed!", id);
00139                                         }
00140                                 }
00141                                 else
00142                                 {
00143                                         // Make a line with points
00144                                         int quality = dBm2Quality(iter->second)/10;
00145                                         pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
00146                                         for(int i=0; i<10; ++i)
00147                                         {
00148                                                 // 2 cm between each points
00149                                                 // the number of points depends on the dBm (which varies from -30 (near) to -80 (far))
00150                                                 pcl::PointXYZRGB pt;
00151                                                 pt.z = float(i+1)*0.02f;
00152                                                 if(i<quality)
00153                                                 {
00154                                                         // yellow
00155                                                         pt.r = 255;
00156                                                         pt.g = 255;
00157                                                 }
00158                                                 else
00159                                                 {
00160                                                         // gray
00161                                                         pt.r = pt.g = pt.b = 100;
00162                                                 }
00163                                                 cloud->push_back(pt);
00164                                         }
00165                                         pcl::PointXYZRGB anchor(255, 0, 0);
00166                                         cloud->push_back(anchor);
00167                                         //UWARN("level %d -> %d pose=%s size=%d", level, iter->second.first, wifiPose.prettyPrint().c_str(), (int)cloud->size());
00168                                         if(!cloudViewer_->addCloud(cloudName, cloud, wifiPose, Qt::yellow))
00169                                         {
00170                                                 UERROR("Adding cloud %d to viewer failed!", id);
00171                                         }
00172                                         else
00173                                         {
00174                                                 cloudViewer_->setCloudPointSize(cloudName, 5);
00175                                         }
00176                                 }
00177                         }
00178                 }
00179 
00180                 //============================
00181                 // Add RGB-D clouds
00182                 //============================
00183                 MapBuilder::processStatistics(stats);
00184         }
00185 
00186 private:
00187         std::map<double, int> wifiLevels_;
00188 };
00189 
00190 
00191 #endif /* MAPBUILDERWIFI_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:20