28 #ifndef MAPBUILDERWIFI_H_ 29 #define MAPBUILDERWIFI_H_ 51 return 2 * (dBm + 100);
65 this->unregisterFromEventsManager();
71 processingStatistics_ =
true;
73 const std::map<int, Transform> & poses = stats.
poses();
74 QMap<std::string, Transform> clouds = cloudViewer_->getAddedClouds();
91 wifiLevels_.insert(std::make_pair(stamp, level));
96 std::map<double, int> nodeStamps;
97 for(std::map<double, int>::iterator iter=nodeStamps_.begin(); iter!=nodeStamps_.end(); ++iter)
99 std::map<int, Transform>::const_iterator jter = poses.find(iter->second);
100 if(jter != poses.end())
102 nodeStamps.insert(*iter);
107 for(std::map<double, int>::iterator iter=wifiLevels_.begin(); iter!=wifiLevels_.end(); ++iter, ++id)
110 double stampWifi = iter->first;
111 std::map<double, int>::iterator previousNode = nodeStamps.lower_bound(stampWifi);
112 if(previousNode!=nodeStamps.end() && previousNode->first > stampWifi && previousNode != nodeStamps.begin())
116 std::map<double, int>::iterator nextNode = nodeStamps.upper_bound(stampWifi);
118 if(previousNode != nodeStamps.end() &&
119 nextNode != nodeStamps.end() &&
120 previousNode->second != nextNode->second &&
123 Transform poseA = poses.at(previousNode->second);
124 Transform poseB = poses.at(nextNode->second);
125 double stampA = previousNode->first;
126 double stampB = nextNode->first;
127 UASSERT(stampWifi>=stampA && stampWifi <=stampB);
130 double ratio = (stampWifi-stampA)/(stampB-stampA);
136 Transform wifiPose = (poseA*v).translation();
138 std::string cloudName =
uFormat(
"level%d",
id);
139 if(clouds.contains(cloudName))
141 if(!cloudViewer_->updateCloudPose(cloudName, wifiPose))
143 UERROR(
"Updating pose cloud %d failed!",
id);
150 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
151 for(
int i=0; i<10; ++i)
156 pt.z = float(i+1)*0.02f;
166 pt.r = pt.g = pt.b = 100;
168 cloud->push_back(pt);
170 pcl::PointXYZRGB anchor;
172 cloud->push_back(anchor);
174 if(!cloudViewer_->addCloud(cloudName, cloud, wifiPose, Qt::yellow))
176 UERROR(
"Adding cloud %d to viewer failed!",
id);
180 cloudViewer_->setCloudPointSize(cloudName, 5);
MapBuilderWifi(CameraThread *camera=0)
virtual ~MapBuilderWifi()
std::map< double, int > nodeStamps_
void processStatistics(const rtabmap::Statistics &stats)
const Signature & getLastSignatureData() const
std::map< double, int > wifiLevels_
#define UASSERT(condition)
const cv::Mat & userDataRaw() const
virtual void processStatistics(const rtabmap::Statistics &stats)
bool uContains(const std::list< V > &list, const V &value)
const std::map< int, Transform > & poses() const
SensorData & sensorData()
std::string UTILITE_EXP uFormat(const char *fmt,...)