Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
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
00037
00038
00039
00040
00041
00042
00043 inline int dBm2Quality(int dBm)
00044 {
00045
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
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
00078
00079 std::map<double, int> nodeStamps;
00080
00081 for(std::map<int, Signature>::const_iterator iter=stats.getSignatures().begin();
00082 iter!=stats.getSignatures().end();
00083 ++iter)
00084 {
00085
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
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
00105 double stampWifi = iter->first;
00106 std::map<double, int>::iterator previousNode = nodeStamps.lower_bound(stampWifi);
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);
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();
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
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
00149
00150 pcl::PointXYZRGB pt;
00151 pt.z = float(i+1)*0.02f;
00152 if(i<quality)
00153 {
00154
00155 pt.r = 255;
00156 pt.g = 255;
00157 }
00158 else
00159 {
00160
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
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
00182
00183 MapBuilder::processStatistics(stats);
00184 }
00185
00186 private:
00187 std::map<double, int> wifiLevels_;
00188 };
00189
00190
00191 #endif