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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:32