From e718dc8ccaa1c56aec6b8d7cff3593f296d90bff Mon Sep 17 00:00:00 2001 From: kazu Date: Tue, 28 Mar 2017 21:02:37 +0200 Subject: [PATCH] added tex many changes/eval etc... --- CMakeLists.txt | 2 +- EvalApOpt.h | 22 +- EvalCompareOpt.h | 79 +- EvalData.h | 2 + EvalWalk.h | 250 ++- EvalWiFi.h | 9 +- EvalWiFiSigStrength.h | 153 ++ Helper.h | 112 ++ PlotErrFunc.h | 92 ++ Plotty.h | 288 +++- Settings.h | 47 + main.cpp | 178 ++- pf/PF.h | 328 ++++ tex/bare_conf.tex | 222 +++ tex/chapters/abstract.tex | 1 + tex/chapters/conclusion.tex | 1 + tex/chapters/experiments.tex | 15 + tex/chapters/interoduction.tex | 1 + tex/chapters/introduction.tex | 1 + tex/chapters/relatedwork.tex | 3 + tex/egbib.bib | 2709 ++++++++++++++++++++++++++++++++ tex/gfx/build.sh | 4 + tex/make.sh | 15 + tex/misc/functions.tex | 137 ++ tex/misc/keywords.tex | 31 + 25 files changed, 4614 insertions(+), 88 deletions(-) create mode 100644 EvalWiFiSigStrength.h create mode 100644 PlotErrFunc.h create mode 100644 pf/PF.h create mode 100644 tex/bare_conf.tex create mode 100644 tex/chapters/abstract.tex create mode 100644 tex/chapters/conclusion.tex create mode 100644 tex/chapters/experiments.tex create mode 100644 tex/chapters/interoduction.tex create mode 100644 tex/chapters/introduction.tex create mode 100644 tex/chapters/relatedwork.tex create mode 100644 tex/egbib.bib create mode 100644 tex/gfx/build.sh create mode 100644 tex/make.sh create mode 100644 tex/misc/functions.tex create mode 100644 tex/misc/keywords.tex diff --git a/CMakeLists.txt b/CMakeLists.txt index bddc432..607fcf6 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -58,7 +58,7 @@ ADD_DEFINITIONS( -fstack-protector-all -g3 - -O0 + -O0 -march=native -DWITH_TESTS diff --git a/EvalApOpt.h b/EvalApOpt.h index c4abf7e..105065f 100644 --- a/EvalApOpt.h +++ b/EvalApOpt.h @@ -27,6 +27,7 @@ #include "Structs.h" #include "Plotty.h" #include "CSV.h" +#include "Helper.h" #include @@ -48,7 +49,7 @@ void plot(const K::SimpleHistogram& h) { class EvalApOpt { Floorplan::IndoorMap* map; - WiFiFingerprints* calib; + WiFiFingerprints calib; VAPGrouper* vap; WiFiOptimizer::LogDistCeiling* opt; Floorplan::Ceilings ceilings; @@ -63,13 +64,19 @@ public: map = Floorplan::Reader::readFromFile(mapFile); // load fingerprints - calib = new WiFiFingerprints(fpFile); + calib = WiFiFingerprints(fpFile); + + + calib = LeHelper::removeOutdoor(calib); + calib = LeHelper::removeStaircases(calib); + LeHelper::plot(map, calib); + // how to handle VAPs vap = new VAPGrouper(VAPGrouper::Mode::LAST_MAC_DIGIT_TO_ZERO, VAPGrouper::Aggregation::AVERAGE); // the optimizer - opt = new WiFiOptimizer::LogDistCeiling(map, *vap, *calib, WiFiOptimizer::LogDistCeiling::Mode::MEDIUM); + opt = new WiFiOptimizer::LogDistCeiling(map, *vap, calib, WiFiOptimizer::LogDistCeiling::Mode::MEDIUM); // some ceiling calculations ceilings = Floorplan::Ceilings(map); @@ -115,6 +122,7 @@ public: continue; } + plot(result); results.push_back(result); dumpStats(result); @@ -135,8 +143,10 @@ public: } // average error + std::cout << "OVERALL RESULT: " << std::endl; std::cout << "error signed: " << statsSigned.asString() << std::endl; std::cout << "error unsigned: " << statsAbs.asString() << std::endl; + std::cout << "--------------------------------------------------------" << std::endl; // all APs known to the map but invisible during fingerprinting [should not happen] std::unordered_set mapUnseen = mapAPs; @@ -212,7 +222,9 @@ public: // } // } - plot.plot(); + if (1 == 0) { + plot.plot(); + } return; } @@ -224,7 +236,7 @@ public: optStats.mac = mac; const WiFiOptimizer::LogDistCeiling::APParams params = opt->optimize(mac, optStats.opt); - const std::vector fps = calib->getFingerprintsFor(vap->getBaseMAC(mac)); + const std::vector fps = calib.getFingerprintsFor(vap->getBaseMAC(mac)); optStats.params = params; diff --git a/EvalCompareOpt.h b/EvalCompareOpt.h index 952dc7b..1f0948b 100644 --- a/EvalCompareOpt.h +++ b/EvalCompareOpt.h @@ -16,9 +16,11 @@ #include "Indoor/floorplan/v2/FloorplanCeilings.h" #include "Indoor/sensors/radio/model/WiFiModelLogDistCeiling.h" +#include "Helper.h" using APAtFloor = std::pair; + /** * compare different optimzation levels * fixed ap pos / fixed params @@ -29,8 +31,9 @@ class EvalCompareOpt { protected: + int power = 1; Floorplan::IndoorMap* map; - WiFiFingerprints* calib; + WiFiFingerprints calib; VAPGrouper* vap; Floorplan::Ceilings ceilings; std::vector mapAPs; @@ -38,13 +41,26 @@ protected: /** ctor with map and fingerprints */ - EvalCompareOpt(const std::string& mapFile, const std::string& fpFile) { + EvalCompareOpt(const std::string& mapFile, const std::string& fpFile, const bool ignoreStaircases, const bool ignoreOutdoor) { // load floorplan map = Floorplan::Reader::readFromFile(mapFile); + // how to group VAPs + vap = new VAPGrouper(VAPGrouper::Mode::LAST_MAC_DIGIT_TO_ZERO, VAPGrouper::Aggregation::AVERAGE); + // load fingerprints - calib = new WiFiFingerprints(fpFile); + calib = WiFiFingerprints(fpFile); + + LeHelper::removeNonFHWS(calib); + if (ignoreOutdoor) {calib = LeHelper::removeOutdoor(calib);} + if (ignoreStaircases) {calib = LeHelper::removeStaircases(calib);} + //LeHelper::plot(map, calib); + WiFiFingerprints calib2 = calib; + for (WiFiFingerprint& fp : calib2.getFingerprints()) { + fp.measurements = vap->group(fp.measurements); + } + LeHelper::plot(map, calib2); // some ceiling calculations ceilings = Floorplan::Ceilings(map); @@ -52,12 +68,9 @@ protected: // all APs within the map mapAPs = FloorplanHelper::getAPs(map); - // how to group VAPs - vap = new VAPGrouper(VAPGrouper::Mode::LAST_MAC_DIGIT_TO_ZERO, VAPGrouper::Aggregation::AVERAGE); - // used to aggreagate fingerprints base = new WiFiOptimizer::Base(*vap); - base->addFingerprints(*calib); + base->addFingerprints(calib); } @@ -121,8 +134,8 @@ protected: const float diff = std::abs(rssiModel - reading.rssi); // adjust - stats.add(std::abs(diff)); - dstAbs.add(std::abs(diff)); + stats.add(std::pow(std::abs(diff), power)); + dstAbs.add(std::pow(std::abs(diff), power)); } @@ -135,6 +148,8 @@ protected: }; + + /** fixed ap pos, fixed ap params */ class EvalCompareOptAllFixed : public EvalCompareOpt { @@ -147,8 +162,9 @@ private: public: - EvalCompareOptAllFixed(const std::string& mapFile, const std::string& fpFile) : EvalCompareOpt(mapFile, fpFile) { - + EvalCompareOptAllFixed(const std::string& mapFile, const std::string& fpFile, const bool ignoreStaircases, const bool ignoreOutdoor) : + EvalCompareOpt(mapFile, fpFile, ignoreStaircases, ignoreOutdoor) { + ; } @@ -182,28 +198,38 @@ public: } /** calculate error for fixed positions and fixed constants */ - void fixedPosFixedParamsForAll() { + K::Statistics fixedPosFixedParamsForAll() { // fire + K::Statistics stats = getStatsAll(txp, exp, waf); std::cout << "----------------------------------------------------" << std::endl; std::cout << "AP POS FROM MAP, FIXED TXP/EXP/WAF FOR ALL APS" << std::endl; - std::cout << getStatsAll(txp, exp, waf).asString() << std::endl; + std::cout << stats.asString() << std::endl; std::cout << std::endl; + return stats; } /** calculate error for fixed positions and optimized constants, but the same 3 for all APs */ - void fixedPosOptParamsForAll() { + K::Statistics fixedPosOptParamsForAll() { auto func = [&] (const float* params) { return getStatsAll(params[0], params[1], params[2]).getAvg(); }; + auto callback = [&] (const int run, const int iteration, const float , const float* ) { + const int percent = ((run*40+iteration)*100) / (40*11); + if (iteration == 0) { + std::cout << percent << "," << std::flush; + } + }; + // use simplex float params[3] = {-40, 2, -8}; K::NumOptAlgoDownhillSimplex opt(3); - opt.setMaxIterations(50); + opt.setMaxIterations(40); opt.setNumRestarts(10); + opt.setCallback(callback); opt.calculateOptimum(func, params); // use genetic @@ -215,16 +241,18 @@ public: // opt.setMutation(0.25); // opt.calculateOptimum(func, params); + K::Statistics stats = getStatsAll(params[0], params[1], params[2]); std::cout << "----------------------------------------------------" << std::endl; std::cout << "AP POS FROM MAP, OPTIMIZING TXP/EXP/WAF: THE SAME FOR ALL APS" << std::endl; std::cout << "params: " << params[0] << "," << params[1] << "," << params[2] << std::endl; - std::cout << getStatsAll(params[0], params[1], params[2]).asString() << std::endl; + std::cout << stats.asString() << std::endl; std::cout << std::endl; + return stats; } /** calculate error for fixed positions and optimized constants, each AP on its own */ - void fixedPosOptParamsForEach() { + K::Statistics fixedPosOptParamsForEach() { K::Statistics _dstAbs; @@ -263,7 +291,7 @@ public: analyzeErrorForAP(mac, pos, params[0], params[1], params[2], tmp); // adjust global error with the resulting params - std::cout << "--" << mac.asString() << " params: " << params[0] << "," << params[1] << "," << params[2] << " err: " << tmp.getAvg() << std::endl; + std::cout << "--" << mac.asString() << " params: " << params[0] << ",\t" << params[1] << ",\t" << params[2] << "\terr: " << tmp.getAvg() << std::endl; analyzeErrorForAP(mac, pos, params[0], params[1], params[2], _dstAbs); } @@ -272,14 +300,19 @@ public: std::cout << "AP POS FROM MAP, OPTIMIZING TXP/EXP/WAF INDIVIDUALLY FOR EACH AP" << std::endl; std::cout << _dstAbs.asString() << std::endl; std::cout << std::endl; + return _dstAbs; } /** calculate error for fixed positions and optimized constants, each AP on its own */ - void optPosOptParamsForEach() { + K::Statistics optPosOptParamsForEach() { K::Statistics _dstAbs; + std::cout << "NOTE" << std::endl; + std::cout << "INCREASE ITERATIONS!" << std::endl; + std::cout << "!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!" << std::endl; + // construct vector containing each AP within the map + add fixed parameters for (const APAtFloor& mapAP : mapAPs) { @@ -312,9 +345,10 @@ public: }; + K::NumOptAlgoRangeRandom opt(valRegion); - opt.setPopulationSize(500); - opt.setNumIerations(150); + opt.setPopulationSize(100); + opt.setNumIerations(40); opt.calculateOptimum(func, params); // local stats @@ -322,7 +356,7 @@ public: analyzeErrorForAP(mac, Point3(params[0], params[1], params[2]), params[3], params[4], params[5], tmp); // adjust global error with the resulting params - std::cout << "--" << mac.asString() << " params: " << params[0] << "," << params[1] << "," << params[2] << "," << params[3] << "," << params[4] << "," << params[5] << " err: " << tmp.getAvg() << std::endl; + std::cout << "--" << mac.asString() << " params: " << params[0] << ",\t" << params[1] << ",\t" << params[2] << ",\t" << params[3] << ",\t" << params[4] << ",\t" << params[5] << "\terr: " << tmp.getAvg() << std::endl; analyzeErrorForAP(mac, Point3(params[0], params[1], params[2]), params[3], params[4], params[5], _dstAbs); } @@ -331,6 +365,7 @@ public: std::cout << "OPTIMIZING POS/TXP/EXP/WAF INDIVIDUALLY FOR EACH AP" << std::endl; std::cout << _dstAbs.asString() << std::endl; std::cout << std::endl; + return _dstAbs; } diff --git a/EvalData.h b/EvalData.h index 15ef0c8..ec4513d 100644 --- a/EvalData.h +++ b/EvalData.h @@ -47,6 +47,8 @@ public: } + + }; #endif // EVALDATA_H diff --git a/EvalWalk.h b/EvalWalk.h index 5fc5054..eff861b 100644 --- a/EvalWalk.h +++ b/EvalWalk.h @@ -1,6 +1,16 @@ #ifndef EVALWALK_H #define EVALWALK_H +#include +#include +#include +#include +#include +#include +#include + +#include + #include "Indoor/sensors/radio/setup/WiFiOptimizer.h" #include "Indoor/sensors/radio/setup/WiFiFingerprint.h" #include "Indoor/sensors/radio/setup/WiFiFingerprints.h" @@ -9,6 +19,8 @@ #include "Indoor/sensors/radio/setup/WiFiOptimizerLogDistCeiling.h" #include "Indoor/sensors/radio/VAPGrouper.h" +#include "Indoor/sensors/imu/StepDetection.h" +#include "Indoor/sensors/imu/TurnDetection.h" #include "Indoor/floorplan/v2/Floorplan.h" #include "Indoor/floorplan/v2/FloorplanReader.h" @@ -19,16 +31,250 @@ #include "Indoor/sensors/offline/FileReader.h" #include "Helper.h" +#include "pf/PF.h" -class EvalWalk { +#include +#include + +class EvalWalk : public Offline::Listener { + + Grid* grid; + K::ParticleFilter* pf; + + std::string runName; + WiFiModelLogDistCeiling wifiModel; + + Plotty plotty; + + Offline::FileReader reader; + + Timestamp lastTransition; + + MyObservation curObs; + MyControl curCtrl; + MyState curEst; + + StepDetection stepDetect; + TurnDetection turnDetect; + + std::vector groundTruth; + + Floorplan::IndoorMap* map; public: - EvalWalk() { + EvalWalk(Floorplan::IndoorMap* map) : wifiModel(map), plotty(map), map(map) { + + const std::string saveFile = Settings::pathData + "/grid.dat"; + grid = new Grid(Settings::Grid::gridSize_cm); + + plotty.buildFloorplan(); + + // deserialize grid + std::ifstream inp(saveFile, std::ofstream::binary); + if (inp) { + grid->read(inp); + inp.close(); + } else { + // build the grid + GridFactory gf(*grid); + gf.build(map); + std::ofstream out(saveFile, std::ofstream::binary); + grid->write(out); + out.close(); + } + + pf = new K::ParticleFilter( Settings::numParticles, std::unique_ptr(new PFInit(grid)) ); + + // TODO: flexible model + wifiModel.loadAPs(map, Settings::WiFiModel::TXP, Settings::WiFiModel::EXP, Settings::WiFiModel::WAF, false); + std::unique_ptr eval = std::unique_ptr( new PFEval(grid, wifiModel) ); + pf->setEvaluation( std::move(eval) ); + + // resampling step? + pf->setNEffThreshold(0.5); + //pf->setResampling( std::unique_ptr>(new K::ParticleFilterResamplingSimple()) ); + pf->setResampling( std::unique_ptr>(new K::ParticleFilterResamplingPercent(0.10)) ); + + // state estimation step + pf->setEstimation( std::unique_ptr>(new K::ParticleFilterEstimationWeightedAverage())); + //pf->setEstimation( std::unique_ptr>(new K::ParticleFilterEstimationRegionalWeightedAverage())); + //pf->setEstimation( std::unique_ptr>(new K::ParticleFilterEstimationOrderedWeightedAverage(0.50f))); + } + + void walk1() { + + runName = "path2_forward_simple"; + std::string path = Settings::path1a; + groundTruth = FloorplanHelper::getGroundTruth(map, Settings::GroundTruth::path1); + + //GridWalkSimpleControl* walk = new GridWalkSimpleControl(); + pf->setTransition( std::unique_ptr( new PFTrans(grid)) ); + + reader.open(path, this); + + + + } + + + + + virtual void onGyroscope(const Timestamp ts, const GyroscopeData data) override { + + const float delta_rad = turnDetect.addGyroscope(ts, data); + curCtrl.turnSinceLastTransition_rad += delta_rad; + + } + + virtual void onAccelerometer(const Timestamp ts, const AccelerometerData data) override { + turnDetect.addAccelerometer(ts, data); + const bool step = stepDetect.add(ts, data); + if (step) { + ++curCtrl.numStepsSinceLastTransition; + } + gotSensorData(ts); + } + + virtual void onGravity(const Timestamp ts, const GravityData data) override { + ; + } + + virtual void onWiFi(const Timestamp ts, const WiFiMeasurements data) override { + std::cout << "WIFI" << std::endl; + curObs.wifi = data; + } + + virtual void onBarometer(const Timestamp ts, const BarometerData data) override { + ; + } + + virtual void onGPS(const Timestamp ts, const GPSData data) override { + curObs.gps = data; + } + + virtual void onCompass(const Timestamp ts, const CompassData data) override { + const float newAzimuth = - data.azimuth + M_PI/2; // oriented towards north for our map + curCtrl.compass_azimuth = curCtrl.compass_azimuth * 0.99 + newAzimuth * 0.01; + } + + +private: + + /** called when any sensor has received new data */ + void gotSensorData(const Timestamp ts) { + curObs.currentTime = ts; + filterUpdateIfNeeded(); + } + + /** check whether its time for a filter update, and if so, execute the update and return true */ + bool filterUpdateIfNeeded() { + + static float avgSum = 0; + static int avgCount = 0; + + // fixed update rate based on incoming sensor data + // allows working with live data and faster for offline data + const Timestamp diff = curObs.currentTime - lastTransition; + if (diff >= Settings::Filter::updateEvery) { + + // as the difference is slightly above the 500ms, calculate the error and incorporate it into the next one + const Timestamp err = diff - Settings::Filter::updateEvery; + lastTransition = curObs.currentTime - err; + + const Timestamp ts1 = Timestamp::fromUnixTime(); + filterUpdate(); + const Timestamp ts2 = Timestamp::fromUnixTime(); + const Timestamp tsDiff = ts2-ts1; + + //const QString filterTime = QString::number(tsDiff.ms()); + //avgSum += tsDiff.ms(); ++avgCount; + //Log::add("xxx", "ts:" + std::to_string(curObs.currentTime.ms()) + " avg:" + std::to_string(avgSum/avgCount)); + return true; + + } else { + + return false; + + } + + } + + + + /** perform a filter-update (called from a background-loop) */ + void filterUpdate() { + + std::cout << "update" << std::endl; + + MyControl ctrlCopy = curCtrl; + static float absHead = M_PI/2; absHead += ctrlCopy.turnSinceLastTransition_rad; + + //lastEst = curEst; + curEst = pf->update(&curCtrl, curObs); + //Log::add("Nav", "cur est: " + curEst.position.asString()); + + // inform listeners about the new estimation +// for (NavControllerListener* l : listeners) {l->onNewEstimation(curEst.position.inMeter());} + + // update estimated path + //estPath.push_back(curEst.position.inMeter()); + +// PFTrans* trans = (PFTrans*)pf->getTransition(); + + + + const K::GnuplotPoint3 p3(curEst.position.x_cm, curEst.position.y_cm, curEst.position.z_cm); + plotty.pathEst.add(p3/100); + + plotty.particles.clear(); + for (const auto p : pf->getParticles()) { + const K::GnuplotPoint3 p3(p.state.position.x_cm, p.state.position.y_cm, p.state.position.z_cm); + plotty.particles.add(p3/100); + } + + // GT + plotty.pathReal.clear(); + for (const Point3 pt : groundTruth) { + plotty.pathReal.add(K::GnuplotPoint3(pt.x, pt.y, pt.z)); + } + + std::string title = + " time " + std::to_string(curObs.currentTime.sec()) + + " steps: " + std::to_string(ctrlCopy.numStepsSinceLastTransition) + + " turn: " + std::to_string(ctrlCopy.turnSinceLastTransition_rad); + plotty.setTitle(title); + + { + Point2 cen(0.1, 0.9); + Point2 dir(std::cos(absHead), std::sin(absHead)); + Point2 arr = cen + dir * 0.1; + plotty.gp << "set arrow 1 from screen " << cen.x << "," << cen.y << " to screen " << arr.x << "," << arr.y << "\n"; + dir = Point2(std::cos(ctrlCopy.compass_azimuth), std::sin(ctrlCopy.compass_azimuth)); + arr = cen + dir * 0.05; + plotty.gp << "set arrow 2 from screen " << cen.x << "," << cen.y << " to screen " << arr.x << "," << arr.y << "\n"; + } + + + // plot + plotty.plot(); + + std::this_thread::sleep_for(std::chrono::milliseconds(30)); + + curCtrl.resetAfterTransition(); + +// const MyGridNode* node = grid->getNodePtrFor(curEst.position); +// if (node) { +// try { +// pathToDest = trans->modDestination.getShortestPath(*node); +// } catch (...) {;} +// } + // mainController->getMapView()->showGridImportance(); + } }; diff --git a/EvalWiFi.h b/EvalWiFi.h index ff1f82b..f078a52 100644 --- a/EvalWiFi.h +++ b/EvalWiFi.h @@ -127,11 +127,6 @@ public: private: - /** is the given mac one of a FHWS ap? */ - bool isFHWS_AP(const MACAddress& mac) { - return mac.asString().substr(0,5) == "D8:84"; - } - void run() { Plotty* plot = new Plotty(map); @@ -168,7 +163,7 @@ private: for (const WiFiMeasurement& m : mes.entries) { // skip non-FHWS APs - if (!isFHWS_AP(m.getAP().getMAC())) {continue;} + if (!LeHelper::isFHWS_AP(m.getAP().getMAC())) {continue;} // get model's rssi for the given location const float rssi_model = wiModel->getRSSI(m.getAP().getMAC(), pos_m); @@ -219,7 +214,7 @@ private: // draw a smoothed version of th epath plot->pathEst.clear(); - for (const Point3 p : path.getAverage(1)) { + for (const Point3 p : path.getAverage(2)) { const K::GnuplotPoint3 gp3(p.x, p.y, p.z); plot->pathEst.add(gp3); } diff --git a/EvalWiFiSigStrength.h b/EvalWiFiSigStrength.h new file mode 100644 index 0000000..730665d --- /dev/null +++ b/EvalWiFiSigStrength.h @@ -0,0 +1,153 @@ +#ifndef EVALWIFISIGSTRENGTH_H +#define EVALWIFISIGSTRENGTH_H + + +#include "Indoor/sensors/radio/setup/WiFiOptimizer.h" +#include "Indoor/sensors/radio/setup/WiFiFingerprint.h" +#include "Indoor/sensors/radio/setup/WiFiFingerprints.h" +#include "Indoor/sensors/radio/setup/WiFiOptimizer.h" + +#include "Indoor/sensors/radio/VAPGrouper.h" +#include "Indoor/sensors/offline/FileReader.h" + +#include "Indoor/floorplan/v2/Floorplan.h" +#include "Indoor/floorplan/v2/FloorplanReader.h" +#include "Indoor/floorplan/v2/FloorplanHelper.h" +#include "Indoor/floorplan/v2/FloorplanCeilings.h" + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include "Structs.h" +#include "Plotty.h" +#include "CSV.h" +#include "Helper.h" + +#include + + +/** + * read path + * fetch wifi + * use given model to estimate the most likely location + * -> WIFI ONLY + */ +class EvalWiFiSigStrength { + +private: + + Floorplan::IndoorMap* map; + BBox3 mapBBox; + + WiFiFingerprints calib; + +public: + + /** ctor with map and fingerprints */ + EvalWiFiSigStrength(const std::string& mapFile, const std::string& fpFile) { + + // load floorplan + map = Floorplan::Reader::readFromFile(mapFile); + + // estimate bbox + mapBBox = FloorplanHelper::getBBox(map); + + // load fingerprints + calib = WiFiFingerprints(fpFile); + + // remove some stuff + LeHelper::removeNonFHWS(calib); + + } + + float scale(const float val, const float min, const float max) { + return (val - min) / (max-min); + } + + + void forAP_avg(Plotty* p, const MACAddress& mac) { + + VAPGrouper vap(VAPGrouper::Mode::LAST_MAC_DIGIT_TO_ZERO, VAPGrouper::Aggregation::AVERAGE); + + // get AP/floor + std::pair _ap = FloorplanHelper::getAP(map, mac); + const Floorplan::Floor* floor = _ap.second; + const Floorplan::AccessPoint* ap = _ap.first; + + // copy + WiFiFingerprints calib = this->calib; + for (WiFiFingerprint& fp : calib.getFingerprints()) { + fp.measurements = vap.group(fp.measurements); + } + + // plot + + + std::cout << ap->mac << std::endl; + + const Point3 apPos3 = ap->getPos(floor); + K::GnuplotPoint3 apPos(apPos3.x, apPos3.y, apPos3.z); + p->points.add(apPos); + + // process every fingerprint location + for (const WiFiFingerprint& fp : calib.getFingerprints()) { + + // either 0 entries [ap not seen here] or 1 entry due to vap grouping [ap seen here] + std::vector mes = fp.getAllForMAC(mac); + + if (!mes.empty()) { + + const float rssi = mes.front().getRSSI(); + const float s = scale(rssi, -100, -40); + const Color c = Color::fromHSV(s*100, 255, 255); + + // fingerprint onto the floor + p->addFloorRect(fp.pos_m - Point3(0,0,1.3), 1, c); + + } + + } + + } + + void perAP_avg() { + + std::vector> aps = FloorplanHelper::getAPs(map); + + for (const auto& it : aps) { + + const Floorplan::Floor* floor = it.second; + const Floorplan::AccessPoint* ap = it.first; + const MACAddress mac(ap->mac); + + Plotty* p = new Plotty(map); + p->setTitle(ap->mac); + p->buildFloorplan(); + forAP_avg(p, mac); + + p->plot(); + + int i = 0; (void) i; + + // MACs: + // d8:84:66:4a:23:d0 <<<< BEST + // d8:84:66:4a:25:c0 + // d8:84:66:4a:4c:60 + + } + + } + + + +}; + + +#endif // EVALWIFISIGSTRENGTH_H diff --git a/Helper.h b/Helper.h index 4a3396d..c559980 100644 --- a/Helper.h +++ b/Helper.h @@ -3,6 +3,10 @@ #include #include +#include +#include + +#include "Plotty.h" class LeHelper { @@ -24,6 +28,114 @@ public: } + /** remove all outdoor fingerprints */ + static WiFiFingerprints removeOutdoor(const WiFiFingerprints& inp) { + + WiFiFingerprints res; + + for (const WiFiFingerprint& fp : inp.getFingerprints()) { + const Point3 pos = fp.pos_m; + + // garden + if (pos == Point3(21, 12, 1.3)) {continue;} + if (pos == Point3(21, 27, 1.3)) {continue;} + if (pos == Point3(39, 12, 1.3)) {continue;} + if (pos == Point3(39, 27, 1.3)) {continue;} + if (pos == Point3(67, 12, 1.3)) {continue;} + if (pos == Point3(67, 27, 1.3)) {continue;} + if (pos == Point3(88, 12, 1.3)) {continue;} + if (pos == Point3(88, 27, 1.3)) {continue;} + + // front door + if (pos == Point3(94, 43, 4+1.3)) {continue;} + if (pos == Point3(110, 43, 4+1.3)) {continue;} + if (pos == Point3(94, 55, 4+1.3)) {continue;} + if (pos == Point3(110, 55, 4+1.3)) {continue;} + if (pos == Point3(67.2, 55, 4+1.3)) {continue;} + + res.add(fp); + } + + return res; + + } + + static WiFiFingerprints removeStaircases(const WiFiFingerprints& inp) { + + WiFiFingerprints res; + + for (const WiFiFingerprint& fp : inp.getFingerprints()) { + const Point3 pos = fp.pos_m; + + // floor 0 + if (pos == Point3(67.2, 48.5, 1.3)) {continue;} + if (pos == Point3(11.2, 48.3, 1.3)) {continue;} + if (pos == Point3(16.5, 11.9, 1.3)) {continue;} + if (pos == Point3(57.4, 2.6, 1.3)) {continue;} + if (pos == Point3(57.4, -3.2, 3.0)) {continue;} + + // floor 1 + if (pos == Point3(67.2, 48.3, 4+1.3)) {continue;} + if (pos == Point3(11.4, 48.3, 4+1.3)) {continue;} + if (pos == Point3(16.1, 11.9, 4+1.3)) {continue;} + if (pos == Point3(57.4, 2.4, 4+1.3)) {continue;} + + // floor 2 + if (pos == Point3(67.0, 48.5, 3.4+4+1.3)) {continue;} + if (pos == Point3(11.6, 48.5, 3.4+4+1.3)) {continue;} + if (pos == Point3(16.3, 11.9, 3.4+4+1.3)) {continue;} + + // floor 3 + if (pos == Point3(67.0, 48.3, 3.4+3.4+4+1.3)) {continue;} + if (pos == Point3(11.4, 48.5, 3.4+3.4+4+1.3)) {continue;} + if (pos == Point3(16.3, 11.9, 3.4+3.4+4+1.3)) {continue;} + + res.add(fp); + + } + + return res; + } + + static void plot(const Floorplan::IndoorMap* map, const WiFiFingerprints& inp, const std::string& title = "Fingerprints") { + + Plotty* p = new Plotty(map); + p->setTitle(title); + p->buildFloorplan(); + p->cpoints.clear(); + for (const WiFiFingerprint& fp : inp.getFingerprints()) { + const K::GnuplotPoint3 gp(fp.pos_m.x, fp.pos_m.y, fp.pos_m.z); + //p->cpoints.add(gp, 1); + const float size = fp.measurements.entries.size() / 10.0 * 1.0; + p->addFloorRect(fp.pos_m, size, Color::fromRGB(255,0,0)); + p->addLabel(std::to_string(fp.measurements.entries.size()), fp.pos_m+Point3(1,1,1)); + } + p->plot(); + + } + + /** is the given mac one of a FHWS ap? */ + static inline bool isFHWS_AP(const MACAddress& mac) { + return mac.asString().substr(0,5) == "D8:84"; + } + + /** remove all non-FHWS APs from the calibration */ + static inline void removeNonFHWS(WiFiFingerprints& calib) { + int removed = 0; + for (WiFiFingerprint& fp : calib.getFingerprints()) { + for (size_t i = 0; i < fp.measurements.entries.size(); ++i) { + const WiFiMeasurement& m = fp.measurements.entries[i]; + if (!isFHWS_AP(m.getAP().getMAC())) { + fp.measurements.entries.erase(fp.measurements.entries.begin() + i); + --i; + ++removed; + } + } + } + std::cout << "removed " << removed << " entries" < + +#include +#include +#include + + +class PlotErrFunc { + + + + struct Entry { + std::string name; + K::Statistics stats; + Entry(const std::string& name, const K::Statistics& stats) : name(name), stats(stats) {;} + }; + + std::vector entries; + + K::Gnuplot gp; + K::GnuplotPlot gplot; + + //std::vector colors = {"#000000", "#ff0000", "#00bb00", "#0000ff"}; + std::vector colors = {"#000000", "#999999", "#0000ff", "#9999ff"}; + + std::string codeFile; + +public: + + /** ctor with x-axis label */ + PlotErrFunc(const std::string& xLabel, const std::string& yLabel) { + gplot.setLabelX(xLabel); + gplot.setLabelY(yLabel); + } + + /** add one curve */ + void add(const std::string name, const K::Statistics stats) { + entries.push_back(Entry(name, stats)); + } + + K::Gnuplot& getGP() { + return gp; + } + + void writeCodeTo(const std::string& file) { + this->codeFile = file; + } + + /** plot all curves */ + void plot() { + + gp << "set grid\n"; + + for (size_t i = 0; i < entries.size(); ++i) { + + const Entry e = entries[i]; + + K::GnuplotPlotElementLines* line = new K::GnuplotPlotElementLines(); + line->setTitle(e.name); + line->setColorHex(colors[i]); + line->setLineWidth(2); + gplot.add(line); + + // 0 - 80% + for (int i = 0; i <= 85; i+= 5) { + const float q = i / 100.0f; + const float y = e.stats.getQuantile(q); + K::GnuplotPoint2 gp(y, q*100); + line->add(gp); + } + + } + + gp.draw(gplot); + + if (codeFile != "") { + std::ofstream out(codeFile); + out << gp.getBuffer(); + out.close(); + } + + gp.flush(); + gp.close(); + + } + +}; + +#endif // PLOTERRFUNC_H diff --git a/Plotty.h b/Plotty.h index a7b15e2..98e1529 100644 --- a/Plotty.h +++ b/Plotty.h @@ -12,22 +12,108 @@ #include #include +struct Color { + + uint8_t r; + uint8_t g; + uint8_t b; + + Color() : r(0), g(0), b(0) { + ; + } + + static Color fromRGB(const uint8_t r, const uint8_t g, const uint8_t b) { + Color c; c.setRGB(r,g,b); + return c; + } + + static Color fromHSV(const uint8_t h, const uint8_t s, const uint8_t v) { + Color c; c.setHSV(h,s,v); + return c; + } + + void setRGB(const uint8_t r, const uint8_t g, const uint8_t b) { + this->r = r; + this->g = g; + this->b = b; + } + + void setHSV(const uint8_t h, const uint8_t s, const uint8_t v) { + + uint8_t region, remainder, p, q, t; + + region = h / 43; + remainder = (h - (region * 43)) * 6; + + p = (v * (255 - s)) >> 8; + q = (v * (255 - ((s * remainder) >> 8))) >> 8; + t = (v * (255 - ((s * (255 - remainder)) >> 8))) >> 8; + + switch (region) { + case 0: + r = v; g = t; b = p; + break; + case 1: + r = q; g = v; b = p; + break; + case 2: + r = p; g = v; b = t; + break; + case 3: + r = p; g = q; b = v; + break; + case 4: + r = t; g = p; b = v; + break; + default: + r = v; g = p; b = q; + break; + } + + } + + std::string toHEX() const { + char buf[8]; + sprintf(buf, "#%02x%02x%02x", r, g, b); + std::string color(buf); + return color; + } + +}; + + class Plotty { public: - Floorplan::IndoorMap* map; + const Floorplan::IndoorMap* map; K::Gnuplot gp; K::GnuplotSplot splot; K::GnuplotSplotElementPoints points; K::GnuplotSplotElementColorPoints cpoints; + K::GnuplotSplotElementLines pathReal; K::GnuplotSplotElementLines pathEst; - K::GnuplotSplotElementLines mapOutline; + K::GnuplotSplotElementPoints particles; + + K::GnuplotSplotElementLines mapOutlineGlass; + K::GnuplotSplotElementLines mapOutlineDrywall; + K::GnuplotSplotElementLines mapOutlineConcrete; + + std::string codeFile; + + struct Settings { + std::vector floors = {}; + bool stairs = true; + bool obstacles = true; + bool outline = true; + float minZ = -9999; + float maxZ = +9999; + } settings; public: - Plotty(Floorplan::IndoorMap* map) : map(map) { + Plotty(const Floorplan::IndoorMap* map) : map(map) { //gp << "set view equal xy\n"; @@ -37,37 +123,17 @@ public: gp << "g(x) = 0\n"; gp << "b(x) = (x > 0) ? 0 : (-x/2)\n"; gp << "set palette model RGB functions r(gray),g(gray),b(gray)\n"; + gp << "set ticslevel 0\n"; - // draw floorplan - mapOutline.setColorHex("#888888"); - splot.add(&mapOutline); - for (Floorplan::Floor* floor : map->floors) { - for (Floorplan::FloorObstacle* obs : floor->obstacles) { - Floorplan::FloorObstacleLine* line = dynamic_cast(obs); - if (line) { - const K::GnuplotPoint3 p1(line->from.x, line->from.y, floor->atHeight); - const K::GnuplotPoint3 p2(line->to.x, line->to.y, floor->atHeight); - mapOutline.addSegment(p1, p2); - } - } - for (Floorplan::Stair* s : floor->stairs) { - for (const Floorplan::StairPart& sp : s->getParts()) { - const K::GnuplotPoint3 p1(sp.start.x, sp.start.y, sp.start.z + floor->atHeight); - const K::GnuplotPoint3 p2(sp.end.x, sp.end.y, sp.end.z + floor->atHeight); - mapOutline.addSegment(p1, p2); - } - } - for (Floorplan::FloorOutlinePolygon* poly : floor->outline) { - gp << "set object polygon from "; - for (size_t i = 0; i < poly->poly.points.size(); ++i) { - if (i > 0) {gp << " to ";} - const Point2 pt = poly->poly.points[i]; - gp << pt.x << "," << pt.y << "," << floor->atHeight << " "; - } - gp << " fs solid fc rgb " << ( poly->outdoor ? "'#ddffdd'" : "'#dddddd'"); - gp << "\n"; - } - } + // how to draw the floorplan + mapOutlineConcrete.setColorHex("#888888"); mapOutlineConcrete.setLineWidth(2); + mapOutlineDrywall.setColorHex("#888888"); + mapOutlineGlass.setColorHex("#888888"); mapOutlineGlass.setDashType(2); + splot.add(&mapOutlineConcrete); + splot.add(&mapOutlineDrywall); + splot.add(&mapOutlineGlass); + + splot.add(&particles); particles.setPointSize(0.33); particles.setColorHex("#0000ff"); splot.add(&pathReal); pathReal.setLineWidth(2); pathReal.setColorHex("#0000ff"); splot.add(&pathEst); @@ -117,6 +183,64 @@ public: gp << "set label '" << txt << "' at " << pos.x << "," << pos.y << "," << pos.z << "\n"; } + void addRectangle(const Point3 p1, const Point3 p2, const Color c, bool front = false, bool fill = true) { + std::vector points = { + Point3(p1.x, p1.y, p1.z), + Point3(p2.x, p1.y, p1.z), + Point3(p2.x, p2.y, p1.z), + Point3(p1.x, p2.y, p1.z), + Point3(p1.x, p1.y, p1.z), + }; + addPolygon(points, c.toHEX(), front, fill); + } + + void addPolygon(const std::vector& points, const std::string& color, bool front = false, bool fill = true) { + + for (const Point3 p : points) { + if (p.z < settings.minZ) {return;} + if (p.z > settings.maxZ) {return;} + } + + gp << "set object polygon from "; + for (size_t i = 0; i < points.size(); ++i) { + const Point3 p = points[i]; + if (i > 0) {gp << " to ";} + gp << p.x << "," << p.y << "," << p.z << " "; + } + gp << (front ? "front" : ""); + if (fill) {gp << " fs solid ";} else {gp << " fs transparent ";} + gp << " fc rgb " << "'" << color << "'"; + gp << "\n"; + + } + + void setZRange(const float min, const float max) { + gp << "set zrange [" << min << ":" << max << "]\n"; + } + + + void addFloorRect(const Point3 pos_m, const float size, Color c) { + + const Point3 p1 = pos_m + Point3(-size, -size, 0); + const Point3 p2 = pos_m + Point3(+size, -size, 0); + const Point3 p3 = pos_m + Point3(+size, +size, 0); + const Point3 p4 = pos_m + Point3(-size, +size, 0); + + std::vector points = {p1,p2,p3,p4,p1}; + + addPolygon(points, c.toHEX()); + +// gp << "set object polygon from "; +// for (size_t i = 0; i < points.size(); ++i) { +// const Point3 p = points[i]; +// if (i > 0) {gp << " to ";} +// gp << p.x << "," << p.y << "," << p.z << " "; +// } +// gp << "front fs solid fc rgb " << "'" << c.toHEX() << "'"; +// gp << "\n"; + + } + void setTitle(const std::string& title) { gp << "set title '" << title << "'\n"; } @@ -129,11 +253,109 @@ public: } } + void equalXY() { + gp << "set view equal xy\n"; + } + + void setView(const float degX, const float degY) { + gp << "set view " << degX << "," << degY << "\n"; + } + + void setScale(const float x, const float y) { + gp << "set multiplot layout 1,1 scale " << x << "," << y << "\n"; + } + + void writeCodeTo(const std::string& file) { + this->codeFile = file; + } + + void noFrame() { + gp << "unset border\n"; + gp << "unset xtics\n"; + gp << "unset ytics\n"; + gp << "unset ztics\n"; + } + + void writeEpsTex(const std::string file, K::GnuplotSize size = K::GnuplotSize(8.5, 5.1)) { + gp.setTerminal("epslatex", size); + gp.setOutput(file); + } + void plot() { gp.draw(splot); + gp << "unset multiplot\n"; // scaling + if (codeFile != "") { + std::ofstream out(codeFile); + out << gp.getBuffer(); + out.close(); + } gp.flush(); } + + void buildFloorplan() { + + std::vector floors; + + // only some floors?? + if (settings.floors.empty()) { + floors = map->floors; + } else { + for (int i : settings.floors) { + floors.push_back(map->floors[i]); + } + } + + + for (Floorplan::Floor* floor : floors) { + + // plot obstacles + if (settings.obstacles) { + for (Floorplan::FloorObstacle* obs : floor->obstacles) { + Floorplan::FloorObstacleLine* line = dynamic_cast(obs); + if (line) { + const K::GnuplotPoint3 p1(line->from.x, line->from.y, floor->atHeight); + const K::GnuplotPoint3 p2(line->to.x, line->to.y, floor->atHeight); + switch(line->material) { + case Floorplan::Material::CONCRETE: mapOutlineConcrete.addSegment(p1, p2); break; + case Floorplan::Material::GLASS: mapOutlineGlass.addSegment(p1, p2); break; + case Floorplan::Material::UNKNOWN: + case Floorplan::Material::DRYWALL: mapOutlineDrywall.addSegment(p1, p2); break; + } + + + } + } + } + + // plot the floor's outline + if (settings.outline) { + for (Floorplan::FloorOutlinePolygon* poly : floor->outline) { + gp << "set object polygon from "; + for (size_t i = 0; i < poly->poly.points.size() + 1; ++i) { + if (i > 0) {gp << " to ";} + const Point2 pt = poly->poly.points[i % poly->poly.points.size()]; // ensures closing the polygon + gp << pt.x << "," << pt.y << "," << floor->atHeight << " "; + } + gp << " fs solid fc rgb " << ( poly->outdoor ? "'#bbeebb'" : "'#dddddd'"); + gp << "\n"; + } + } + + // plot the stairs as polygon + if (settings.stairs) { + for (Floorplan::Stair* s : floor->stairs) { + std::vector quads = Floorplan::getQuads(s->getParts(), floor); + for (const Floorplan::Quad3& q : quads) { + addPolygon({q.p1, q.p2, q.p3, q.p4, q.p1}, "#c0c0c0"); + } + } + } + + } + + } + }; #endif // PLOTTY_H diff --git a/Settings.h b/Settings.h index c0b1a31..bef3f1f 100644 --- a/Settings.h +++ b/Settings.h @@ -6,6 +6,7 @@ namespace Settings { + const std::string pathData = "/apps/android/workspace/OTHER2017/data/"; const std::string pathWalks = "/apps/android/workspace/OTHER2017/data/"; const std::string path1a = pathWalks + "path1/1490208103510.csv"; @@ -18,6 +19,52 @@ namespace Settings { const std::string fMap = "/apps/android/workspace/IndoorMap/maps/SHL37.xml"; const std::string fCalib = "/apps/android/workspace/OTHER2017/data/wifi_fp_all.dat"; + const std::string fPathGFX = "/apps/android/workspace/OTHER2017/tex/gfx/"; + + int numParticles = 5000; + + float smartphoneAboveGround = 1.3; + + namespace IMU { + const float turnSigma = 1.5 + 1.5;//1.5; + const float stepLength = 0.80; + const float stepSigma = 0.40; + } + + namespace Grid { + constexpr int gridSize_cm = 20; + } + + namespace Filter { + const Timestamp updateEvery = Timestamp::fromMS(500); + } + + +// //const GridPoint destination = GridPoint(70*100, 35*100, 0*100); // use destination +// const GridPoint destination = GridPoint(0,0,0); // do not use destination + +// namespace SensorDebug { +// const Timestamp updateEvery = Timestamp::fromMS(200); +// } + + namespace WiFiModel { + + constexpr float sigma = 8.0; + + /** if the wifi-signal-strengths are stored on the grid-nodes, this needs a grid rebuild! */ + constexpr float TXP = -44; + constexpr float EXP = 2.5; + constexpr float WAF = -8.0; +// constexpr float TXP = -64.5896; +// constexpr float EXP = 1.25986; +// constexpr float WAF = -2.47467; + + // how to perform VAP grouping + const VAPGrouper vg_calib = VAPGrouper(VAPGrouper::Mode::LAST_MAC_DIGIT_TO_ZERO, VAPGrouper::Aggregation::AVERAGE); + const VAPGrouper vg_eval = VAPGrouper(VAPGrouper::Mode::LAST_MAC_DIGIT_TO_ZERO, VAPGrouper::Aggregation::AVERAGE); + } + + namespace GroundTruth { // IPIN2017 [toni] diff --git a/main.cpp b/main.cpp index 24ff843..0b0ccc9 100644 --- a/main.cpp +++ b/main.cpp @@ -1,3 +1,5 @@ +#define BREAK raise(SIGTRAP); + #include "Indoor/sensors/radio/setup/WiFiOptimizer.h" #include "Indoor/sensors/radio/setup/WiFiFingerprint.h" #include "Indoor/sensors/radio/setup/WiFiFingerprints.h" @@ -10,6 +12,7 @@ #include "Indoor/floorplan/v2/FloorplanHelper.h" #include +#include #include #include #include @@ -22,11 +25,102 @@ #include "EvalWalk.h" #include "EvalData.h" #include "EvalWiFi.h" +#include "EvalWiFiSigStrength.h" + +#include "PlotErrFunc.h" + +// build plots for the paper +void paperOutputs() { + + Floorplan::IndoorMap* map = Floorplan::Reader::readFromFile(Settings::fMap); + + if (1==1){ + EvalWiFiSigStrength sig(Settings::fMap, Settings::fCalib); + Plotty* p = new Plotty(map); + p->writeCodeTo(Settings::fPathGFX + "compare-wifi-in-out.gp"); + p->writeEpsTex(Settings::fPathGFX + "compare-wifi-in-out.tex"); + p->settings.floors = {0}; + p->settings.maxZ = 1; + p->buildFloorplan(); + sig.forAP_avg(p, MACAddress("d8:84:66:4a:23:d0")); + p->equalXY(); + p->setView(0,0); + p->setScale(3.1, 3.1); + p->addRectangle(Point3(62, 24, 0), Point3(72, 34, 0), Color::fromRGB(0,0,0), false, false); + p->noFrame(); + p->plot(); + delete p; + } + + if (1==1) { + + const bool ignoreStaircases = false; + const bool ignoreOutdoor = false; + EvalCompareOptAllFixed allFixed(Settings::fMap, Settings::fCalib, ignoreStaircases, ignoreOutdoor); + + K::Statistics s1 = allFixed.fixedPosFixedParamsForAll(); //BREAK; + K::Statistics s2 = allFixed.fixedPosOptParamsForAll(); //BREAK; + K::Statistics s3 = allFixed.fixedPosOptParamsForEach(); //BREAK; + K::Statistics s4 = allFixed.optPosOptParamsForEach(); //BREAK; + + PlotErrFunc pef("\\small{error (dB)}", "\\small{fingerprints (\\%)}"); + pef.add("\\small{empiric}", s1); + pef.add("\\small{real pos, opt params}", s2); + pef.add("\\small{real pos, opt params [per AP]}", s3); + pef.add("\\small{opt pos, opt params [per AP]}", s4); + + pef.getGP().setTerminal("epslatex", K::GnuplotSize(8.5, 5)); + pef.getGP().setOutput(Settings::fPathGFX + "wifi-opt-error-hist-methods.tex"); + pef.writeCodeTo(Settings::fPathGFX + "wifi-opt-error-hist-methods.gp"); + pef.getGP() << "set key right bottom width -4 samplen 0.5\n"; + pef.getGP() << "set rmargin 0.4\n"; + pef.getGP() << "set tmargin 0.4\n"; + pef.plot(); + + } + + // error histogram all pos, all params, between in/out/stair, in/out, in/stair, in + if(1==1){ + EvalCompareOptAllFixed e1(Settings::fMap, Settings::fCalib, false, false); + EvalCompareOptAllFixed e2(Settings::fMap, Settings::fCalib, true, false); + EvalCompareOptAllFixed e3(Settings::fMap, Settings::fCalib, false, true); + EvalCompareOptAllFixed e4(Settings::fMap, Settings::fCalib, true, true); + + K::Statistics s1 = e1.optPosOptParamsForEach(); + K::Statistics s2 = e2.optPosOptParamsForEach(); + K::Statistics s3 = e3.optPosOptParamsForEach(); + K::Statistics s4 = e4.optPosOptParamsForEach(); + + PlotErrFunc pef("\\small{error (dB)}", "\\small{fingerprints (\\%)}"); + pef.add("\\small{floor + stairs + out}", s1); + pef.add("\\small{floor + out}", s2); + pef.add("\\small{floor + stairs}", s3); + pef.add("\\small{floor}", s4); + + pef.getGP().setTerminal("epslatex", K::GnuplotSize(8.5, 5)); + pef.getGP().setOutput(Settings::fPathGFX + "wifi-opt-error-hist-stair-outdoor.tex"); + pef.writeCodeTo(Settings::fPathGFX + "wifi-opt-error-hist-stair-outdoor.gp"); + pef.getGP() << "set key right bottom width -3\n"; + pef.getGP() << "set rmargin 0.4\n"; + pef.getGP() << "set tmargin 0.4\n"; + pef.plot(); + + } + +} -#define BREAK raise(SIGTRAP); int main(void) { +// paperOutputs(); return 0; + + if (1 == 1) { + Floorplan::IndoorMap* map = Floorplan::Reader::readFromFile(Settings::fMap);; + EvalWalk walk(map); + walk.walk1(); + return 0; + } + // test gps within data files if (1 == 0) { EvalData::dumpGPSforPath(Settings::path1a); BREAK; @@ -35,35 +129,83 @@ int main(void) { EvalData::dumpGPSforPath(Settings::path2b); BREAK; } - // test wifi within data files - if (1 == 1) { - //EvalWiFi ew1(Settings::fMap, Settings::path2a, Settings::GroundTruth::path2); - EvalWiFi ew1(Settings::fMap, Settings::path2a, Settings::GroundTruth::path1); - //ew1.fixedParams(-40, 2.5, -8); BREAK; - ew1.fixedParams(-64.5905, 1.25988, -2.47863); BREAK; + // eval average signal-strength per AP + if (1 == 0) { + + EvalWiFiSigStrength ewss(Settings::fMap, Settings::fCalib); + ewss.perAP_avg(); + + } + + + // test wifi within data files + if (1 == 0) { + //EvalWiFi ew1(Settings::fMap, Settings::path2a, Settings::GroundTruth::path2); + EvalWiFi ew1(Settings::fMap, Settings::path2a, Settings::GroundTruth::path2); + //ew1.fixedParams(-40, 2.5, -8); BREAK; + //ew1.fixedParams(-64.5905, 1.25988, -2.47863); BREAK; + ew1.fixedParams(-59.4903,1.52411,-3.25077); BREAK; + } - // run walking // run earthmapping //testMapEarthReg(fMap); -// EvalApOpt eval(fMap, fCalib); -// eval.optAll(); - - - // run evaluation if (1 == 0) { - EvalCompareOptAllFixed allFixed(Settings::fMap, Settings::fCalib); - allFixed.fixedPosFixedParamsForAll(); - allFixed.fixedPosOptParamsForAll(); - allFixed.fixedPosOptParamsForEach(); - allFixed.optPosOptParamsForEach(); + EvalApOpt eval(Settings::fMap, Settings::fCalib); + eval.optAll(); } + // compare wifi opt methods + if (1 == 1) { + + const bool ignoreStaircases = false; + const bool ignoreOutdoor = false; + EvalCompareOptAllFixed allFixed(Settings::fMap, Settings::fCalib, ignoreStaircases, ignoreOutdoor); + + K::Statistics s1 = allFixed.fixedPosFixedParamsForAll(); //BREAK; + K::Statistics s2 = allFixed.fixedPosOptParamsForAll(); //BREAK; + K::Statistics s3 = allFixed.fixedPosOptParamsForEach(); //BREAK; + K::Statistics s4 = allFixed.optPosOptParamsForEach(); //BREAK; + + PlotErrFunc pef("error (dB)", "fingerprints (%)"); + pef.add("empiric", s1); + pef.add("real pos, opt params [same for all]", s2); + pef.add("real pos, opt params [for each]", s3); + pef.add("opt pos, opt params [for each]", s4); + pef.plot(); + + } + + // compare leaving out fingerprints + if (1 == 0) { + + EvalCompareOptAllFixed e1(Settings::fMap, Settings::fCalib, false, false); + EvalCompareOptAllFixed e2(Settings::fMap, Settings::fCalib, true, false); + EvalCompareOptAllFixed e3(Settings::fMap, Settings::fCalib, false, true); + EvalCompareOptAllFixed e4(Settings::fMap, Settings::fCalib, true, true); + + K::Statistics s1 = e1.optPosOptParamsForEach(); + K::Statistics s2 = e2.optPosOptParamsForEach(); + K::Statistics s3 = e3.optPosOptParamsForEach(); + K::Statistics s4 = e4.optPosOptParamsForEach(); + + PlotErrFunc pef("error (dB)", "fingerprints (%)"); + pef.add("floor + stairs + out", s1); + pef.add("floor + out", s2); + pef.add("floor + stairs", s3); + pef.add("floor", s4); + pef.plot(); + + } + + + + // Floorplan::IndoorMap* map = Floorplan::Reader::readFromFile("/apps/android/workspace/OTHER2017/data/SHL33a.xml"); diff --git a/pf/PF.h b/pf/PF.h new file mode 100644 index 0000000..59b40f2 --- /dev/null +++ b/pf/PF.h @@ -0,0 +1,328 @@ +#ifndef PF_H +#define PF_H + +#include + +#include +#include + +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include "../Settings.h" + +struct MyGridNode : public GridNode, public GridPoint {//, public WiFiGridNode<30> { + + float navImportance; + float getNavImportance() const { return navImportance; } + + float walkImportance; + float getWalkImportance() const { return walkImportance; } + + + /** empty ctor */ + MyGridNode() : GridPoint(-1, -1, -1) {;} + + /** ctor */ + MyGridNode(const int x_cm, const int y_cm, const int z_cm) : GridPoint(x_cm, y_cm, z_cm) {;} + + + static void staticDeserialize(std::istream& inp) { + //WiFiGridNode::staticDeserialize(inp); + } + + static void staticSerialize(std::ostream& out) { + //WiFiGridNode::staticSerialize(out); + } + +}; + +struct MyState : public WalkState, public WalkStateFavorZ, public WalkStateHeading { + + + /** ctor */ + MyState(const int x_cm, const int y_cm, const int z_cm) : WalkState(GridPoint(x_cm, y_cm, z_cm)), WalkStateHeading(Heading(0), 0) { + ; + } + + MyState() : WalkState(GridPoint()), WalkStateHeading(Heading(0), 0) { + ; + } + + MyState& operator += (const MyState& o) { + position += o.position; + return *this; + } + + MyState& operator /= (const float val) { + position /= val; + return *this; + } + + MyState operator * (const float val) const { + MyState copy = *this; + copy.position = copy.position * val; + return copy; + } + +}; + +/** observed sensor data */ +struct MyObservation { + + /** wifi measurements */ + WiFiMeasurements wifi; + + /** gps measurements */ + GPSData gps; + + // TODO: switch to a general activity enum/detector for barometer + accelerometer + ...? + /** detected activity */ + ActivityButterPressure::Activity activity; + + /** time of evaluation */ + Timestamp currentTime; + +}; + +/** (observed) control data */ +struct MyControl { + + /** turn angle (in radians) since the last transition */ + float turnSinceLastTransition_rad = 0; + + /** number of steps since the last transition */ + int numStepsSinceLastTransition = 0; + + /** absolute heading in radians */ + float compass_azimuth = 0; + + // TODO: switch to a general activity enum/detector using barometer + accelerometer? + /** currently detected activity */ + ActivityButterPressure::Activity activity; + + /** reset the control-data after each transition */ + void resetAfterTransition() { + turnSinceLastTransition_rad = 0; + numStepsSinceLastTransition = 0; + } + +}; + +class PFInit : public K::ParticleFilterInitializer { + +private: + + Grid* grid; + +public: + + PFInit(Grid* grid) : grid(grid) { + + } + + virtual void initialize(std::vector>& particles) override { + + std::minstd_rand gen; + std::uniform_int_distribution distIdx(0, grid->getNumNodes()-1); + std::uniform_real_distribution distHead(0, 2*M_PI); + + for (K::Particle& p : particles) { + const int idx = distIdx(gen); + const MyGridNode& node = (*grid)[idx]; + p.state.position = node; // random position + p.state.heading.direction = Heading(distHead(gen)); // random heading + p.weight = 1.0 / particles.size(); // equal weight + } + + } + +}; + +class PFTrans : public K::ParticleFilterTransition { + +public: + + /** local, static control-data COPY */ + MyControl ctrl; + + Grid* grid; + GridWalker walker; + + WalkModuleFavorZ modFavorZ; + WalkModuleHeadingControl modHeading; + WalkModuleNodeImportance modImportance; + WalkModuleFollowDestination modDestination; + WalkModuleActivityControl modActivity; + + std::minstd_rand gen; + +public: + + PFTrans(Grid* grid) : grid(grid), modHeading(&ctrl, Settings::IMU::turnSigma), modDestination(*grid), modActivity(&ctrl) { + + //walker.addModule(&modFavorZ); + walker.addModule(&modHeading); + //walker.addModule(&modImportance); + //walker.addModule(&modActivity); + +// if (Settings::destination != GridPoint(0,0,0)) { +// //walker.addModule(&modDestination); +// modDestination.setDestination(grid->getNodeFor(Settings::destination)); +// } + + } + + + + + void transition(std::vector>& particles, const MyControl* _ctrl) override { + + // local copy!! observation might be changed async outside!! (will really produces crashes!) + this->ctrl = *_ctrl; + ((MyControl*)_ctrl)->resetAfterTransition(); + + std::normal_distribution noise(0, Settings::IMU::stepSigma); + + // sanity check + Assert::equal((int)particles.size(), Settings::numParticles, "number of particles does not match the settings!"); + + //for (K::Particle& p : particles) { + //#pragma omp parallel for num_threads(3) + for (int i = 0; i < Settings::numParticles; ++i) { + + //#pragma omp atomic + const float dist_m = std::abs(ctrl.numStepsSinceLastTransition * Settings::IMU::stepLength + noise(gen)); + + K::Particle& p = particles[i]; + + double prob; + p.state = walker.getDestination(*grid, p.state, dist_m, prob); + //p.weight *= prob;//(prob > 0.01) ? (1.0) : (0.15); + //p.weight = (prob > 0.01) ? (1.0) : (0.15); + //p.weight = prob; + //p.weight = 1.0; // reset + //p.weight = std::pow(p.weight, 0.1); // make all particles a little more equal [less strict] + //p.weight *= std::pow(prob, 0.1); // add grid-walk-probability + p.weight = prob; // grid-walk-probability + if (p.weight != p.weight) {throw Exception("nan");} + + } + + } + +}; + +class PFEval : public K::ParticleFilterEvaluation { + + Grid* grid; + + WiFiModelLogDistCeiling& wifiModel; + + + WiFiObserverFree wiFiProbability; // free-calculation + //WiFiObserverGrid wiFiProbability; // grid-calculation + + // smartphone is 1.3 meter above ground + const Point3 person = Point3(0,0,Settings::smartphoneAboveGround); + +public: + + PFEval(Grid* grid, WiFiModelLogDistCeiling& wifiModel) : + grid(grid), wifiModel(wifiModel), + + wiFiProbability(Settings::WiFiModel::sigma, wifiModel) { // WiFi free + //wiFiProbability(Settings::WiFiModel::sigma) { // WiFi grid + + + } + + double getStairProb(const K::Particle& p, const ActivityButterPressure::Activity act) { + + const float kappa = 0.75; + + const MyGridNode& gn = grid->getNodeFor(p.state.position); + switch (act) { + + case ActivityButterPressure::Activity::STAY: + if (gn.getType() == GridNode::TYPE_FLOOR) {return kappa;} + if (gn.getType() == GridNode::TYPE_DOOR) {return kappa;} + {return 1-kappa;} + + case ActivityButterPressure::Activity::UP: + case ActivityButterPressure::Activity::DOWN: + if (gn.getType() == GridNode::TYPE_STAIR) {return kappa;} + if (gn.getType() == GridNode::TYPE_ELEVATOR) {return kappa;} + {return 1-kappa;} + + } + + return 1.0; + + } + + double evaluation(std::vector>& particles, const MyObservation& _observation) override { + + double sum = 0; + + // local copy!! observation might be changed async outside!! (will really produces crashes!) + const MyObservation observation = _observation; + + // vap-grouping + const int numAP1 = observation.wifi.entries.size(); + const WiFiMeasurements wifiObs = Settings::WiFiModel::vg_eval.group(_observation.wifi); + const int numAP2 = wifiObs.entries.size(); + + Log::add("Filter", "VAP: " + std::to_string(numAP1) + " -> " + std::to_string(numAP2)); + + // sanity check + Assert::equal((int)particles.size(), Settings::numParticles, "number of particles does not match the settings!"); + + //#pragma omp parallel for num_threads(3) + for (int i = 0; i < Settings::numParticles; ++i) { + + K::Particle& p = particles[i]; + + // WiFi free + const double pWiFi = wiFiProbability.getProbability(p.state.position.inMeter()+person, observation.currentTime, wifiObs); + + // WiFi grid + //const MyGridNode& node = grid->getNodeFor(p.state.position); + //const double pWiFi = wiFiProbability.getProbability(node, observation.currentTime, wifiObs); + + + //Log::add("xxx", std::to_string(observation.currentTime.ms()) + "_" + std::to_string(wifiObs.entries[0].ts.ms())); + + const double pStair = 1;//getStairProb(p, observation.activity); + const double pGPS = 1; + const double prob = pWiFi * pGPS * pStair; + + p.weight *= prob; // NOTE: keeps the weight returned by the transition step! + //p.weight = prob; // does NOT keep the weights returned by the transition step + if (p.weight != p.weight) {throw Exception("nan");} + + #pragma omp atomic + sum += p.weight; + + } + + return sum; + + } + +}; + +#endif // PF_H diff --git a/tex/bare_conf.tex b/tex/bare_conf.tex new file mode 100644 index 0000000..b2969ee --- /dev/null +++ b/tex/bare_conf.tex @@ -0,0 +1,222 @@ + +%% bare_conf.tex +%% V1.4b +%% 2015/08/26 +%% by Michael Shell +%% See: +%% http://www.michaelshell.org/ +%% for current contact information. +%% +%% This is a skeleton file demonstrating the use of IEEEtran.cls +%% (requires IEEEtran.cls version 1.8b or later) with an IEEE +%% conference paper. +%% +%% Support sites: +%% http://www.michaelshell.org/tex/ieeetran/ +%% http://www.ctan.org/pkg/ieeetran +%% and +%% http://www.ieee.org/ + +%%************************************************************************* +%% Legal Notice: +%% This code is offered as-is without any warranty either expressed or +%% implied; without even the implied warranty of MERCHANTABILITY or +%% FITNESS FOR A PARTICULAR PURPOSE! +%% User assumes all risk. +%% In no event shall the IEEE or any contributor to this code be liable for +%% any damages or losses, including, but not limited to, incidental, +%% consequential, or any other damages, resulting from the use or misuse +%% of any information contained here. +%% +%% All comments are the opinions of their respective authors and are not +%% necessarily endorsed by the IEEE. +%% +%% This work is distributed under the LaTeX Project Public License (LPPL) +%% ( http://www.latex-project.org/ ) version 1.3, and may be freely used, +%% distributed and modified. A copy of the LPPL, version 1.3, is included +%% in the base LaTeX documentation of all distributions of LaTeX released +%% 2003/12/01 or later. +%% Retain all contribution notices and credits. +%% ** Modified files should be clearly indicated as such, including ** +%% ** renaming them and changing author support contact information. ** +%%************************************************************************* + + +% *** Authors should verify (and, if needed, correct) their LaTeX system *** +% *** with the testflow diagnostic prior to trusting their LaTeX platform *** +% *** with production work. The IEEE's font choices and paper sizes can *** +% *** trigger bugs that do not appear when using other class files. *** *** +% The testflow support page is at: +% http://www.michaelshell.org/tex/testflow/ + + + +\documentclass[conference]{IEEEtran} +% Some Computer Society conferences also require the compsoc mode option, +% but others use the standard conference format. +% +% If IEEEtran.cls has not been installed into the LaTeX system files, +% manually specify the path to it like: +% \documentclass[conference]{../sty/IEEEtran} + + +% needed packages + +\usepackage{color, colortbl} +%\usepackage[table]{xcolor} +\usepackage{cite} +\usepackage{graphicx} +\usepackage{amsfonts} + +\usepackage[cmex10]{amsmath} + +\interdisplaylinepenalty=2500 +\usepackage{algorithmic} +\usepackage{array} +\usepackage{mdwmath} +\usepackage{mdwtab} +\usepackage{eqparbox} + +\usepackage{epstopdf} +%\usepackage{ulem} + + + + +% replacement for the SI package +\newcommand{\SI}[2]{\ensuremath{#1}\text{\,#2}} +\newcommand{\SIrange}[3]{\ensuremath{#1} to \ensuremath{#2}\text{\,#3}} + +% units for the SI package +\newcommand{\centimeter}{cm} +\newcommand{\meter}{m} +\newcommand{\per}{/} +\newcommand{\milli}{m} +\newcommand{\second}{s} +\newcommand{\giga}{G} +\newcommand{\hertz}{Hz} +\newcommand{\dBm}{dBm} +\newcommand{\percent}{\%} +\newcommand{\decibel}{dB} +\newcommand{\dB}{dB} +\newcommand{\hpa}{hPa} +\newcommand{\degree}{\ensuremath{^{\circ}}} + +% missing math operators +\DeclareMathOperator*{\argmin}{arg\,min} +\DeclareMathOperator*{\argmax}{arg\,max} + + +% vector and matrix typesetting +\renewcommand{\vec}[1]{\boldsymbol{#1}} % italic and greek symbols +\newcommand{\mat}[1]{\vec{#1}} % the same as vec + + +%other macros +\newcommand{\noStep}{\overline{\text{step}}} + + +% gfx include folder +\graphicspath{ {gfx/baro/},{gfx/graph/},{gfx/paths/},{gfx/eval/},{gfx/},{gfx/grid/}} + + +% correct bad hyphenation here +\hyphenation{op-tical net-works semi-conduc-tor} + + +% input stuff +\input{misc/keywords} +\input{misc/functions} + + +\begin{document} +% +% paper title +% Titles are generally capitalized except for words such as a, an, and, as, +% at, but, by, for, in, nor, of, on, or, the, to and up, which are usually +% not capitalized unless they are the first or last word of the title. +% Linebreaks \\ can be used within to get better formatting as desired. +% Do not put math or special symbols in the title. +\title{minimizing system setup times } + + +% author names and affiliations +% use a multiple column layout for up to three different +% affiliations +\author{ + + \IEEEauthorblockN{Frank Ebner, Toni Fetzer and Frank Deinzer}% + \IEEEauthorblockA{% + Faculty of Computer Science and Business Information Systems\\ + University of Applied Sciences W\"urzburg-Schweinfurt\\ + W\"urzburg, Germany\\ + \{frank.ebner, toni.fetzer, frank.deinzer\}@fhws.de\\ + } + \and + + \IEEEauthorblockN{Marcin Grzegorzek} + \IEEEauthorblockA{% + Pattern Recognition Group \\ + University of Siegen\\ + Siegen, Germany\\ + \{marcin.grzegorzek\}@uni-siegen.de + }% +} + +% conference papers do not typically use \thanks and this command +% is locked out in conference mode. If really needed, such as for +% the acknowledgment of grants, issue a \IEEEoverridecommandlockouts +% after \documentclass + +% use for special paper notices +%\IEEEspecialpapernotice{(Invited Paper)} + + +% make the title area +\maketitle + +% As a general rule, do not put math, special symbols or citations +% in the abstract +\input{chapters/abstract} + + +% For peer review papers, you can put extra information on the cover +% page as needed: +% \ifCLASSOPTIONpeerreview +% \begin{center} \bfseries EDICS Category: 3-BBND \end{center} +% \fi +% +% For peerreview papers, this IEEEtran command inserts a page break and +% creates the second title. It will be ignored for other modes. +\IEEEpeerreviewmaketitle + + +\input{chapters/introduction} + +\input{chapters/relatedwork} + +\input{chapters/experiments} + +\input{chapters/conclusion} + + +% conference papers do not normally have an appendix + +% use section* for acknowledgment +%\section*{Acknowledgment} + +%The authors would like to thank... + +% balancing +%\IEEEtriggeratref{8} +% The "triggered" command can be changed if desired: +%\IEEEtriggercmd{\enlargethispage{-5in}} + + +% references section +\bibliographystyle{IEEEtran} +\bibliography{IEEEabrv,egbib} + +\end{document} + + diff --git a/tex/chapters/abstract.tex b/tex/chapters/abstract.tex new file mode 100644 index 0000000..af14975 --- /dev/null +++ b/tex/chapters/abstract.tex @@ -0,0 +1 @@ +abstract diff --git a/tex/chapters/conclusion.tex b/tex/chapters/conclusion.tex new file mode 100644 index 0000000..c62279b --- /dev/null +++ b/tex/chapters/conclusion.tex @@ -0,0 +1 @@ +conclusion diff --git a/tex/chapters/experiments.tex b/tex/chapters/experiments.tex new file mode 100644 index 0000000..51dfdc5 --- /dev/null +++ b/tex/chapters/experiments.tex @@ -0,0 +1,15 @@ +experiments + +Lorem ipsum dolor sit amet, consetetur sadipscing elitr, sed diam nonumy eirmod tempor invidunt ut labore et dolore magna aliquyam erat, sed diam voluptua. At vero eos et accusam et justo duo dolores et ea rebum. Stet clita kasd gubergren, no sea takimata sanctus est Lorem ipsum dolor sit amet. Lorem ipsum dolor sit amet, consetetur sadipscing elitr, sed diam nonumy eirmod tempor invidunt ut labore et dolore magna aliquyam erat, sed diam voluptua. At vero eos et accusam et justo duo dolores et ea rebum. Stet clita kasd gubergren, no sea takimata sanctus est Lorem ipsum dolor sit amet. + +\input{gfx/compare-wifi-in-out.tex} +starker einfluss der glasscheiben.. 3 meter nach dem AP ist nur noch sehr wenig uebrig + + +\input{gfx/wifi-opt-error-hist-methods.tex} + +\input{gfx/wifi-opt-error-hist-stair-outdoor.tex} +outdoor hat insgesamt nicht all zu viel einfluss, da die meisten APs +an den outdoor punkten kaum gesehen werden. auf einzelne APs kann +der einfluss jedoch recht groß sein, siehe den fingerprint plot von +dem einen ausgewählten AP diff --git a/tex/chapters/interoduction.tex b/tex/chapters/interoduction.tex new file mode 100644 index 0000000..af14975 --- /dev/null +++ b/tex/chapters/interoduction.tex @@ -0,0 +1 @@ +abstract diff --git a/tex/chapters/introduction.tex b/tex/chapters/introduction.tex new file mode 100644 index 0000000..17bbd55 --- /dev/null +++ b/tex/chapters/introduction.tex @@ -0,0 +1 @@ +introduction diff --git a/tex/chapters/relatedwork.tex b/tex/chapters/relatedwork.tex new file mode 100644 index 0000000..468af66 --- /dev/null +++ b/tex/chapters/relatedwork.tex @@ -0,0 +1,3 @@ +relatedwork + +\cite{Ebner-15} diff --git a/tex/egbib.bib b/tex/egbib.bib new file mode 100644 index 0000000..65b5eb1 --- /dev/null +++ b/tex/egbib.bib @@ -0,0 +1,2709 @@ +@Book{Szeliski08, + author = {R. Szeliski}, + title = {Computer Vision: Algorithms and Applications}, + publisher = {Springer}, + year = {2010}, +} +@book{grewal2007global, + title={Global positioning systems, inertial navigation, and integration}, + author={Grewal, Mohinder S and Weill, Lawrence R and Andrews, Angus P}, + year={2007}, + publisher={John Wiley \& Sons} +} + +IGNORE{thrun2005probabilistic, + title={Probabilistic robotics}, + author={Thrun, Sebastian and Burgard, Wolfram and Fox, Dieter}, + year={2005}, + publisher={MIT press} +} + +@Book{Daszkow03, + author = {Alexandra Daszkowski}, + title = {Das Körperbild bei Frauen und Männern}, + publisher = {Tectum Verlag}, + year = {2003}, +} + +@misc{Perceptron, + author = {Perceptron, Inc.}, + title = {Hersteller von 3D Laser Scannern}, + note = {\url{http://www.perceptron.com/index.php/de/-produkte/3d-scanning-loesungen-g.html} [Stand 09. Februar 2014]}, +} + +@misc{David, + author = {David 3D Solutions}, + title = {Hersteller von 3D Laser Scannern}, +} + +@misc{KinectConstants, + author = {Microsoft}, + title = {Constanten des Kinect SDK}, + note = {\url{http://msdn.microsoft.com/en-us/library/hh855368} [Stand 09. Februar 2014]}, +} + +@misc{HuffYUV, + author = {Ben Rudiak-Gould}, + title = {HuffYUV Codec }, + note = {\url{http://neuron2.net/www.math.berkeley.edu/benrg/huffyuv.html} [Stand 09. Februar 2014]}, +} + +@misc{Konol11, + author = {Kurt Konolige and Patrick Mihelich}, + title = {Technical description of Kinect calibration}, + note = {\url{http://ftp.isr.ist.utl.pt/pub/roswiki/kinect_calibration(2f)technical.html} [Stand 09. Februar 2014]}, + year = {2011}, +} + +@misc{opencvImage, + author = {opencv dev team}, + title = {Reading and Writing Images and Video}, + note = {\url{http://docs.opencv.org/modules/highgui/doc/reading_and_writing_images_and_video.html?highlight=imwrite#imwrite} [Stand 21. Februar 2014]}, +} + +@misc{Javier13, + author = {Javier Penalva}, + title = {Kinect para Windows ya está listo para escanear cuerpos y objetos en 3D}, + note = {\url{http://www.xataka.com/consolas-y-videojuegos/kinect-para-windows-ya-esta-listo-para-escanear-cuerpos-y-objetos-en-3d} [Stand 18. Februar 2014]}, + year = {2013}, +} + +@misc{Baader, + author = {Baader Planetarium}, + title = {Der Begriff binning oder on-chip binning}, + note = {\url{http://www.sbig.de/universitaet/glossar-htm/binning.htm} [Stand 09. Februar 2014]}, +} + +@misc{Wunderlich12, + author = {D. Wunderlich}, + title = {Class description - FrameGrabber}, + note = {\url{http://pille.iwr.uni-heidelberg.de/~kinect01/doc/classdescription.html#kinectcloud-section} [Stand 09. Februar 2014]}, +} + +@misc{Aptina, + author = {Aptina}, + title = {MT9M001 Data Sheet}, + note = {\url{http://www.aptina.com/products/image_sensors/mt9m001c12stm/} [Stand 09. Februar 2014]}, +} + +@misc{OpenBeacon, + author = {OpenBeacon}, + title = {OpenBeacon.org}, + note = {\url{http://www.openbeacon.org/} [Stand 24. Februar 2014]}, +} + +@misc{embeddedVi, + author = {Embedded Vision}, + title = {3-D Sensors Bring Depth Discernment to Embedded Vision Designs}, + note = {\url{http://www.embedded-vision.com/platinum-members/embedded-vision-alliance/embedded-vision-training/documents/pages/3d-sensors-depth-discernment} [Stand 09. Februar 2014]}, +} + +@misc{mickin10, + author = {Microsoft}, + title = {PrimeSense Supplies 3-D-Sensing Technology to Project Natal for Xbox 360}, + note = {\url{http://www.microsoft.com/en-us/news/press/2010/mar10/03-31primesensepr.aspx} [Stand 09. Februar 2014]}, +} + +@misc{knies11, + author = {R. Knies}, + title = {Kinect Body Tracking Reaps Renown}, + note = {\url{http://research.microsoft.com/en-us/news/features/kinectskeletal-092711.aspx} [Stand 09. Februar 2014]}, +} + +@misc{msdnskeletal, + author = {Microsoft}, + title = {Skeletal Tracking}, + note = {\url{http://msdn.microsoft.com/en-us/library/hh973074.aspx} [Stand 09. Februar 2014]}, +} + +@inproceedings{Lang12, +author ={Benjamin Langmann and Klaus Hartmann and Otmar Loffeld}, +title = {Depth Camera Technology Comparison And Performance Evaluation}, +booktitle = {Int. Conf. on Pattern Recognition Applications and Methods}, +year = {2012}, +} + +@inproceedings{Bo06, +author={Wu Bo and R. Nevatia}, +booktitle={Computer Vision and Pattern Recognition, 2006 IEEE Computer Society Conf. on}, +title={Tracking of Multiple, Partially Occluded Humans based on Static Body Part Detection}, +year={2006}, +IGNOREmonth={June}, +volume={1}, +pages={951-958}, +} + +@inproceedings{feldmann03, + title={An Indoor Bluetooth-Based Positioning System: Concept, Implementation and Experimental Evaluation.}, + author={Feldmann, Silke and Kyamakya, Kyandoghere and Zapater, Ana and Lue, Zighuo}, + booktitle={Int. Conf. on Wireless Networks}, + pages={109--113}, + year={2003} +} + +@article{shotton2013real, + title={Real-time human pose recognition in parts from single depth images}, + author={Shotton, Jamie and Sharp, Toby and Kipman, Alex and Fitzgibbon, Andrew and Finocchio, Mark and Blake, Andrew and Cook, Mat and Moore, Richard}, + journal={Communications of the ACM}, + volume={56}, + number={1}, + pages={116--124}, + year={2013}, + publisher={ACM} +} + +@article{pei2010, + title={Using inquiry-based Bluetooth RSSI probability distributions for indoor positioning}, + author={Pei, Ling and Chen, Ruizhi and Liu, Jingbin and Kuusniemi, Heidi and Tenhunen, Tomi and Chen, Yuwei}, + journal={Journal of Global Positioning Systems}, + volume={9}, + number={2}, + pages={122--130}, + year={2010} +} + +@inproceedings{Fang09, +author={Shih-Hau Fang and Tsung-Nan Lin}, +booktitle={Intelligent Signal Processing, 2009. WISP 2009. IEEE Int. Symp. on}, +title={{Accurate WLAN Indoor Localization Based on RSS, Fluctuations Modeling}}, +year={2009}, +IGNOREmonth={Aug}, +pages={27-30}, +} + +@inproceedings{Shotton11, +author ={J. Shotton and R. Girshick and A. Fitzgibbon and T. Sharp and M. Cook and M. Finochio and R. Moore and P. Kohli and A. Criminisi and A. Kipman and A. Blacke}, +title = {Real-Time Human Pose Recognition in Parts from Single Depth Images}, +booktitle = {IEEE Computer Vision and Pattern Recognition (CVPR) 2011}, +year = {2011}, +} + +@article{Hartley1997, + author = {Richard I. Hartley}, + title = {Triangulation}, + journal = {Computer Vision and Image Understanding}, + year = {1997}, + volume = {68}, + number = {2}, + pages = {146--157}, +} + +@article{Wren97, +author={C.R. Wran and A. Azarbayejani and T. Darrell and A. P. Pentland.}, +journal={IEEE Transactions on Pattern Analysis and Machine Intelligence}, +title={Pfinder: real-time tracking of the human body}, +year={1997}, +IGNOREmonth={Jul}, +volume={19}, +number={7}, +pages={780-785}, +} + +@article{Koeping12, + author = {Lukas K\"oping and Thomas M\"uhsam and Christian Ofenberg and Bernhard Czech and Michael Bernard and Jens Schmer and Frank Deinzer}, + title = {Indoor Navigation Using Particle Filter and Sensor Fusion}, + journal = {Annu. of Navigation}, + year = {2012}, + volume = {19}, + number = {2}, + pages = {31--40}, + IGNOREmonth = {12}, +} + +@article{Ville09, + author = {Ville Honkavirta and Tommi Perälä and Simo Ali-Löytty and Robert Piche}, + title = {A Comparative Survey of WLAN Location Fingerprinting Methods}, + journal = {Workshop on Positioning, Navigation and Communication}, + year = {2009}, + volume = {6}, + number = {1}, + pages = {243--251}, +} + +@article{Saxena07, + author = {A. Saxena and Sung H. Chung and Andrew Y. Ng}, + title = {3-D Depth Reconstruction from a Single Still Image}, + journal = {Int. Journal of Computer Vision}, + year = {2008}, + volume = {76}, + number = {1}, + pages = {53--69}, +} + +@inbook{Hartley04, + author = {Richard I. Hartley and Andrew Zisserman}, + title = {Multiple View Geometry in Computer Vision}, + chapter = {Epipolar Geometry and the Fundamental Matrix}, + publisher = {Cambridge University Press}, + year = {2004}, +} + +@inbook{Hartley04Cam, + author = {Richard I. Hartley and Andrew Zisserman}, + title = {Multiple View Geometry in Computer Vision}, + chapter = {Camera Models}, + publisher = {Cambridge University Press}, + year = {2004}, +} + +@article{Bernardini02, + author = {Fausto Bernardini and Holly E. Rushmeier}, + title = {The 3D Model Acquisition Pipeline}, + journal = {Comput. Graph. Forum}, + year = {2002}, + volume = {21}, + number = {2}, + pages = {149--172}, +} + +@phdthesis{Forest04, + author = {Josep Forest i Collado}, + title = {New methods for triangulation-based shape acquisition using laser scanners}, + school = {Universitat de Girona}, + year = {2004} + } + +@phdthesis{Schaller11, + author = {Christian Schaller}, + title = {Time-of-Flight- A New Modality for Radiotherapy}, + school = {Universität Erlangen-Nürnberg}, + year = {2011} + } + +@inbook{Ishii12, + author = {Idaku Ishii}, + title = {Advanced Image Acquisition, Processing Techniques and Applications}, + chapter = {A Coded Structured Light Projection Method for High-Frame-Rate 3D Image Acquisition}, + publisher ={InTech}, + year = {2012}, +} + +@article{Scharstein03, + author = {Daniel Scharstein and Richard Szeliski}, + title = {High-Accuracy Stereo Depth Maps Using Structured Light}, + journal = {Computer Vision and Pattern Recognition, 2003. Proc.. 2003 IEEE Computer Society Conf. on}, + year = {2003}, + volume = {1}, + pages = {195--202}, +} + +@article{Bel57, + author = "Richard Bellman", + title = "A Markovian Decision Process", + journal = "Indiana Univ. Math. J.", + fjournal = "Indiana University Mathematics Journal", + volume = 6, + year = 1957, + issue = 4, + pages = "679--684", + issn = "0022-2518", +} + +@ARTICLE{fox2003bayesian, + title={Bayesian Filtering for Location Estimation}, + author={Fox, Dieter and Schulz, Dirk and Borriello, Gaetano and Hightower, Jeffrey and Liao, Lin}, + journal={IEEE pervasive computing}, + volume={2}, + number={3}, + pages={24--33}, + year={2003}, + publisher={IEEE Computer Society} +} + +@inproceedings{Luo07, +author={Luo, R.C. and Chun Chi Lai}, +booktitle={Advanced Robotics and Its Social Impacts, 2007. ARSO 2007. IEEE Workshop on}, +title={Indoor Mobile Robot Localization using Probabilistic Multi-Sensor Fusion}, +year={2007}, +IGNOREmonth={Dec}, +pages={1-6}, +keywords={feature extraction;mobile robots;sensor fusion;service robots;Hokuyo infrared range-finder;Polaroid 6500 ultrasonic rangers;feature extraction;indoor mobile robot localization;light refraction;mobile service robot;probabilistic multisensor fusion;servo sonar ring;Acoustic materials;Acoustic refraction;Acoustic sensors;Feature extraction;Indoor environments;Mobile robots;Sensor phenomena and characterization;Service robots;Servomechanisms;Sonar measurements}, +doi={10.1109/ARSO.2007.4531415},} + +@ARTICLE{Luo11, +author={Luo, R.C. and Chih-Chia Chang and Chun Chi Lai}, +journal={IEEE Sensors Journal}, +title={Multisensor Fusion and Integration: Theories, Applications, and its Perspectives}, +year={2011}, +IGNOREmonth={Dec}, +volume={11}, +number={12}, +pages={3122-3138}, +keywords={decision making;inference mechanisms;mechatronics;sensor fusion;autonomous mechatronic system;biomedical applications;classification methods;decision-making processes;estimation methods;inference methods;intelligent robots;microelectromechanical systems;military applications;multiple sensors;multisensor fusion and integration;nanoelectromechanical systems;Classification;Intelligent sensors;Kalman filters;Mechatronics;Robot sensing systems;Sensor fusion;Sensor systems;Classification methods;estimation methods;inference methods;intelligent robotics;mechatronics;multisensor fusion and integration (MFI)}, +doi={10.1109/JSEN.2011.2166383}, +ISSN={1530-437X},} + +@inproceedings{Blanchart09, +author={Blanchart, P. and Liyun He and Le Gland, F.}, +booktitle={FUSION 09}, +title={Information fusion for indoor localization}, +year={2009}, +IGNOREmonth={July}, +pages={2083-2090}, +keywords={belief networks;particle filtering (numerical methods);traffic information systems;Bayesian filter;cartographic constraints;indoor localization;information fusion;particle filter approximation;pedestrian user;proximity beacon measurements;Additive noise;Bayesian methods;Glands;Helium;Information filtering;Information filters;Information resources;Particle measurements;Position measurement;Telecommunications;cartographic constraints;information fusion;particle filtering;pedestrian navigation system (PNS);proximity beacon;ranging beacon},} + +@inproceedings{golding99, +author={Golding, A.R. and Lesh, N.}, +booktitle={Wearable Computers, 1999. Digest of Papers. The Third Int. Symp. on}, +title={Indoor Navigation Using a Diverse Set Of Cheap, Wearable Sensors}, +year={1999}, +IGNOREmonth={Oct}, +pages={29-36}, +keywords={accelerometers;computerised instrumentation;computerised navigation;force sensors;inference mechanisms;intelligent sensors;learning (artificial intelligence);magnetic sensors;magnetometers;optical sensors;sensor fusion;temperature sensors;user modelling;accelerometers;algorithm performance;context awareness;data cooking module;error rate;high-level features computation;indoor navigation algorithm;information integration;light sensors;machine learning;magnetometers;raw sensor signals;sensor input stream;temperature sensors;user location inference;user state inference;wearable sensors;Accelerometers;Context awareness;Error analysis;Machine learning;Magnetic sensors;Magnetometers;Navigation;Sensor phenomena and characterization;Temperature sensors;Wearable sensors}, +doi={10.1109/ISWC.1999.806640},} + +@inproceedings{meng11, +author={Wei Meng and Wendong Xiao and Wei Ni and Lihua Xie}, +booktitle={Indoor Positioning and Indoor Navigation (IPIN), Int. Conf. on}, +title={Secure and robust Wi-Fi fingerprinting indoor localization}, +year={2011}, +IGNOREmonth={Sept}, +pages={1-7}, +keywords={fingerprint identification;indoor radio;radio networks;telecommunication security;wireless LAN;K nearest neighbor algorithm;KNN;Wi-Fi wireless networks;access point attacks;distribution estimation;in-building communication infrastructures;indoor positioning;probabilistic fingerprinting localization method;random sample consensus;reference points;robust Wi-Fi fingerprinting indoor localization;secure Wi-Fi fingerprinting indoor localization;weighted-mean method;Accuracy;Distortion measurement;Histograms;IEEE 802.11 Standards;Probabilistic logic;Robustness;Sensors;RANSAC;Wi-Fi;fingerprinting;indoor localization;sensor network;signal strength;wireless network}, +doi={10.1109/IPIN.2011.6071908},} + +@inproceedings{boonsriwai13, +author={Boonsriwai, S. and Apavatjrut, A.}, +booktitle={Electrical Engineering/Electronics, Computer, Telecommunications and Information Technology (ECTI-CON), 2013 10th Int. Conf. on}, +title={Indoor WIFI localization on mobile devices}, +year={2013}, +IGNOREmonth={May}, +pages={1-5}, +keywords={Global Positioning System;buildings (structures);communication complexity;indoor radio;smart phones;wireless LAN;GPS;WIFI localization techniques;WIFI-enable devices;access points;building structures;computational complexity;fingerprinting localization techniques;indoor WIFI localization;localization algorithms;mobile devices;mobile users;multitrilateration;positioning calculation;reference position;signal degradation;smartphone;system resource consumption;wireless device;wireless signal;Accuracy;Buildings;Databases;Distance measurement;IEEE 802.11 Standards;Mobile communication;Mobile handsets}, +doi={10.1109/ECTICon.2013.6559592},} + +@inproceedings{Mirowsk13, +author={Mirowski, Piotr and Ho, Tin Kam and Saehoon Yi and MacDonald, Michael}, +booktitle={Indoor Positioning and Indoor Navigation (IPIN), Int. Conf. on}, +title={SignalSLAM: Simultaneous localization and mapping with mixed WiFi, Bluetooth, LTE and magnetic signals}, +year={2013}, +IGNOREmonth={Oct}, +pages={1-10}, +keywords={LTE;SLAM;WiFi;crowd-sourcing;kernel methods;localization}, +doi={10.1109/IPIN.2013.6817853},} + +@inproceedings{Biswas10, +author={Biswas, J. and Veloso, M.}, +booktitle={Robotics and Automation (ICRA), 2010 IEEE Int. Conf. on}, +title={WiFi localization and navigation for autonomous indoor mobile robots}, +year={2010}, +IGNOREmonth={May}, +pages={4379-4384}, +keywords={constraint theory;graph theory;mobile robots;path planning;sampling methods;signal detection;wireless LAN;WiFi localization;WiFi sensory data;autonomous indoor mobile robots;continuous perceptual model;custom built mobile robot;discrete graph based WiFi signal strength sampling;geometric constraints;Indoor environments;Mobile robots;Robot kinematics;Robot sensing systems;Robotics and automation;Robustness;Signal generators;Skeleton;Solid modeling;Sonar navigation}, +doi={10.1109/ROBOT.2010.5509842}, +ISSN={1050-4729}, +} + +@article{crowley1993principles, + title={Principles and techniques for sensor data fusion}, + author={Crowley, James L and Demazeau, Yves}, + journal={Signal processing}, + volume={32}, + number={1}, + pages={5--27}, + year={1993}, + publisher={Elsevier}, +} + +@phdthesis{Wiora01, + author = {Georg Wiora}, + title = {Optische 3D-Messtechnik: Präzise Gestaltvermessung mit einem erweiterten Streifenprojektionsverfahren}, + school = {Ruprechts-Karls-Universtität Heidelberg}, + year = {2001} + } + +@techreport{Bentell10, +author = {J. Bentell and P. Nies and J. Cloots and J. Vermeiren and B. Grietens and O. David and A. Shurkun and R. Schneider}, +title = {Flip Chipped INGaAs Photodiode Arrays For Gated Imaging With Eye-Safe Lasers}, +institution = {XenICs N.V.}, +year ={2010} +} + +@techreport{Kemeny08, +author = {J. Kemeny and K. Turner}, +title = {Ground-Based LiDAR Rock Slope Mapping And Assessment }, +institution = {University of Arizona - Department of Mining and Geological Engineering}, +year ={2008} +} + +@techreport{Smisek011, +author = {J. Smisek and M. Jancosek and T. Pajdla}, +title = {3D With Kinect}, +institution = {Czech Technical University in Prague}, +year ={2011} +} + +@techreport{Grimes08, +author = {J. Grimes}, +title = {Global Positioning System Standard Positioning Service Performance Standard}, +institution = {Department of Defense United States of America}, +year ={2008} +} + +@techreport{Konoldige11, +author = {K. Konoldige and P. Mihelich}, +title = {Technical Description Of Kinect Calibration}, +institution = {Willow Garage}, +year ={2011} + +} + +@article{Kolb2009, + author = {Andreas Kolb and Erhardt Barth and Reinhard Koch and Rasmus Larsen}, + title = {Time-of-Flight Cameras In Computer Graphics}, + journal = {Computer Graphics Forum}, + year = {2009}, + volume = {xx}, + number = {z}, + pages = {1--18}, +} + +@article{Khoshelham12, + author = {Kourosh Khoshelham and Oude Elberink}, + title = {Accuracy and Resolution of Kinect Depth Data for Indoor Mapping Applications}, + journal = {Sensors}, + year = {2012}, + volume = {12}, + pages = {1437--1454}, +} + +@inbook{Mutto13, + editor = {C. Dal Mutto and P. Zanuttigh and G. M. Cortelazzo}, + title = {Time-of-Flight Cameras And Microsoft Kinect}, + chapter = {Microsoft Kinect Range Camera }, + publisher ={Springer}, + year = {2013}, +} + +@patent{primePatent0310, + author = {B. Freedman and A. Shpunt and M. Machline and Y. Arieli}, + title = {Depth Mapping Using Projected Patterns}, + year = {2010}, + number = {US 0118123}, + type = {Patent}, + location = {US}, + REMurl = {http://appft1.uspto.gov/netacgi/nph-Parser?Sect1=PTO1&Sect2=HITOFF&d=PG01&p=1&u=/netahtml/PTO/srchnum.html&r=1&f=G&l=50&s1=20080240502.PGNR.}, +} + +@patent{primePatent0810, + author = {B. Freedman and A. Shpunt and Y. Arieli}, + title = {Distance-Varying Illumination and Imaging Techniques for Depth Mapping}, + year = {2010}, + number = {US 0290698}, + type = {Patent}, + location = {US}, + REMurl = {http://appft1.uspto.gov/netacgi/nph-Parser?Sect1=PTO1&Sect2=HITOFF&d=PG01&p=1&u=/netahtml/PTO/srchnum.html&r=1&f=G&l=50&s1=20100290698.PGNR.}, +} + +@ARTICLE{Ohya98, +author={Ohya, A. and Kosaka, A. and Kak, A.}, +journal={IEEE Transactions on Robotics and Automation}, +title={Vision-based navigation by a mobile robot with obstacle avoidance using single-camera vision and ultrasonic sensing}, +year={1998}, +IGNOREmonth={Dec}, +volume={14}, +number={6}, +pages={969-978}, +keywords={collision avoidance;mobile robots;navigation;robot vision;self-adjusting systems;ultrasonic transducers;YAMABICO robot;mobile robot;obstacle avoidance;position correction system;robot vision;self-localization;single-camera vision;ultrasonic sensing;vision-based navigation;Cameras;Computer vision;Image edge detection;Intelligent robots;Laboratories;Mobile robots;Navigation;Orbital robotics;Robot sensing systems;Robot vision systems}, +doi={10.1109/70.736780}, +ISSN={1042-296X},} + +@inproceedings{ganapathi10, +author={Ganapathi, V. and Plagemann, C. and Koller, D. and Thrun, S.}, +booktitle={Computer Vision and Pattern Recognition (CVPR), 2010 IEEE Conf. on}, +title={Real time motion capture using a single time-of-flight camera}, +year={2010}, +IGNOREmonth={June}, +pages={755-762}, +keywords={filtering theory;motion estimation;pose estimation;filtering algorithm;human pose markerless tracking;kinematic chain;local model-based search;monocular depth image;programmable graphics hardware;real time motion capture;single time-of-flight camera;unscented transform;Biological system modeling;Cameras;Computer science;Filtering algorithms;Graphics;Humans;Kinematics;Layout;Motion analysis;Tracking}, +doi={10.1109/CVPR.2010.5540141}, +ISSN={1063-6919},} + +@inproceedings{Koeping14, + author = {L. K{\"o}ping and M. Grzegorzek and F. Deinzer}, + title = {{Probabilistic Step and Turn Detection in Indoor Localisation}}, + booktitle = {Data Fusion and Target Tracking Conf.}, + year = {2014}, + IGNOREmonth = {April}, +} + +@ARTICLE{Zhao08, +author={Tao Zhao and Nevatia, R. and Bo Wu}, +journal={IEEE Transactions on Pattern Analysis and Machine Intelligence}, +title={Segmentation and Tracking of Multiple Humans in Crowded Environments}, +year={2008}, +IGNOREmonth={July}, +volume={30}, +number={7}, +pages={1198-1211}, +keywords={Bayes methods;Markov processes;Monte Carlo methods;hidden feature removal;image sampling;image segmentation;inference mechanisms;maximum likelihood estimation;object detection;probability;tracking;traffic engineering computing;3D human shape model;Bayesian MAP estimation problem;camera model;crowded environment;data-driven Markov chain Monte Carlo;foreground/background separation;human detection;human shape;image cues;image observation;joint image likelihood;multiple human segmentation;multiple human tracking;multiple partially occluded human hypotheses;occlusion reasoning;proposal probability;sampling method;Markov chain Monte Carlo;Multiple Human Segmentation;Multiple Human Tracking;Algorithms;Artificial Intelligence;Biometry;Environment;Humans;Image Enhancement;Image Interpretation, Computer-Assisted;Imaging, Three-Dimensional;Movement;Pattern Recognition, Automated;Reproducibility of Results;Sensitivity and Specificity;Subtraction Technique}, +doi={10.1109/TPAMI.2007.70770}, +ISSN={0162-8828},} + +@incollection{Doucet11:ATO, + author = {Arnaud Doucet and Adam M. Johansen}, + title = {{A Tutorial on Particle Filtering and Smoothing: Fifteen years later}}, + booktitle = {The Oxford Handbook of Nonlinear Filtering}, + editor = {Dan Crisan and Boris Rozovsky}, + publisher = {Oxford University Press}, + year = {2011}, +} + +@ARTICLE{Doucet00:OSM, + author = {Arnaud Doucet and Simon Godsill and Christophe Andrieu}, + title = {{On Sequential Monte Carlo Sampling Methods for Bayesian Filtering}}, + journal = {Statistics and Computing}, + year = {2000}, + IGNOREmonth = {July}, + volume = {10}, + number = {3}, + pages = {197-208}, +} + +@article{Gordon93:NAT, + author = {N. J. Gordon and D. J. Salmond and A. F. M. Smith}, + title = {{Novel approach to nonlinear/non-Gaussian Bayesian state estimation}}, + journal = {IEE Proc. F Radar and Signal Processing}, + year = {1993}, + IGNOREmonth = {apr}, + volume = {140}, + number = {2}, + pages = {107-113}, +} + +@article {Isard98:CCD, + author = {Michael Isard and Andrew Blake}, + title = {{CONDENSATION - Conditional Density Propagation for Visual Tracking}}, + journal = {Int. Journal of Computer Vision}, + year = {1998}, + IGNOREmonth = {aug}, + volume = {29}, + number = {1}, + pages = {5-28}, +} + +@article{Arulampalam02:ATO, + author = {M. Sanjeev Arulampalam and Simon Maskell and Neil Gordon and Tim Clapp}, + title = {A Tutorial on Particle Filters for Online Nonlinear/Non-Gaussian Bayesian Tracking}, + journal = {IEEE Transactions on Signal Processing}, + year = {2002}, + IGNOREmonth = {feb}, + volume = {50}, + number = {2}, + pages = {174-188}, +} + +@inbook{Doucet01:AIT, + author = {{Arnaud Doucet and Nando De Freitas Neil Gordon}}, + title = {{An Introduction to Sequential Monte Carlo Methods}}, + booktitle = {Sequential Monte Carlo Methods in Practice,}, + publisher = {Springer-Verlag,}, + address = {New York}, + year = {2001} +} + +@inproceedings{IAmTheAntenna, + author = {Zhang, Zengbin and Zhou, Xia and Zhang, Weile and Zhang, Yuanyang and Wang, Gang and Zhao, Ben Y. and Zheng, Haitao}, + title = {I Am the Antenna: Accurate Outdoor AP Location using Smartphones}, + booktitle = {Proc. of the 17th Annu. Int. Conf. on Mobile Computing and Networking}, + IGNOREseries = {MobiCom '11}, + year = {2011}, + isbn = {978-1-4503-0492-4}, + location = {Las Vegas, Nevada, USA}, + pages = {109--120}, + numpages = {12}, + REMurl = {http://doi.acm.org/10.1145/2030613.2030626}, + doi = {10.1145/2030613.2030626}, + acmid = {2030626}, + publisher = {ACM}, + address = {New York, NY, USA}, + keywords = {access point location, smartphones, wifi}, +} + +@article{IntroductionToRadio, + author={Friis, Harald T.}, + journal={IEEE Spectrum}, + title={Introduction to radio and radio antennas}, + year={1971}, + volume={8}, + number={4}, + pages={55-61}, + doi={10.1109/MSPEC.1971.5218045}, + ISSN={0018-9235}, +} + +@article{ANoteOnASimpleTransmissionFormula, + author={Friis, Harald T.}, + journal={Proc. of the IRE}, + title={A Note on a Simple Transmission Formula}, + year={1946}, + volume={34}, + number={5}, + pages={254-256}, + keywords={Capacitors;Circuits;Hazards;Laboratories;Lightning;Receiving antennas;Shape;Surges;Transmitting antennas;Voltage}, + doi={10.1109/JRPROC.1946.234568}, + ISSN={0096-8390}, +} + +@article{PathLossPredictionModelsForIndoor, + author={Seidel, Scott Y. and Rappaport, Theodore S.}, + journal={IEEE Transactions on Antennas and Propagation}, + title={914 {MHz} Path Loss Prediction Models for Indoor Wireless Communications in Multifloored Buildings}, + year={1992}, + volume={40}, + number={2}, + pages={207-217}, + keywords={electromagnetic wave absorption;mobile radio systems;radiowave propagation;914 MHz;UHF;building layout;concrete walls;contour plots;floor attenuation factors;floors;indoor wireless communications;multifloored buildings;office partitions;path loss prediction models;radiowave propagation;site-specific models;Concrete;Floors;Loss measurement;Measurement standards;Narrowband;Predictive models;Propagation losses;Radio transmitters;Receivers;Wireless communication}, + doi={10.1109/8.127405}, + ISSN={0018-926X}, +} + +@book{teschl2, + title={Mathematik Fur Informatiker: Band 2: Analysis und Statistik}, + author={Teschl, Gerald and Teschl, Susanne}, + isbn={9783540724513}, + IGNOREseries={Mathematik f{\"u}r Informatiker}, + year={2007}, + publisher={Springer}, + address={Berlin}, + edition={2}, + totalpages={387}, +} + +@book{teschl1, + title={Mathematik Fur Informatiker: Band 1: Diskrete Mathematik und Lineare Algebra}, + author={Teschl, Gerald and Teschl, Susanne}, + isbn={9783540708247}, + IGNOREseries={Mathematik f{\"u}r Informatiker}, + year={2007}, + publisher={Springer}, + address={Berlin}, + edition={2}, + totalpages={510}, +} + +@book{WirelessNetworking, + title={Wireless Networking Technology: From Principles to Successful Implementation}, + isbn={9780750667883 0750667885}, + IGNOREurl={http://www.engineeringvillage.com/controller/servlet/OpenURL?genre=book&isbn=9780750667883}, + language={English}, + urldate={2013-10-15}, + publisher={Elsevier, Newnes}, + address={Burlington, {MA}}, + author={Rackley, Steve}, + year={2007}, +} + +% questionable.... +% http://www.cse.buffalo.edu/srds2009/F2DA.html +@inproceedings{RssiUnreliable, + author={Parameswaran, Ambili T. and Husain, Mohammad I. and Upadhyaya, Shambhu}, + title={Is RSSI a Reliable Parameter in Sensor Localization Algorithms: An Experimental Study}, + booktitle={Proc. of the Field Failure Data Analysis Workshop (F2DA)}, + address={New York, NY, USA}, + year={2009}, +} + + +%questionable... +@inproceedings{RssiAlgoComparison, + author = {Zanca, Giovanni and Zorzi, Francesco and Zanella, Andrea and Zorzi, Michele}, + title = {Experimental comparison of RSSI-based localization algorithms for indoor wireless sensor networks}, + booktitle = {Proc. of the workshop on Real-world wireless sensor networks}, + IGNOREseries = {REALWSN '08}, + year = {2008}, + isbn = {9781605581231}, + location = {Glasgow, Scotland}, + pages = {1--5}, + numpages = {5}, + REMurl = {http://doi.acm.org/10.1145/1435473.1435475}, + doi = {10.1145/1435473.1435475}, + acmid = {1435475}, + publisher = {ACM}, + address = {New York, NY, USA}, + keywords = {RSSI, WSN, experimental, localization, sensors, testbed}, +} + + +@misc{PropagationLosses, + author = {Wilson, Robert}, + IGNOREmonth = aug, + school = {University of Southern California}, + title = {Propagation Losses Through Common Building Materials 2.4 GHz vs 5 GHz.}, + hhowpublished = {\url{http://www.ko4bb.com/Manuals/05%29\_GPS\_Timing/E10589\_Propagation\_Losses\_2\_and\_5GHz.pdf}}, + note = {last accessed 15.06.2015}, + year = {2002}, +} + +@article{RssiHumanInteraction, + author = {Graham, Ben and Tachtatzis, Christos and Di Franco, Fabio and Bykowski, Marek and Tracey, David C. and Timmons, Nick F. and Morrison, Jim}, + title = {Analysis of the Effect of Human Presence on a Wireless Sensor Network}, + journal = {Int. Journal of Ambient Computing and Intelligence (IJACI)}, + issue_date = {January 2011}, + volume = {3}, + number = {1}, + IGNOREmonth = jan, + year = {2011}, + issn = {1941-6237}, + pages = {1--13}, + numpages = {13}, + REMurl = {http://dx.doi.org/10.4018/jaci.2011010101}, + doi = {10.4018/jaci.2011010101}, + acmid = {2433177}, + publisher = {IGI Global}, + address = {Hershey, PA, USA}, + keywords = {Built Environment Networks (BENs), Human Presence, Node Placement, Radiation Patterns, Wireless Sensor Networks (WSNs)}, +} + +@inproceedings{PassiveLocalization, + author = {Youssef, Moustafa and Mah, Matthew and Agrawala, Ashok}, + title = {Challenges: Device-free Passive Localization for Wireless Environments}, + booktitle = {Proc. of the 13th Annu. Int. Conf. on Mobile Computing and Networking}, + IGNOREseries = {MobiCom '07}, + year = {2007}, + isbn = {9781595936813}, + location = {Montr\&\#233;al, Qu\&\#233;bec, Canada}, + pages = {222--229}, + numpages = {8}, + REMurl = {http://doi.acm.org/10.1145/1287853.1287880}, + doi = {10.1145/1287853.1287880}, + acmid = {1287880}, + publisher = {ACM}, + address = {New York, NY, USA}, + keywords = {device-free localization, passive localization, passive radio map}, +} + +@book{WirelessCommunications, + address = {Upper Saddle River, NJ, USA}, + title = {Wireless Communications: Principles and Practice}, + isbn = {0130422320 9780130422323}, + shorttitle = {Wireless communications}, + language = {English}, + publisher = {Prentice Hall {PTR}}, + author = {Rappaport, Theodore S.}, + year = {2002} +} + +@inproceedings{RssiReadingDifference, + author={Lui, Gough and Gallagher, Thomas and Li, Binghao and Dempster, Andrew G. and Rizos, Chris}, + booktitle={Int. Conf. on Localization and GNSS}, + title={Differences in RSSI Readings Made by Different Wi-Fi Chipsets: A Limitation of WLAN Localization}, + year={2011}, + pages={53-57}, + keywords={UHF integrated circuits;microwave integrated circuits;mobile computing;wireless LAN;RSSI reading;WLAN localization;Wi-Fi chipset;Wi-Fi fingerprinting positioning systems;Wi-Fi location;frequency 2.4 GHz;frequency 5 GHz;received signal strength indicator;Accuracy;Calibration;Fingerprint recognition;IEEE 802.11 Standards;Performance evaluation;Testing;Wireless communication;RSSI differences;WLAN localization;Wi-Fi chipsets;fingerprinting;limitations}, + doi={10.1109/ICL-GNSS.2011.5955283}, +} + +% influence of the human body on signal propagation +@inproceedings{RadiationProperties, + author = {Tuovinen, Tommi and Berg, Markus and Yazdandoost, Kamya Y. and Salonen, Erkki and Linatti, Jari}, + title = {Radiation Properties of the Planar UWB Dipole Antenna in the Proximity of Dispersive Body Models}, + booktitle = {Proc. of the 7th Int. Conf. on Body Area Networks}, + IGNOREseries = {BodyNets '12}, + year = {2012}, + isbn = {9781936968602}, + location = {Oslo, Norway}, + pages = {82--88}, + numpages = {7}, + REMurl = {http://dl.acm.org/citation.cfm?id=2442691.2442713}, + acmid = {2442713}, + publisher = {Institute for Computer Sciences, Social-Informatics and Telecommunications Engineering (ICST)}, + address = {Brussels, Belgium}, + keywords = {UWB WBAN systems, UWB dipole antenna, human body effect, reflections}, +} + +% about all types of antennas +@book{PracticalAntennaHandbook, + title={Practical Antenna Handbook}, + author={Carr, Joseph J.}, + publisher={McGraw-Hill}, + address = {New York, NY, USA}, + year={2001}, + IGNOREmonth={5}, + edition={4}, + isbn={9780071374354 0071389318}, + totalpages={608}, + timestamp={2013.10.16}, +} + +% reflection, diffraction, gain, scattering, ... +@book{CertifiedWirelessNetworkAdmin, + title={CWNA Certified Wireless Network Administrator Official Study Guide (Exam PW0-100)}, + author={Carpenter, Tom and Barrett, Joel}, + publisher={McGraw-Hill Osborne Media}, + address={New York, NY, USA}, + year={2007}, + IGNOREmonth={8}, + edition={4}, + isbn={9780071494908}, + REMurl={http://amazon.com/o/ASIN/0071494901/}, + totalpages={644}, + timestamp={2013.10.16}, +} + + +% ieee standard for 802.11 (revision 2007) +@Manual{ieee80211, + author={IEEE}, + journal={IEEE Std 802.11-2007 (Revision of IEEE Std 802.11-1999)}, + INGOREtitle={Standard for Information Technology - Telecommunications and Information Exchange Between Systems - Local and Metropolitan Area Networks - Specific Requirements - Part 11: Wireless LAN Medium Access Control (MAC) and Physical Layer (PHY) Specifications}, + title={Wireless LAN Medium Access Control (MAC) and Physical Layer (PHY) Specifications}, + organization = {Institute of Electrical and Electronics Engineers, Inc.}, + year={2007}, + pages={1-1076}, + publisher={IEEE Computer Society}, + address = {New York, NY, USA}, + doi={10.1109/IEEESTD.2007.373646},} +} + +% ieee standard for 802.11 (revision 2012) +@Manual{ieee80211_2012, + author={IEEE}, + journal={IEEE Std 802.11-2012 (Revision of IEEE Std 802.11-2007)}, + IGNOREtitle={Standard for Information technology -- Telecommunications and information exchange between systems Local and metropolitan area networks -- Specific requirements - Part 11: Wireless LAN Medium Access Control (MAC) and Physical Layer (PHY) Specifications}, + title={Wireless LAN Medium Access Control (MAC) and Physical Layer (PHY) Specifications}, + organization = {Institute of Electrical and Electronics Engineers, Inc.}, + IGNOREmonth={3}, + year={2012}, + pages={1-2793}, + publisher={IEEE Computer Society}, + address = {New York, NY, USA}, + doi={10.1109/IEEESTD.2012.6178212}, +} + + +% using some phy-layer info of intel cards as fingerprint metric instead of rssi +@inproceedings{PhyLayerFingerprints, + author = {Sen, Souvik and Radunovic, Bo\v{z}idar and Choudhury, Romit Roy and Minka, Tom}, + title = {You are facing the Mona Lisa: spot localization using PHY layer information}, + booktitle = {Proc. of the 10th Int. Conf. on Mobile Systems, Applications, and Services}, + IGNOREseries = {MobiSys '12}, + year = {2012}, + isbn = {9781450313018}, + location = {Low Wood Bay, Lake District, UK}, + pages = {183--196}, + numpages = {14}, + REMurl = {http://doi.acm.org/10.1145/2307636.2307654}, + doi = {10.1145/2307636.2307654}, + acmid = {2307654}, + publisher = {ACM}, + address = {New York, NY, USA}, + keywords = {application, cross-layer, localization, wireless}, +} + +% fingerprinting using robots +@inproceedings{robotFingerprinting, + title = {Autonomous RF Surveying Robot for Indoor Localization and Tracking}, + author = {Palaniappan, Ravishankar and Mirowski, Piotr and Ho, Tin Kam and Steck, Harald and Whiting, Philip and MacDonald, Michael}, + booktitle = {Indoor Positioning and Indoor Navigation (IPIN), Int. Conf. on}, + numpages = {4}, + year = {2011}, + IGNOREmonth = {9}, + location = {Guimarães, Portugal}, +} + +% one of THE two sources for wifi location +@inproceedings{radar, + author={Bahl, Paramvir and Padmanabhan, Venkata N.}, + booktitle={Proc. of the 19th Annu. Joint Conf. of the IEEE Computer and Communications Societies}, + title={RADAR: An In-Building RF-based User Location and Tracking System}, + year={2000}, + volume={2}, + pages={775-784}, + keywords={mobile computing;radio tracking;radiowave propagation;signal processing;wireless LAN;RADAR;RF-based tracking system;in-building tracking system;local-area wireless networks;location-aware systems;mobile computing devices;multiple base stations;overlapping coverage;signal propagation modeling;signal strength processing;user location;Base stations;Computer networks;Global Positioning System;Mobile computing;Radar signal processing;Radar tracking;Radio frequency;Signal processing;Wireless LAN;Wireless networks}, + doi={10.1109/INFCOM.2000.832252}, + ISSN={0743-166X}, +} + +% 1000 scans per fingerprint, histogram, interpolation +@inproceedings{secureAndRobust, + author={Meng, Wei and Xiao, Wendong and Ni, Wei and Xie, Lihua}, + booktitle={Indoor Positioning and Indoor Navigation (IPIN), Int. Conf. on}, + title={Secure and Robust Wi-Fi Fingerprinting Indoor Localization}, + year={2011}, + pages={1-7}, + keywords={fingerprint identification;indoor radio;radio networks;telecommunication security;wireless LAN;K nearest neighbor algorithm;KNN;Wi-Fi wireless networks;access point attacks;distribution estimation;in-building communication infrastructures;indoor positioning;probabilistic fingerprinting localization method;random sample consensus;reference points;robust Wi-Fi fingerprinting indoor localization;secure Wi-Fi fingerprinting indoor localization;weighted-mean method;Accuracy;Distortion measurement;Histograms;IEEE 802.11 Standards;Probabilistic logic;Robustness;Sensors;RANSAC;Wi-Fi;fingerprinting;indoor localization;sensor network;signal strength;wireless network}, + doi={10.1109/IPIN.2011.6071908}, +} + +% some attunuation factors, propagation models, etc. +@inproceedings{PropagationModelling, + author={El-Kafrawy, Kareem and Youssef, Moustafa and El-Keyi, Amr and Naguib, Ayman}, + booktitle={Vehicular Technology Conf. (VTC)}, + title={Propagation Modeling for Accurate Indoor WLAN RSS-Based Localization}, + year={2010}, + pages={1-5}, + keywords={mobility management (mobile radio);ray tracing;wireless LAN;3D ray tracing;RSS-based localization;accurate indoor WLAN;location determination systems;noisy wireless channel;propagation modeling;wall attenuation factor;Accuracy;Attenuation;Materials;Measurement uncertainty;Ray tracing;Solid modeling;Three dimensional displays}, + doi={10.1109/VETECF.2010.5594108}, + ISSN={1090-3038}, +} + +@article{ElectromagneticPropagation, + author={Richalot, Elodie and Bonilla, Matthieu and Wong, Man-Fai and Fouad-Hanna, Victor and Baudrand, Henri and Wiart, Joe}, + journal={IEEE Transactions on Microwave Theory and Techniques}, + title={Electromagnetic Propagation into Reinforced-Concrete Walls}, + year={2000}, + volume={48}, + number={3}, + pages={357-366}, + keywords={UHF radio propagation;concrete;electromagnetic wave propagation;finite element analysis;indoor radio;mobile radio;1800 MHz;900 MHz;EM propagation;EM properties;FEM;Floquet modes;angle of arrival;building construction materials;buildings walls;diffused field;electromagnetic properties;expansion of fields;finite-element techniques;reflection characteristics;reinforced-concrete walls;transmission characteristics;wireless communication system design;Building materials;Concrete;Electromagnetic propagation;Electromagnetic reflection;Finite element methods;Fresnel reflection;Ray tracing;Slabs;Steel;Wireless communication}, + doi={10.1109/22.826834}, + ISSN={0018-9480}, +} + +% LAN - background +@book{CCNA, + title={CCNA Cisco Certified Network Associate Study Guide (Exam 640-802)}, + author={Deal, Richard}, + publisher={McGraw-Hill}, + address={New York, NY, USA}, + isbn={0071643737 9780071643733}, + IGNOREseries={Certification Press}, + year={2008}, + pages={983}, +} + + +@misc{VAP1, + title={Virtual Access Points}, + author={Kittappa, Thenu}, + IGNOREurl={http://community.arubanetworks.com/aruba/attachments/aruba/115/1358/1/AppNote.MultipleBSSIDs.pdf}, + IGNOREnote={\url{http://community.arubanetworks.com/aruba/attachments/aruba/115/1358/1/AppNote.MultipleBSSIDs.pdf}}, + howpublished={\url{http://community.arubanetworks.com/aruba/attachments/aruba/115/1358/1/AppNote.MultipleBSSIDs.pdf}}, + note={zuletzt abgerufen am 28.11.2013}, + pages={13}, + year={2006}, +} + +@misc{VAP2, + title={IEEE P802.11 Wireless LANs - Virtual Access Points}, + author={Aboba, Bernard}, + year={2003}, + REMurl={http://aboba.drizzlehosting.com/IEEE/11-03-154r1-I-Virtual-Access-Points.doc}, + note={\url{http://aboba.drizzlehosting.com/IEEE/11-03-154r1-I-Virtual-Access-Points.doc}}, + note={zuletzt abgerufen am 28.11.2013}, + pages={13}, +} + +% reference points to reset errors, automatic floorplan generation, backend-phase +@inproceedings{crowdinside, + author = {Alzantot, Moustafa and Youssef, Moustafa}, + title = {CrowdInside: Automatic Construction of Indoor Floorplans}, + booktitle = {Proc. of the 20th Int. Conf. on Advances in Geographic Information Systems}, + IGNOREseries = {SIGSPATIAL '12}, + year = {2012}, + isbn = {978-1-4503-1691-0}, + location = {Redondo Beach, California}, + pages = {99--108}, + numpages = {10}, + REMurl = {http://doi.acm.org/10.1145/2424321.2424335}, + doi = {10.1145/2424321.2424335}, + acmid = {2424335}, + publisher = {ACM}, + address = {New York, NY, USA}, + keywords = {alpha-shapes, automatic floorplan construction, crowdsourcing}, +} + +% gradientenverfahren +@book{NumerischeMethoden, + title={Numerische Methoden: Eine Einführung für Informatiker, Naturwissenschaftler, Ingenieure und Mathematiker}, + author={Huckle, Thomas and Schneider, Stefan}, + publisher={Springer}, + address={Berlin}, + year={2006}, + IGNOREmonth={3}, + edition={2}, + isbn={9783540303169}, + REMurl={http://amazon.com/o/ASIN/3540303162/}, + totalpages={385}, +} + +% optimization, downhill-simplex +% https://portal.dnb.de/opac.htm?query=978-3-8348-2011-2&method=simpleSearch +@book{GrundlagenDerMathOptimierung, + title={Grundlagen der Mathematischen Optimierung: Diskrete Strukturen, Komplexitätstheorie, Konvexitätstheorie, Lineare Optimierung, Simplex-Algorithmus, Dualität}, + author={Gritzmann, Peter}, + isbn={9783834820112}, + IGNOREseries={Aufbaukurs Mathematik}, + year={2013}, + publisher={Springer Fachmedien}, + address={Wiesbaden}, + totalpages={525}, +} + +% basics on numerical optimization +% https://portal.dnb.de/opac.htm?method=showFullRec.¤tResultId=978-3-8274-2949-0%26any¤tPosition=0 +@book{REMNichtlineareOptimierung, + title={Nichtlineare Optimierung: Theorie, Numerik und Experimente}, + author={Reinhardt, Rüdiger and Hoffmann, Armin and Gerlach, Tobias}, + publisher={Springer}, + address={Berlin}, + year={2013}, + isbn={9783827429490}, + totalpages={383}, +} + + + + +% original downhill-simplex source +@article{downhillSimplex1, + author={Powell, Michael J. D.}, + title={An iterative method for finding stationary values of a function of several variables}, + issn={1460-2067}, + journal={The Computer Journal}, + volume={5}, + number={2}, + pages={147--151}, + publisher={Oxford University Press}, + year={1962}, + IGNOREmonth={8}, +} + +% modified downhill-simplex source +@article{downhillSimplex2, + title={A Simplex Method for Function Minimization}, + author={Nelder, John A. and Mead, Roger}, + issn={1460-2067}, + journal={The Computer Journal}, + volume={7}, + number={4}, + pages={308--313}, + publisher={Oxford University Press}, + year={1965}, + IGNOREmonth={1}, +} + +% lateration, linearization, numerical errors, LIST OF OTHER METRICS INSTEAD OF RSSI? +@inproceedings{LaterationLinear, + author={Li, Zang and Trappe, Wade and Zhang, Yanyong and Nath, Badri}, + booktitle={Proc. of the 4th Int. Symp. on Information Processing in Sensor Networks}, + title={Robust Statistical Methods for Securing Wireless Localization in Sensor Networks}, + year={2005}, + pages={91-98}, + publisher = {IEEE Press}, + address = {Piscataway, NJ, USA}, + doi={10.1109/IPSN.2005.1440903}, +} + +% gps lateration and history +@book{REMSatellitennavigation, + title={Satellitennavigation }, + author={Dodel, Hans and Häupler, Dieter}, + publisher={Springer}, + address={Heidelberg}, + year={2010}, + edition={2}, + isbn={9783540794448}, + totalpages={531}, +} + +% localization without a-priori knowledge +@inproceedings{WithoutThePain, + author = {Chintalapudi, Krishna and Padmanabha Iyer, Anand and Padmanabhan, Venkata N.}, + title = {Indoor Localization Without the Pain}, + booktitle = {Proc. of the 16th Annu. Int. Conf. on Mobile Computing and Networking}, + IGNOREseries = {MobiCom '10}, + year = {2010}, + isbn = {978-1-4503-0181-7}, + location = {Chicago, Illinois, USA}, + pages = {173--184}, + numpages = {12}, + publisher = {ACM}, + address = {New York, NY, USA}, +} + +% about lateration using RSSI and possible errors +@article{PositionEstimationRssi, + author={Pu, Chuan-Chin and Chung, Wan-Young}, + title={An Integrated Approach for Position Estimation using RSSI in Wireless Sensor Network}, + journal={Journal of Ubiquitous Convergence Technology}, + pages={78--87}, + volume={2}, + number={2}, + IGNOREmonth={11}, + year={2008}, +} + +% about lateration, rssi, convenience, errors +% http://www.iaeng.org/publication/IMECS2009/ +@inproceedings{AccuracyOfRssi, + title={Accuracy of Location Identification with Antenna Polarization on RSSI}, + author={Huang, Xu and Barralet, Mark and Sharma, Dharmendra}, + booktitle={Proc. of the Int. MultiConf. of Engineers and Computer Scientists}, + year={2009}, + volume={1}, + publisher={Newswood Limited}, + address={Hong Kong}, + ISBN={9789881701220}, + pages={542--546}, +} + +% basics about TDOA +@inproceedings{TimeDifferenceOfArrival1, + author={Khanzada, T. J. S. and Ali, A.R. and Omar, A.S.}, + title={Time Difference of Arrival estimation using super resolution algorithms to minimize Distance Measurement Error for indoor positioning systems}, + booktitle={IEEE Int. Multitopic Conf.}, + year={2008}, + pages={443-447}, +} + +% TOA and AOA explained +@inproceedings{TOAAOA, + author = {Deligiannis, Nikos and Louvros, Spiros and Kotsopoulos, Stavros}, + title = {Optimizing Location Positioning Using Hybrid TOA-AOA Techniques in Mobile Cellular Networks}, + booktitle = {Proc. of the 3rd Int. Conf. on Mobile Multimedia Communications}, + IGNOREseries = {MobiMedia '07}, + IGNOREmonth={8}, + year = {2007}, + isbn = {9789630626705}, + location = {Nafpaktos, Aitolokarnania, Greece}, + IGNOREpages = {20:1--20:7}, + articleno = {20}, + numpages = {7}, + publisher = {ICST}, + address = {Brussels, Belgium}, +} + + +% errors during euclid distance, sensor fusion with beeps, antenna-position +@inproceedings{PushTheLimit, + author = {Liu, Hongbo and Gan, Yu and Yang, Jie and Sidhom, Simon and Wang, Yan and Chen, Yingying and Ye, Fan}, + title = {Push the Limit of WiFi based Localization for Smartphones}, + booktitle = {Proc. of the 18th Annu. Int. Conf. on Mobile Computing and Networking}, + IGNOREseries = {Mobicom '12}, + year = {2012}, + isbn = {9781450311595}, + location = {Istanbul, Turkey}, + pages = {305--316}, + numpages = {12}, + acmid = {2348581}, + publisher = {ACM}, + address = {New York, NY, USA}, +} + +% lateration and rssi smoothing +@inproceedings{EnhancedRssi, + author = {Lau, Erin-Ee-Lin and Chung, Wan-Young}, + title = {Enhanced RSSI-Based Real-Time User Location Tracking System for Indoor and Outdoor Environments}, + booktitle = {Proc. of the 2007 Int. Conf. on Convergence Information Technology}, + IGNOREseries = {ICCIT '07}, + year = {2007}, + isbn = {0-7695-3038-9}, + pages = {1213--1218}, + numpages = {6}, + acmid = {1335696}, + publisher = {IEEE Computer Society}, + address = {Washington, DC, USA}, +} + +% probabilistic, parzen, histogram, squared error +@article{ProbabilisticWlan, + author={Roos, Teemu and Myllym\"{a}ki, Petri and Tirri, Henry and Misikangas, Pauli and Siev\"{a}nen, Juha}, + title={A Probabilistic Approach to WLAN User Location Estimation}, + journal = {Int. Journal of Wireless Information Networks}, + pages = {155--164}, + volume={9}, + number={3}, + IGNOREmonth={7}, + year={2002}, + doi = {10.1023/a:1016003126882}, + keywords = {bayesian, location, probability, wi-fi}, +} + +% the 2nd great source for indoor localization +@inproceedings{horus, + author = {Youssef, Moustafa and Agrawala, Ashok}, + title = {The Horus WLAN Location Determination System}, + booktitle = {Proc. of the 3rd Int. Conf. on Mobile Systems, Applications, and Services}, + IGNOREseries = {MobiSys '05}, + year = {2005}, + isbn = {1-931971-31-5}, + location = {Seattle, Washington}, + pages = {205--218}, + numpages = {14}, + REMurl = {http://doi.acm.org/10.1145/1067170.1067193}, + doi = {10.1145/1067170.1067193}, + acmid = {1067193}, + publisher = {ACM}, + address = {New York, NY, USA}, +} + +% bayes, normal-distribution, histogram, statistical independence of APs, ... +@inproceedings{WlanLocationDetermination, + author = {Youssef, Moustafa A. and Agrawala, Ashok and Shankar, A. Udaya}, + title = {WLAN Location Determination via Clustering and Probability Distributions}, + booktitle = {Proc. of the First IEEE Int. Conf. on Pervasive Computing and Communications}, + IGNOREseries = {PERCOM '03}, + year = {2003}, + isbn = {0-7695-1893-1}, + pages = {143-150}, + REMurl = {http://dl.acm.org/citation.cfm?id=826025.826335}, + acmid = {826335}, + publisher = {IEEE Computer Society}, + address = {Washington, DC, USA}, +} + +% the source for particle filtering and other stuff +@book{robotics, + title={Probabilistic Robotics}, + author={Thrun, Sebastian and Burgard, Wolfram and Fox, Dieter}, + publisher={The MIT Press}, + address = {Cambridge, MA, USA}, + year={2005}, + IGNOREmonth={8}, + isbn={9780262201629}, + totalpages={672}, +} + + +% path-loss-reference +@inproceedings{PotentialRisks, + author = {Jung, Wook Rak and Bell, Scott and Petrenko, Anastasia and Sizo, Anton}, + title = {Potential Risks of WiFi-based Indoor Positioning and Progress on Improving Localization Functionality}, + booktitle = {Proc. of the Fourth ACM SIGSPATIAL Int. Workshop on Indoor Spatial Awareness}, + IGNOREseries = {ISA '12}, + year = {2012}, + isbn = {978-1-4503-1697-2}, + location = {Redondo Beach, California}, + pages = {13--20}, + numpages = {8}, + REMurl = {http://doi.acm.org/10.1145/2442616.2442621}, + doi = {10.1145/2442616.2442621}, + acmid = {2442621}, + publisher = {ACM}, + address = {New York, NY, USA}, + keywords = {SaskEPS, WPS, indoor positioning, map-matching}, +} + + +% some path-loss exponents for the log-distance model +@article{ANewPathLossPrediction, + title={A new path loss prediction statistical model for indoor wireless communications}, + author={Polydorou, D. S. and Capsalis, C. N.}, + journal={Int. Journal of Infrared and Millimeter Waves}, + publisher={Plenum Publishing Corporation}, + address={New York, NY, USA}, + volume={15}, + number={1}, + year={1994}, + pages={201--228}, +} + + +% signal-strength prediction for coverage, furniture impact, raytracing +@article{PredictingRFCoverage, + author={Rajkumar, A. and Naylor, B. F. and Feisullin, F. and Rogers, L.}, + title={Predicting RF coverage in large environments using ray-beam tracing and partitioning tree represented geometry}, + journal={Wireless Networks}, + issue_date={June 1996}, + volume={2}, + number={2}, + IGNOREmonth={6}, + year={1996}, + issn={1022-0038}, + pages={143--154}, + numpages={12}, + REMurl={http://dx.doi.org/10.1007/BF01225637}, + doi={10.1007/BF01225637}, + acmid={234826}, + publisher={Springer-Verlag New York, Inc.}, + address={Secaucus, NJ, USA}, +} + + +@book{IntroductionToRF, + title={Introduction to RF Propagation}, + author={Seybold, John S.}, + publisher={Wiley-Interscience}, + address={Hoboken, NJ, USA}, + year={2005}, + IGNOREmonth={9}, + IGNOREedition={1}, + isbn={9780471655961}, + REMurl={http://amazon.com/o/ASIN/0471655961/}, + totalpages={352}, +} + + +% what to do with missing map APs +@inproceedings{AccuracyCharacterization, + author = {Cheng, Yu-Chung and Chawathe, Yatin and LaMarca, Anthony and Krumm, John}, + title = {Accuracy Characterization for Metropolitan-scale Wi-Fi Localization}, + booktitle = {Proc. of the 3rd Int. Conf. on Mobile Systems, Applications, and Services}, + IGNOREseries = {MobiSys '05}, + year = {2005}, + isbn = {1-931971-31-5}, + location = {Seattle, Washington}, + pages = {233--245}, + numpages = {13}, + REMurl = {http://doi.acm.org/10.1145/1067170.1067195}, + doi = {10.1145/1067170.1067195}, + acmid = {1067195}, + publisher = {ACM}, + address = {New York, NY, USA}, +} + +% THE dsp guide +@book{dsp, + title={The Scientist and Engineer's Guide to Digital Signal Processing}, + author={Smith, Steven W.}, + publisher={California Technical Publishing}, + address={San Diego, CA, USA}, + year={1999}, + edition={2}, + isbn={9780966017649}, + REMurl={http://amazon.com/o/ASIN/0966017641/}, + totalpages={650}, +} + + +% differential RSSI measurements +@article{differentialRssi, + author={Wang, Jie and Gao, Qinghua and Wang, Hongyu and Chen, Hongyang and Jin, Minglu}, + title={Differential radio map-based robust indoor localization}, + journal={EURASIP Journal on Wireless Communications and Networking}, + publisher={Springer}, + address={Heidelberg}, + pages={12}, + volume={2011}, + number={1}, + year={2011}, +} + + + +% probability, log, noise effects, etc. +% http://books.google.de/books/about/An_introduction_to_the_theory_of_random.html?id=meFSAAAAMAAJ&redir_esc=y +@book{RandomSignalsAndNoise, + title={An Introduction to the Theory of Random Signals and Noise}, + author={Davenport, Wilbur B. Jr. and Root, William L.}, + publisher={McGraw-Hill}, + address = {New York, NY, USA}, + year={1958}, + totalpages={393}, +} + + +% distance between fingerprints and its impact +@inproceedings{LocatingInFingerprintSpace, + author = {Yang, Zheng and Wu, Chenshu and Liu, Yunhao}, + title = {Locating in Fingerprint Space: Wireless Indoor Localization with Little Human Intervention}, + booktitle = {Proc. of the 18th Annu. Int. Conf. on Mobile Computing and Networking}, + IGNOREseries = {Mobicom '12}, + year = {2012}, + isbn = {978-1-4503-1159-5}, + location = {Istanbul, Turkey}, + pages = {269--280}, + numpages = {12}, + REMurl = {http://doi.acm.org/10.1145/2348543.2348578}, + doi = {10.1145/2348543.2348578}, + acmid = {2348578}, + publisher = {ACM}, + address = {New York, NY, USA}, + keywords = {RSS fingerprint, floor plan, indoor localization, site survey, smartphones}, +} + + +% different kernel density functions +@article{kernel1, + author = {Gerani, Shima and Carman, Mark and Crestani, Fabio}, + title = {Aggregation Methods for Proximity-Based Opinion Retrieval}, + journal = {ACM Transactions on Information Systems}, + issue_date = {November 2012}, + volume = {30}, + number = {4}, + IGNOREmonth = {11}, + year = {2012}, + issn = {1046-8188}, + IGNOREpages = {26:1--26:36}, + articleno = {26}, + numpages = {36}, + REMurl = {http://doi.acm.org/10.1145/2382438.2382445}, + doi = {10.1145/2382438.2382445}, + acmid = {2382445}, + publisher = {ACM}, + address = {New York, NY, USA}, + keywords = {Opinion, blog, proximity, retrieval, sentiment}, +} + + +% log probability (scaling) +@inproceedings{LogLinearModels, + author = {Smith, David A. and Eisner, Jason}, + title = {Minimum Risk Annealing for Training Log-linear Models}, + booktitle = {Proc. of the COLING/ACL on Main Conf. Poster Sessions}, + series = {COLING-ACL '06}, + year = {2006}, + location = {Sydney, Australia}, + pages = {787--794}, + numpages = {8}, + REMurl = {http://dl.acm.org/citation.cfm?id=1273073.1273174}, + acmid = {1273174}, + publisher = {Association for Computational Linguistics}, + address = {Stroudsburg, PA, USA}, +} + +% explains the additional parameter after the path loss model +@article{empiricalPathLossModel, + author = {Erceg, V. and Greenstein, L. J. and Tjandra, S. Y. and Parkoff, S. R. and Gupta, A. and Kulic, B. and Julius, A. A. and Bianchi, R.}, + title = {An Empirically Based Path Loss Model for Wireless Channels in Suburban Environments}, + journal = {IEEE Journal on Selected Areas in Communications}, + issue_date = {September 2006}, + volume = {17}, + number = {7}, + IGNOREmonth = sep, + year = {2006}, + issn = {0733-8716}, + pages = {1205--1211}, + numpages = {7}, + REMurl = {http://dx.doi.org/10.1109/49.778178}, + doi = {10.1109/49.778178}, + acmid = {2313013}, + publisher = {IEEE Press}, + address = {Piscataway, NJ, USA}, +} + +% FHWS Journal +@ARTICLE{Koeping14-ILU, + author={K{\"o}ping, Lukas and Ebner, Frank and Grzegorzek, Marcin and Deinzer, Frank}, + title={{Indoor Localization Using Step and Turn Detection Together with Floor Map + Information}}, + journal={FHWS Science Journal}, + publisher={University of Applied Sciences W{\"u}rzburg - Schweinfurt}, + address={W{\"u}rzburg}, + numpages={9}, + volume={}, + number={}, + year={2014}, +} + +@inproceedings{Koeping14-PSA, + author = {Lukas K\"{o}ping and Marcin Grzegorzek and Frank Deinzer}, + title = {{Probabilistic Step and Turn Detection in Indoor Localization}}, + booktitle = {Conf. on Data Fusion and Target Tracking 2014: Algorithms and Applications (DFTT 2014)}, + year = {2014}, + IGNOREmonth = {April}, + address = {Liverpool, UK}, + pages = {1-7}, +} + +@article{Deinzer09:AFF, + author = {Frank Deinzer and Christian Derichs and Heinrich Niemann and Joachim Denzler}, + title = {{A Framework for Actively Selecting Viewpoints in Object Recognition}}, + journal = {Int. Journal of Pattern Recognition and Artificial Intelligence}, + year = {2009}, + IGNOREmonth = {June}, + volume = {23}, + number = {4}, + pages = {765-799}, +} + +@book{Deinzer05:OAI, + author = {Frank Deinzer}, + title = {Optimale Ansichtenauswahl in der aktiven Objekterkennung}, + publisher = {Logos Verlag Berlin}, + series = {Studien zur Mustererkennung}, + volume = {20}, + year = {2005}, +} + +@article{Link11:FAM, + author = {Jo Agila Bitsch Link and Paul Smith and Klaus Wehrle}, + title = {FootPath: Accurate map-based indoor navigation using smartphones}, + journal = {Indoor Positioning and Indoor Navigation (IPIN), Int. Conf. on}, + year = {2011}, + IGNOREmonth = {September}, + pages = {1-8}, +} + + +@inproceedings{gradientDescent, +author={Mofarreh-Bonab, Mostafa and Ghorashi, Seyed Ali}, +booktitle={3th Int. eConf. on Computer and Knowledge Engineering (ICCKE)}, +title={A low complexity and high speed gradient descent based secure localization in Wireless Sensor Networks}, +year={2013}, +IGNOREmonth={Oct}, +pages={300-303}, +keywords={gradient methods;iterative methods;least mean squares methods;telecommunication network routing;telecommunication security;wireless sensor networks;LMdS;WSN;fault probability;gradient based method;gradient descent algorithm;gradient descent based secure localization;high speed gradient descent based secure localization;iterative algorithms;least median square;localization;localization error;monitoring applications;network quality;routing;voting based secure localization;wireless sensor networks;Estimation;Monitoring;Robustness;Wireless sensor networks;gradient based localization;iterative algorithm;secure localization}, +doi={10.1109/ICCKE.2013.6682841},} + +@article{Godsill04:MCS, + author = {Simon J. Godsill and Arnaud Doucet and Mike West}, + title = {Monte Carlo Smoothing for Nonlinear Time Series}, + journal = {Journal of the American Statistical Association}, + year = {2004}, + IGNOREmonth = {March}, + volume = {99}, + number = {465}, + pages = {156-168}, +} + +@inproceedings{Mizell03-UGT, + author={Mizell, D.}, + booktitle={Wearable Computers, 2003. Proc. of the Seventh IEEE Int. Symp. on}, + title={{Using gravity to estimate accelerometer orientation}}, + year={2003}, + IGNOREmonth={October}, + pages={252-253}, +} + +@inproceedings{Kunze09-WWA, + author={Kunze, K. and Lukowicz, P. and Partridge, K. and Begole, B.}, + booktitle={Wearable Computers, 2009. ISWC '09. Int. Symp. on}, + title={{Which Way Am I Facing: Inferring Horizontal Device Orientation from an Accelerometer Signal}}, + year={2009}, + IGNOREmonth={September}, + pages={149-150}, +} + +@inproceedings{Steinhoff10-DRF, + author={Steinhoff, U. and Schiele, B.}, + booktitle={Pervasive Computing and Communications (PerCom), 2010 IEEE Int. Conf. on}, + title={{Dead reckoning from the Pocket - An Experimental Study}}, + year={2010}, + IGNOREmonth={March}, + pages={162-170}, +} + +@inproceedings{Binghao13-UBI, + author={Binghao Li and Harvey, B. and Gallagher, T.}, + booktitle={Indoor Positioning and Indoor Navigation (IPIN), Int. Conf. on}, + title={Using Barometers to Determine the Height for Indoor Positioning}, + year={2013}, + IGNOREmonth={Oct}, + pages={1-7}, +} + +@inproceedings{Nurminen13-PSI, + author={Nurminen, H. and Ristimaki, A. and Ali-Loytty, S. and Piche, R.}, + booktitle={Indoor Positioning and Indoor Navigation (IPIN), Int. Conf. on}, + title={Particle Filter and Smoother for Indoor Localization}, + year={2013}, + IGNOREmonth={October}, + pages={1-10}, +} + +@inproceedings{Willemsen15, + author={Willemsen, T. and Keller, F. and Sternberg, H.}, + booktitle={Indoor Positioning and Indoor Navigation (IPIN), Int. Conf. on}, + title={A Topological Approach with MEMS in Smartphones based on Routing-Graph}, + year={2015}, + IGNOREmonth={October}, + pages={1-6}, +} + +@inproceedings{Muralidharan14-BPS, + author = {Muralidharan, Kartik and Khan, Azeem Javed and Misra, Archan and Balan, Rajesh Krishna and Agarwal, Sharad}, + title = {Barometric Phone Sensors: More Hype Than Hope!}, + booktitle = {Proc. of the 15th Workshop on Mobile Computing Systems and Applications}, + year = {2014}, + isbn = {978-1-4503-2742-8}, + location = {Santa Barbara, California}, + pages = {12:1--12:6}, +} + +@inproceedings{Graph1, +author={Tian, J. and H{\"a}hner, J. and Becker, C. and Stepanov, I. and Rothermel, K.}, +booktitle={Simulation Symp., 2002. Proc. of the 35th Annu.}, +title={Graph-based Mobility Model for Mobile ad-hoc Network Simulation}, +year={2002}, +IGNOREmonth={April}, +pages={337-344}, +keywords={graph theory;mobile communication;mobile computing;protocols;telecommunication network routing;ad hoc routing protocols;graph-based mobility model;mobile ad hoc network;mobile ad hoc networks;random walk model;realistic movement;routing protocols;spatial constraints;Brain modeling;Cities and towns;Electronic mail;Mobile ad hoc networks}, +doi={10.1109/SIMSYM.2002.1000171}, +ISSN={1082-241X},} + +@inproceedings{Brajdic-WDS13, + author = {Brajdic, Agata and Harle, Robert}, + title = {Walk Detection and Step Counting on Unconstrained Smartphones}, + booktitle = {Proc. of the 2013 ACM Conf. on Ubiquitous Computing}, + year = {2013}, + IGNOREmonth = {September}, + isbn = {978-1-4503-1770-2}, + location = {Zurich, Switzerland}, + pages = {225--234}, +} + +@inproceedings{Li12-ARA, + author = {Li, Fan and Zhao, Chunshui and Ding, Guanzhong and Gong, Jian and Liu, Chenxing and Zhao, Feng}, + title = {{A reliable and accurate indoor localization method using phone inertial sensors}}, + booktitle = {Proc. of the 2012 ACM Conf. on Ubiquitous Computing}, + year = {2012}, + IGNOREmonth = {September}, + pages = {421--430}, +} + +@article{Woodman08-PLF, + author = {Oliver Woodman and Robert Harle}, + title = {{Pedestrian Localisation for Indoor Environments}}, + journal = {Proc. of the 10th Int. Conf. on Ubiquitous Computing}, + year = {2008}, + IGNOREmonth = {September}, + pages = {114-123}, +} + +@inproceedings{Blanchert09-IFF, + author={Blanchart, P. and Liyun He and Le Gland, F.}, + title={{Information Fusion for Indoor Localization}}, + booktitle={Proc. of the 12th Int. Conf. on Information Fusion}, + year={2009}, + IGNOREmonth={July}, + pages={2083--2090}, +} + +@inproceedings{Hilsenbeck14-GBD, + author = {Hilsenbeck, Sebastian and Bobkov, Dmytro and Schroth, Georg and Huitl, Robert and Steinbach, Eckehard}, + title = {{Graph-based Data Fusion of Pedometer and WiFi Measurements for Mobile Indoor Positioning}}, + booktitle = {Proc. of the 2014 ACM Int. Joint Conf. on Pervasive and Ubiquitous Computing}, + year = {2014}, + pages = {147--158}, +} + +@book{Forbes11-SD, + title={Statistical Distributions}, + author={Catherine Forbes and Merran Evans and Nicholas Hastings and Brian Peacock}, + isbn={978-0470390634}, + series={Wiley Series in Probability and Statistics}, + year={2011}, + publisher={Wiley}, + address={New Jersey}, + edition={4}, + totalpages={230}, +} + +@inproceedings{Deinzer01-CIV, + author = {Deinzer, Frank and Denzler, Joachim and Niemann, Heinrich}, + title = {On Fusion of Multiple Views for Active Object Recognition}, + year = {2001}, + pages = {239-245}, + booktitle = {Pattern Recognition -- Proc. of the 23rd DAGM Symp.}, + IGNOREmonth = {9}, + editor = {B. Radig}, + series = {LNCS}, + volume = {2191}, + address = {Heidelberg}, + publisher = {Springer} + +} + +@inproceedings{Mohssen14-ITH, + author = {Mohssen, Nesma and Momtaz, Rana and Aly, Heba and Youssef, Moustafa}, + title = {{It's the Human That Matters: Accurate User Orientation Estimation for Mobile Computing Applications}}, + booktitle = {Proc. of the 11th Int. Conf. on Mobile and Ubiquitous Systems: Computing, Networking and Services}, + year = {2014}, + pages = {70--79}, + numpages = {10}, +} + +@inproceedings{Fetzer14, +author={Fetzer, Toni and Deinzer, Frank and K{\"o}ping, Lukas and Grzegorzek, Marcin}, +booktitle={Indoor Positioning and Indoor Navigation (IPIN), Int. Conf. on}, +title={Statistical Indoor Localization Using Fusion of Depth-Images and Step Detection}, +year={2014}, +IGNOREmonth={October}, +pages={1-9}} + +@inproceedings{Ebner14, +author={Ebner, Frank and Deinzer, Frank and K{\"o}ping, Lukas and Grzegorzek, Marcin}, +booktitle={Indoor Positioning and Indoor Navigation (IPIN), Int. Conf. on}, +title={{R}obust {S}elf-{L}ocalization using {W}i-{F}i, {S}tep/{T}urn-{D}etection and {R}ecursive {D}ensity {E}stimation}, +year={2014}, +IGNOREmonth={October}, +pages={1-9}} + +@phdthesis{mautz2012indoor, + title={Indoor positioning technologies}, + author={Mautz, Rainer}, + year={2012}, + school={Habilitationsschrift ETH Z{\"u}rich, 2012} +} + +@inproceedings{Parviainen-08, +author={Parviainen, J. and Kantola, J. and Collin, J.}, +booktitle={Position, Location and Navigation Symp., 2008 IEEE/ION}, +title={Differential barometry in personal navigation}, +year={2008}, +IGNOREmonth={May}, +pages={148-152}, +keywords={barometers;height measurement;microsensors;pressure sensors;satellite navigation;MEMS barometer data;altitude information;differential barometry;personal navigation;satellite navigation systems;Costs;Floors;Global Positioning System;Internet;Least squares methods;Micromechanical devices;Satellite navigation systems;Seismic measurements;TCPIP;Ventilation}, +doi={10.1109/PLANS.2008.4570051},} + +@inproceedings{wang2006fusion, + title={Fusion of barometric sensors, WLAN signals and building information for 3-D indoor/campus localization}, + author={Wang, Hui and Lenz, Henning and Szabo, Andrei and Hanebeck, Uwe D and Bamberger, Joachim}, + booktitle={Proc. of Int. Conf. on Multisensor Fusion and Integration for Intelligent Systems (MFI 2006), S}, + pages={426--432}, + year={2006}, +} + +@inproceedings{Ebner-15, + author={Ebner, Frank and Fetzer, Toni and K{\"o}ping, Lukas and Grzegorzek, Marcin and Deinzer, Frank}, + booktitle={Indoor Positioning and Indoor Navigation (IPIN), Int. Conf. on}, + title={{Multi Sensor 3D Indoor Localisation}}, + year={2015}, + IGNOREmonth={October}, + pages={1-10}, +} + +@book{condon1967handbook, + title={Handbook of physics}, + author={Condon, E.U. and Odishaw, H.}, + lccn={66020002}, + series={McGraw-Hill handbooks}, + year={1967}, + publisher={McGraw-Hill}, +} + +@book{btle, + title={Specification of the Bluetooth System v4.2}, + publisher={Bluetooth Special Interest Group}, + year={2014}, +} + +@article{smith1997scientist, + title={The scientist and engineer's guide to digital signal processing}, + author={Smith, Steven W and others}, + year={1997}, + publisher={California Technical Pub. San Diego} +} + +@article{Hazas04-LAW, +author={Hazas, M. and Scott, J. and Krumm, J.}, +journal={Computer}, +title={{Location-aware Computing Comes of Age}}, +year={2004}, +IGNOREmonth={February}, +volume={37}, +number={2}, +pages={95-97}, +} + +@article{Dhar11-CAB, + author = {Dhar, Subhankar and Varshney, Upkar}, + title = {{Challenges and Business Models for Mobile Location-based Services and Advertising}}, + journal = {Communications of the ACM}, + volume = {54}, + number = {5}, + IGNOREmonth = {May}, + year = {2011}, + pages = {121--128}, +} + +@article{Kaasinen03-UNF, + author = {Kaasinen, Eija}, + title = {{User Needs for Location-aware Mobile Services}}, + journal = {Personal and Ubiquitous Computing}, + volume = {7}, + number = {1}, + IGNOREmonth = {May}, + year = {2003}, + pages = {70--79}, +} + +@inproceedings{Macvean12-IAS, + author = {Macvean, Andrew and Robertson, Judy}, + title = {{iFitQuest: A School Based Study of a Mobile Location-aware Exergame for Adolescents}}, + booktitle = {Proc. of the 14th Int. Conf. on Human-computer Interaction with Mobile Devices and Services}, + series = {MobileHCI '12}, + year = {2012}, + pages = {359--368}, +} + +@inproceedings{Kaminskas13-LAM, + author = {Kaminskas, Marius and Ricci, Francesco and Schedl, Markus}, + title = {{Location-aware Music Recommendation Using Auto-tagging and Hybrid Matching}}, + booktitle = {Proc. of the 7th ACM Conf. on Recommender Systems}, + series = {RecSys '13}, + year = {2013}, + pages = {17--24}, +} + +@article{Perera14-CAC, +author={Perera, C. and Zaslavsky, A. and Christen, P. and Georgakopoulos, D.}, +journal={Communications Surveys Tutorials, IEEE}, +title={{Context Aware Computing for The Internet of Things: A Survey}}, +year={2014}, +IGNOREmonth={First Quarter}, +volume={16}, +number={1}, +pages={414-454}, +} + +@inproceedings{Nurminen2014, +abstract = {This article presents a training-free probabilistic pedestrian motion model that uses indoor map information represented as a set of links that are connected by nodes. This kind of structure can be modelled as a graph. In the proposed model, as a position estimate reaches a link end, the choice probabilities of the next link are proportional to the total link lengths (TLL), the total lengths of the subgraphs accessible by choosing the considered link alternative. The TLLs can be computed off-line using only the graph, and they can be updated if training data are available. A particle filter in which all the particles move on the links following the TLL-based motion model is formulated. The TLL-based motion model has advantageous theoretical properties compared to the conventional models. Furthermore, the real-data WLAN positioning tests show that the positioning accuracy of the algorithm is similar or in many cases better than that of the conventional algorithms. The TLL-based model is found to be advantageous especially if position measurements are used infrequently, with 10-second or more time intervals.}, +author = {Nurminen, Henri and Koivisto, Mike and Ali-Loytty, Simo and Piche, Robert}, +booktitle = {Int. Conf. on Indoor Positioning and Indoor Navigation (IPIN)}, +doi = {10.1109/IPIN.2014.7275539}, +file = {:home/toni/Documents/literatur/fusion16/Motion model for positioning with graph-based indoor map.pdf:pdf}, +isbn = {978-1-4673-8054-6}, +keywords = {Atmospheric measurements,Computational modeling,Particle measurements,Position measurement,Proposals,TLL,Training data,Wireless LAN,graph,graph theory,graph-based indoor map,indoor navigation,indoor positioning,map-matching,motion model,particle filter,particle filtering (numerical methods),position measurement,radio links,real-data WLAN positioning test,total link length,training-free probabilistic pedestrian motion mode,wireless LAN}, +IGNOREmonth = {oct}, +pages = {646--655}, +publisher = {IEEE}, +shorttitle = {Indoor Positioning and Indoor Navigation (IPIN), 2}, +title = {{Motion Model for Positioning with Graph-based Indoor Map}}, +year = {2014} +} + + +@book{albrecht2013computer, + title={Computer Algebra: Symbolic and Algebraic Computation}, + author={Albrecht, Rudolf and Buchberger, Bruno and Collins, George Edwin and Loos, Rudiger}, + volume={4}, + year={2013}, + publisher={Springer Science \& Business Media} +} + +@book{bernardo2009bayesian, + title={Bayesian Theory}, + author={Bernardo, Jos{\'e} M and Smith, Adrian FM}, + volume={405}, + year={2009}, + publisher={John Wiley \& Sons} +} + +@book{sarkka2013bayesian, + title={Bayesian Filtering and Smoothing}, + author={S{\"a}rkk{\"a}, Simo}, + number={3}, + year={2013}, + publisher={Cambridge University Press} +} + +@book{rinne2008taschenbuch, + title={Taschenbuch der Statistik}, + author={Rinne, Horst}, + year={2008}, + publisher={Harri Deutsch Verlag} +} + +@article{aldrich1997ra, + title={RA Fisher and the Making of Maximum Likelihood 1912-1922}, + author={Aldrich, John and others}, + journal={Statistical Science}, + volume={12}, + number={3}, + pages={162--176}, + year={1997}, + publisher={Institute of Mathematical Statistics} +} + +@Misc{kypraios12, + author = {Kypraios, Theo}, + title = {Introduction to Bayesian Statistics}, + year = {2012}, + IGNOREmonth = {10}, + note = {Lecture Presentation}, + url = {https://www.maths.nottingham.ac.uk/personal/tk/files/talks/Cran_10_12.pdf [\today]} +} + +@article{ghahramani2001introduction, + title={An Introduction to Hidden Markov Models and Bayesian Networks}, + author={Ghahramani, Zoubin}, + journal={Int. Journal of Pattern Recognition and Artificial Intelligence}, + volume={15}, + number={01}, + pages={9--42}, + year={2001}, + publisher={World Scientific} +} + +@article{rabiner1989tutorial, + title={A Tutorial on Hidden Markov Models and Selected Applications in Speech Recognition}, + author={Rabiner, Lawrence R}, + journal={Proc. of the IEEE}, + volume={77}, + number={2}, + pages={257--286}, + year={1989}, + publisher={IEEE} +} + +@inproceedings{wang2013collapsed, + title={Collapsed variational Bayesian Inference for Hidden Markov Models}, + author={Wang, Pengyu and Blunsom, Phil}, + booktitle={Proc. of the Sixteenth Int. Conf. on Artificial Intelligence and Statistics}, + pages={599--607}, + year={2013} +} + +@article{baum1966statistical, + title={Statistical Inference for Probabilistic Functions of Finite State Markov Chains}, + author={Baum, Leonard E and Petrie, Ted}, + journal={The Ann. of Mathematical Statistics}, + pages={1554--1563}, + year={1966}, + publisher={JSTOR} +} + +@book{gilks2005markov, + title={Markov Chain Monte Carlo}, + author={Gilks, Walter R}, + year={2005}, + publisher={Wiley Online Library} +} + +@article{roweis1999unifying, + title={A Unifying Review of Linear Gaussian Models}, + author={Roweis, Sam and Ghahramani, Zoubin}, + journal={Neural Computation}, + volume={11}, + number={2}, + pages={305--345}, + year={1999}, + publisher={MIT Press} +} + +@article{chen2003bayesian, + title={Bayesian Filtering: From Kalman Filters to Particle Filters, and Beyond}, + author={Chen, Zhe}, + journal={Statistics}, + volume={182}, + number={1}, + pages={1--69}, + year={2003} +} + +@book{gelman2014bayesian, + title={Bayesian Data Analysis}, + author={Gelman, Andrew and Carlin, John B and Stern, Hal S and Rubin, Donald B}, + volume={2}, + year={2014}, + publisher={Taylor \& Francis} +} + +@article{jaynes1968prior, + title={Prior Probabilities}, + author={Jaynes, Edwin T}, + journal={Systems Science and Cybernetics, IEEE Transactions on}, + volume={4}, + number={3}, + pages={227--241}, + year={1968}, + publisher={IEEE} +} + +@article{kass1996selection, + title={The Selection of Prior Distributions by Formal Rules}, + author={Kass, Robert E and Wasserman, Larry}, + journal={Journal of the American Statistical Association}, + volume={91}, + number={435}, + pages={1343--1370}, + year={1996}, + publisher={Taylor \& Francis Group} +} + +@book{jaynes2003probability, + title={Probability Theory: The Logic of Science}, + author={Jaynes, Edwin T}, + year={2003}, + publisher={Cambridge university press} +} + +@article {Jeffreys453, + author = {Jeffreys, Harold}, + title = {An Invariant Form for the Prior Probability in Estimation Problems}, + volume = {186}, + number = {1007}, + pages = {453--461}, + year = {1946}, + doi = {10.1098/rspa.1946.0056}, + publisher = {The Royal Society}, + issn = {0080-4630}, + journal = {Proc. of the Royal Society of London A: Mathematical, Physical and Engineering Sciences} +} + +@inproceedings{julier1997new, + title={New Extension of the Kalman Filter to Nonlinear Systems}, + author={Julier, Simon J and Uhlmann, Jeffrey K}, + booktitle={AeroSense'97}, + pages={182--193}, + year={1997}, + organization={Int. Society for Optics and Photonics} +} + +@article{rosenblatt1956central, + title={A Central Limit Theorem and a Strong Mixing Condition}, + author={Rosenblatt, Murray}, + journal={Proc. of the National Academy of Sciences of the United States of America}, + volume={42}, + number={1}, + pages={43}, + year={1956}, + publisher={National Academy of Sciences} +} + +@article{kalman1960new, + title={A New Approach to Linear Filtering and Prediction Problems}, + author={Kalman, Rudolph Emil}, + journal={Journal of Fluids Engineering}, + volume={82}, + number={1}, + pages={35--45}, + year={1960}, + publisher={American Society of Mechanical Engineers} +} + +@Article{Halton:1970:RPS, + author = "John H. Halton", + title = "A Retrospective and Prospective Survey of the {Monte + Carlo} Method", + journal = j-SIAM-REVIEW, + volume = "12", + number = "1", + pages = "1--63", + year = "1970", + CODEN = "SIREAD", + DOI = "http://dx.doi.org/10.1137/1012001", + ISSN = "0036-1445 (print), 1095-7200 (electronic)", + ISSN-L = "0036-1445", + bibdate = "Thu Mar 27 09:06:14 MDT 2014", + bibsource = "http://epubs.siam.org/toc/siread/12/1; + http://www.math.utah.edu/pub/tex/bib/prng.bib; + http://www.math.utah.edu/pub/tex/bib/siamreview.bib", + acknowledgement = ack-nhfb, + fjournal = "SIAM Review", + journal-URL = "http://epubs.siam.org/sirev", + onlinedate = "January 1970", +} + +@incollection{Platzer:2008, + year={2008}, + isbn={978-3-540-78639-9}, + booktitle={Bildverarbeitung für die Medizin 2008}, + series={Informatik Aktuell}, + editor={Tolxdorff, Thomas and Braun, Jürgen and Deserno, ThomasM. and Horsch, Alexander and Handels, Heinz and Meinzer, Hans-Peter}, + doi={10.1007/978-3-540-78640-5_58}, + title={3D Blood Flow Reconstruction from 2D Angiograms}, + url={http://dx.doi.org/10.1007/978-3-540-78640-5_58}, + publisher={Springer Berlin Heidelberg}, + author={Platzer, Esther-S. and Deinzer, Frank and Paulus, Dietrich and Denzler, Joachim}, + pages={288-292}, + language={English} +} + +@article{haugh2004monte, + title={The Monte Carlo Framework, Examples from Finance and Generating Correlated Random Variables}, + author={Haugh, Martin}, + journal={Course Notes}, + year={2004} +} + +@misc{orhan2012particle, + title={Particle Filtering}, + author={Orhan, Emin}, + note={Technical Report}, + howpublished={\url{http://www.cns.nyu.edu/~eorhan/} (Visited: 27.11.2015)}, + year={2012} +} + +@article{doucet2000, +year={2000}, +issn={0960-3174}, +journal={Statistics and Computing}, +volume={10}, +number={3}, +doi={10.1023/A:1008935410038}, +title={On sequential Monte Carlo sampling methods for Bayesian filtering}, +publisher={Kluwer Academic Publishers}, +keywords={Bayesian filtering; nonlinear non-Gaussian state space models; sequential Monte Carlo methods; particle filtering; importance sampling; Rao-Blackwellised estimates}, +author={Doucet, Arnaud and Godsill, Simon and Andrieu, Christophe}, +pages={197-208}, +language={English} +} + +@article{kong1994sequential, + title={Sequential Imputations and Bayesian Missing Data Problems}, + author={Kong, Augustine and Liu, Jun S and Wong, Wing Hung}, + journal={Journal of the American Statistical Association}, + volume={89}, + number={425}, + pages={278--288}, + year={1994}, + publisher={Taylor \& Francis} +} + +@inproceedings{douc2005comparison, + title={Comparison of Resampling Schemes for Particle Filtering}, + author={Douc, Randal and Capp{\'e}, Olivier}, + booktitle={Image and Signal Processing and Analysis, 2005. ISPA 2005. Proc. of the 4th Int. Symp. on}, + pages={64--69}, + year={2005}, + organization={IEEE} +} + +@book{efron1994introduction, + title={An Introduction to the Bootstrap}, + author={Efron, Bradley and Tibshirani, Robert J}, + year={1994}, + publisher={CRC press} +} + +@article{arulampalam2002tutorial, + title={A Tutorial on Particle Filters for Online Nonlinear/Non-Gaussian Bayesian Tracking}, + author={Arulampalam, M Sanjeev and Maskell, Simon and Gordon, Neil and Clapp, Tim}, + journal={Signal Processing, IEEE Transactions on}, + volume={50}, + number={2}, + pages={174--188}, + year={2002}, + publisher={IEEE} +} + +@ARTICLE{Gordon93, +author={Gordon, N.J. and Salmond, D.J. and Smith, A.F.M.}, +journal={Radar and Signal Processing, IEE Proc. F}, +title={Novel Approach to Nonlinear/Non-Gaussian Bayesian State Estimation}, +year={1993}, +volume={140}, +number={2}, +pages={107-113}, +keywords={Bayes methods;Kalman filters;filtering and prediction theory;state estimation;tracking;Gaussian noise;algorithm;bearings only tracking problem;bootstrap filter;extended Kalman filter;measurement model;nonGaussian Bayesian state estimation;nonlinear Bayesian state estimation;random samples;recursive Bayesian filters;simulation;state transition model;state vector density}, +ISSN={0956-375X}, +IGNOREmonth={Apr}, +} + + +@article{DBLP:LiSSC13, + author = {Tiancheng Li and + Shudong Sun and + Tariq P. Sattar and + Juan M. Corchado}, + title = {Fighting against Sample Degeneracy and Impoverishment in Particle + Filters: Particularly on Intelligent Choices}, + journal = {CoRR}, + volume = {abs/1308.2443}, + year = {2013}, + url = {http://arxiv.org/abs/1308.2443}, + timestamp = {Tue, 10 Dec 2013 12:03:02 +0100}, + biburl = {http://dblp.uni-trier.de/rec/bib/journals/corr/LiSSC13}, + bibsource = {dblp computer science bibliography, http://dblp.org} +} + +@PHDTHESIS{blanco2009phd, + author = {Blanco, Jos{\'{e}}-Luis}, + IGNOREmonth = {{nov}}, + title = {Contributions to Localization, Mapping and Navigation in Mobile Robotics}, + year = {2009}, + school = {PhD. in Electrical Engineering, University of Malaga}, + url = {http://www.mrpt.org/Paper:J.L._Blanco_Phd_Thesis} +} + +@article{kunsch2005recursive, + title={Recursive Monte Carlo Filters: Algorithms and Theoretical Analysis}, + author={K{\"u}nsch, Hans R}, + journal={Ann. of Statistics}, + pages={1983--2021}, + year={2005}, + publisher={JSTOR} +} + +@article{rekleitis2004particle, + title={A Particle Filter Tutorial for Mobile Robot Localization}, + author={Rekleitis, Ioannis M}, + journal={Centre for Intelligent Machines, McGill University, Tech. Rep. TR-CIM-04-02}, + year={2004} +} + +@article{cappe2007overview, + title={An Overview of Existing Methods and Recent Advances in Sequential Monte Carlo}, + author={Capp{\'e}, Olivier and Godsill, Simon J and Moulines, Eric}, + journal={Proc. of the IEEE}, + volume={95}, + number={5}, + pages={899--924}, + year={2007}, + publisher={IEEE} +} + +@article{chen2000mixture, + title={Mixture Kalman Filters}, + author={Chen, Rong and Liu, Jun S}, + journal={Journal of the Royal Statistical Society: Series B (Statistical Methodology)}, + volume={62}, + number={3}, + pages={493--508}, + year={2000}, + publisher={Wiley Online Library} +} + +@inproceedings{van2000unscented, + title={The unscented Particle Filter}, + author={Van Der Merwe, Rudolph and Doucet, Arnaud and De Freitas, Nando and Wan, Eric}, + booktitle={NIPS}, + pages={584--590}, + year={2000} +} + +@inproceedings{wan2000unscented, + title={The unscented Kalman filter for nonlinear estimation}, + author={Wan, Eric and Van Der Merwe, Ronell and others}, + booktitle={Adaptive Systems for Signal Processing, Communications, and Control Symp. 2000. AS-SPCC. The IEEE 2000}, + pages={153--158}, + year={2000}, + organization={IEEE} +} + +@inproceedings{Muller:2003:PFS, + author = {M\"{u}ller, Matthias and Charypar, David and Gross, Markus}, + title = {Particle-based Fluid Simulation for Interactive Applications}, + booktitle = {Proc. of the 2003 ACM SIGGRAPH/Eurographics Symp. on Computer Animation}, + series = {SCA '03}, + year = {2003}, + isbn = {1-58113-659-5}, + location = {San Diego, California}, + pages = {154--159}, + numpages = {6}, + url = {http://dl.acm.org/citation.cfm?id=846276.846298}, + acmid = {846298}, + publisher = {Eurographics Association}, + address = {Aire-la-Ville, Switzerland, Switzerland}, +} + +@incollection{isard1998smoothing, + title={A Smoothing Filter for Condensation}, + author={Isard, Michael and Blake, Andrew}, + booktitle={Computer Vision—ECCV'98}, + pages={767--781}, + year={1998}, + publisher={Springer} +} + +@inproceedings{klaas2006fast, + title={Fast Particle Smoothing: If I had a Million Particles}, + author={Klaas, Mike and Briers, Mark and De Freitas, Nando and Doucet, Arnaud and Maskell, Simon and Lang, Dustin}, + booktitle={Proc. of the 23rd Int. Conf. on Machine learning}, + pages={481--488}, + year={2006}, + organization={ACM} +} + +@article{kitagawa1996monte, + title={Monte Carlo Filter and Smoother for non-Gaussian nonlinear State Space Models}, + author={Kitagawa, Genshiro}, + journal={Journal of Computational and Graphical Statistics}, + volume={5}, + number={1}, + pages={1--25}, + year={1996}, + publisher={Taylor \& Francis} +} + +@inproceedings{achtelik2009visual, + title={Visual Tracking and Control of a Quadcopter using a Stereo Camera System and Inertial Sensors}, + author={Achtelik, Markus and Zhang, Tianguang and K{\"u}hnlenz, Kolja and Buss, Martin}, + booktitle={Mechatronics and Automation, 2009. ICMA 2009. Int. Conf. on}, + pages={2863--2869}, + year={2009}, + organization={IEEE} +} + +@book{simonoff2012smoothing, + title={Smoothing Methods in Statistics}, + author={Simonoff, Jeffrey S}, + year={2012}, + publisher={Springer Science \& Business Media} +} + +@book{sachs2013angewandte, + title={Angewandte Statistik: Anwendung statistischer Methoden}, + author={Sachs, Lothar}, + year={2013}, + publisher={Springer-Verlag} +} + +@book{simon2006optimal, + title={Optimal State Estimation: Kalman, H-infinity, and Nonlinear Approaches}, + author={Simon, Dan}, + year={2006}, + publisher={John Wiley \& Sons} +} + +@inproceedings{doucet2000rao, + title={Rao-Blackwellised Particle Filtering for Dynamic Bayesian Networks}, + author={Doucet, Arnaud and De Freitas, Nando and Murphy, Kevin and Russell, Stuart}, + booktitle={Proc. of the Sixteenth Conf. on Uncertainty in Artificial Intelligence}, + pages={176--183}, + year={2000}, + organization={Morgan Kaufmann Publishers Inc.} +} + +@article{briers2010smoothing, + title={Smoothing Algorithms for State-Space Models}, + author={Briers, Mark and Doucet, Arnaud and Maskell, Simon}, + journal={Ann. of the Institute of Statistical Mathematics}, + volume={62}, + number={1}, + pages={61--89}, + year={2010}, + publisher={Springer} +} + +@article{fearnhead2010sequential, + title={A Sequential Smoothing Algorithm with Linear Computational Cost}, + author={Fearnhead, Paul and Wyncoll, David and Tawn, Jonathan}, + journal={Biometrika}, + volume={97}, + number={2}, + pages={447--464}, + year={2010}, + publisher={Biometrika Trust} +} + +@article{kitagawa1987non, + title={Non-Gaussian State-Space Modeling of Nonstationary Time Series}, + author={Kitagawa, Genshiro}, + journal={Journal of the American Statistical Association}, + volume={82}, + number={400}, + pages={1032--1041}, + year={1987}, + publisher={Taylor \& Francis Group} +} + +@article{mayne1966solution, + title={A Solution of the Smoothing Problem for Linear Dynamic Systems}, + author={Mayne, DQ}, + journal={Automatica}, + volume={4}, + number={2}, + pages={73--92}, + year={1966}, + publisher={Elsevier} +} + +@TECHREPORT{briers2004smoothing, + AUTHOR = {Briers, Mark and Doucet, Arnaud and Maskell, Simon}, + TITLE = {Smoothing Algorithms for State-Space Models}, + NUMBER = {CUED/F-INFENG/TR.498}, + INSTITUTION = {Cambridge University Engineering Department}, + YEAR = {2004}, +} + +@inproceedings{Robertson:2009:SLM, + author = {Robertson, Patrick and Angermann, Michael and Krach, Bernhard}, + title = {Simultaneous Localization and Mapping for Pedestrians Using Only Foot-mounted Inertial Sensors}, + booktitle = {Proc. of the 11th Int. Conf. on Ubiquitous Computing}, + series = {UbiComp '09}, + year = {2009}, + isbn = {978-1-60558-431-7}, + location = {Orlando, Florida, USA}, + pages = {93--96}, + numpages = {4}, + publisher = {ACM}, + address = {New York, NY, USA}, + keywords = {ins-based positioning, odometry, indoor positioning, pedestrian navigation, simultaneous localization and mapping}, +} + +@inproceedings{jensen-09, +author={Jensen, Christian S. and Hua Lu and Bin Yang}, +booktitle={Mobile Data Management: Systems, Services and Middleware, 2009. MDM '09. Tenth Int. Conf. on}, +title={Graph Model Based Indoor Tracking}, +year={2009}, +pages={122-131}, +keywords={graph theory;radio tracking;radiofrequency identification;radionavigation;telecommunication network topology;RFID-based positioning;base graph model;indoor navigation;indoor positioning technologies;indoor tracking;specific reader deployment graph model;symbolic positioning technologies;uniform data management infrastructure;Bluetooth;Computer science;Data structures;Mobile computing;Navigation;Partitioning algorithms;Radiofrequency identification;Space technology;Technology management;Topology}, +doi={10.1109/MDM.2009.23}, +IGNOREmonth={May},} + +@MastersThesis{Ebner:Thesis:2013, + author = {Frank Ebner}, + title = {{Statistische Selbstlokalisation mittels WiFi SLAM}}, + school = {University of Applied Sciences W{\"u}rzburg - Schweinfurt}, + address = {W{\"u}rzburg}, + year = {2013}, + } + +@article{shortestPath:96, +year={1996}, +issn={0025-5610}, +journal={Mathematical Programming}, +volume={73}, +number={2}, +doi={10.1007/BF02592101}, +title={Shortest Paths Algorithms: Theory and Experimental Evaluation}, +url={http://dx.doi.org/10.1007/BF02592101}, +publisher={Springer-Verlag}, +keywords={Graph algorithms; Network optimization; Shortest paths; Theory and experimental evaluation of algorithms}, +author={Cherkassky, Boris V. and Goldberg, Andrew V. and Radzik, Tomasz}, +pages={129-174}, +language={English} +} + +@inproceedings{werner2014homotopy, +Title = {Homotopy and Alternative Routes in Indoor Navigation Scenarios}, +Author = {Martin Werner and Sebastian Feld}, +Booktitle = {Indoor Positioning and Indoor Navigation (IPIN), Int. Conf. on}, +Year = {2014}, +Pages = {1-9}, +} + +@inproceedings{Li2015, +abstract = {This paper presents an indoor navigation algorithm that uses multiple kinds of sensors and technologies, such as MEMS sensors (i.e., gyros, accelerometers, magnetometers, and a barometer), WiFi, and magnetic matching. The corresponding real-time software on smartphones includes modules such dead-reckoning, WiFi positioning, and magnetic matching. DR is used for providing continuous position solutions and for the blunder detection of both WiFi fingerprinting and magnetic matching. Finally, WiFi and magnetic matching results are passed into the position-tracking module as updates. Meanwhile, a barometer is used to detect floor changes, so as to switch floors and the WiFi and magnetic databases. This algorithm was tested during the 5th EvAAL indoor navigation competition. Position errors on three quarters (75 {\%}) of test points (totally 62 test points were selected to evaluate the algorithm) were under 6.6 m.}, +author = {Li, You and Zhang, Peng and Niu, Xiaoji and Zhuang, Yuan and Lan, Haiyu and El-Sheimy, Naser}, +booktitle = {Int. Conf. on Indoor Positioning and Indoor Navigation (IPIN)}, +doi = {10.1109/IPIN.2015.7346966}, +file = {:home/toni/Documents/literatur/fusion16/Real-time indoor navigation using smartphone sensors.pdf:pdf}, +isbn = {978-1-4673-8402-5}, +keywords = {5th EvAAL indoor navigation competition,Fingerprint recognition,IEEE 802.11 Standard,Indoor navigation,Localisation System,MEMS sensors,Magnetometers,Position measurement,Sensors,WiFi fingerprinting,WiFi positioning,accelerometers,barometer,barometers,dead-reckoning,floor change detection,gyros,gyroscopes,indoor navigation,magnetic features,magnetic matching,magnetometers,micromechanical devices,position-tracking module,radionavigation,real-time indoor navigation,smart phones,smartphone,smartphone sensors,wireless LAN}, +mendeley-tags = {Localisation System}, +IGNOREmonth = {oct}, +pages = {1--10}, +publisher = {IEEE}, +shorttitle = {Indoor Positioning and Indoor Navigation (IPIN), 2}, +title = {{Real-time Indoor Navigation using Smartphone Sensors}}, +year = {2015} +} + +@article{Yang2015, +author = {Yang, Zheng and Wu, Chenshu and Zhou, Zimu and Zhang, Xinglin and Wang, Xu and Liu, Yunhao}, +doi = {10.1145/2676430}, +file = {:home/toni/Documents/literatur/fusion16/Mobility Increases Localizability$\backslash$: A Survey on Wireless Indoor.pdf:pdf}, +issn = {03600300}, +journal = {ACM Computing Surveys}, +keywords = {Mobility,smartphones,wireless indoor localization}, +IGNOREmonth = {apr}, +number = {3}, +pages = {1--34}, +publisher = {ACM}, +title = {{Mobility Increases Localizability: A Survey on Wireless Indoor Localization using Inertial Sensors}}, +volume = {47}, +year = {2015} +} + +@article{Gu2009, +abstract = {Recently, indoor positioning systems (IPSs) have been designed to provide location information of persons and devices. The position information enables location-based protocols for user applications. Personal networks (PNs) are designed to meet the users' needs and interconnect users' devices equipped with different communications technologies in various places to form one network. Location-aware services need to be developed in PNs to offer flexible and adaptive personal services and improve the quality of lives. This paper gives a comprehensive survey of numerous IPSs, which include both commercial products and research-oriented solutions. Evaluation criteria are proposed for assessing these systems, namely security and privacy, cost, performance, robustness, complexity, user preferences, commercial availability, and limitations. We compare the existing IPSs and outline the trade-offs among these systems from the viewpoint of a user in a PN.}, +author = {Gu, Yanying and Lo, Anthony and Niemegeers, Ignas}, +doi = {10.1109/SURV.2009.090103}, +file = {:home/toni/Documents/literatur/fusion16/A Survey of Indoor Positioning Systems for.pdf:pdf}, +isbn = {1553-877X}, +issn = {1553877X}, +journal = {IEEE Communications Surveys and Tutorials}, +keywords = {Indoor positioning systems,Location techniques,Personal networks}, +number = {1}, +pages = {13--32}, +shorttitle = {Communications Surveys {\&} Tutorials, IEEE}, +title = {{A Survey of Indoor Positioning Systems for Wireless Personal Networks}}, +volume = {11}, +year = {2009} +} + +@article{Khaleghi2013, +abstract = {There has been an ever-increasing interest in multi-disciplinary research on multisensor data fusion technology, driven by its versatility and diverse areas of application. Therefore, there seems to be a real need for an analytical review of recent developments in the data fusion domain. This paper proposes a comprehensive review of the data fusion state of the art, exploring its conceptualizations, benefits, and challenging aspects, as well as existing methodologies. In addition, several future directions of research in the data fusion community are highlighted and described.}, +author = {Khaleghi, Bahador and Khamis, Alaa and Karray, Fakhreddine O. and Razavi, Saiedeh N.}, +doi = {10.1016/j.inffus.2011.08.001}, +file = {:home/toni/.local/share/data/Mendeley Ltd./Mendeley Desktop/Downloaded/Khaleghi et al. - 2013 - Multisensor data fusion A review of the state-of-the-art.pdf:pdf}, +issn = {15662535}, +journal = {Information Fusion}, +keywords = {Fusion methodologies,Multisensor data fusion,Taxonomy}, +IGNOREmonth = {jan}, +number = {1}, +pages = {28--44}, +title = {{Multisensor data fusion: A review of the state-of-the-art}}, +volume = {14}, +year = {2013} +} + +@inproceedings{Liao2003, +abstract = { Tracking the activity of people in indoor environments has gained considerable attention in the robotics community over the last years. Most of the existing approaches are based on sensors, which allow to accurately determining the locations of people but do not provide means to distinguish between different persons. In this paper we propose a novel approach to tracking moving objects and their identity using noisy, sparse information collected by id-sensors such as infrared and ultrasound badge systems. The key idea of our approach is to use particle filters to estimate the locations of people on the Voronoi graph of the environment. By restricting particles to a graph, we make use of the inherent structure of indoor environments. The approach has two key advantages. First, it is by far more efficient and robust than unconstrained particle filters. Second, the Voronoi graph provides a natural discretization of human motion, which allows us to apply unsupervised learning techniques to derive typical motion patterns of the people in the environment. Experiments using a robot to collect ground-truth data indicate the superior performance of Voronoi tracking. Furthermore, we demonstrate that EM-based learning of behavior patterns increases the tracking performance and provides valuable information for high-level behavior recognition.}, +author = {Liao, Lin and Fox, D. and Hightower, J. and Kautz, H. and Schulz, D.}, +booktitle = {Proc. 2003 IEEE/RSJ Int. Conf. on Intelligent Robots and Systems (IROS 2003)}, +doi = {10.1109/IROS.2003.1250715}, +file = {:home/toni/Documents/literatur/fusion16/Voronoi .pdf:pdf}, +isbn = {0-7803-7860-1}, +keywords = {Computer science,Humans,Indoor environments,Particle filters,Pattern recognition,Robot sensing systems,Robustness,State-space methods,Ultrasonic imaging,Voronoi graph,Voronoi tracking,Working environment noise,array signal processing,computational geometry,high-level behavior recognition,human motion,indoor environments,infrared badge system,mobile robots,motion estimation,noisy sensor data,particle filters,robot,tracking,tracking moving objects,ultrasound badge systems,unsupervised learning techniques}, +pages = {723--728}, +publisher = {IEEE}, +shorttitle = {Intelligent Robots and Systems, 2003. (IROS 2003).}, +title = {{Voronoi Tracking: Location Estimation Using Sparse and Noisy Sensor Data}}, +volume = {1}, +year = {2003} +} + + +@article{Afyouni2012, +abstract = {This paper surveys indoor spatial models developed for research fields ranging from mobile robot mapping, to indoor location-based services (LBS), and most recently to context-aware navigation services applied to indoor environments. Over the past few years, several studies have evaluated the potential of spatial models for robot navigation and ubiquitous computing. In this paper we take a slightly different perspective, considering not only the underlying properties of those spatial models, but also to which degree the notion of context can be taken into account when delivering services in indoor environments. Some preliminary recommendations for the development of indoor spatial models are introduced from a context-aware perspective. A taxonomy of models is then presented and assessed with the aim of providing a flexible spatial data model for navigation purposes, and by taking into account the context dimensions.}, +author = {Afyouni, Imad and Ray, Cyril and Claramunt, Christophe}, +doi = {10.5311/JOSIS.2012.4.73}, +file = {:home/toni/.local/share/data/Mendeley Ltd./Mendeley Desktop/Downloaded/Afyouni, Ray, Claramunt - 2012 - Spatial models for context-aware indoor navigation systems A survey.pdf:pdf}, +issn = {1948-660X}, +journal = {Journal of Spatial Information Science}, +keywords = {context-awareness,indoor spatial data models,location-dependent queries,navigation systems and wayfinding,qualitative spatial representation,quantitative spatial representation}, +language = {en}, +IGNOREmonth = {Jun}, +number = {4}, +pages = {85--123}, +title = {{Spatial models for context-aware indoor navigation systems: A survey}}, +volume = {1}, +year = {2012} +} + +@inproceedings{Hilsenbeck2014, +abstract = {We propose a graph-based, low-complexity sensor fusion approach for ubiquitous pedestrian indoor positioning using mobile devices. We employ our fusion technique to combine relative motion information based on step detection with WiFi signal strength measurements. The method is based on the well-known particle filter methodology. In contrast to previous work, we provide a probabilistic model for location estimation that is formulated directly on a fully discretized, graph-based representation of the indoor environment. We generate this graph by adaptive quantization of the indoor space, removing irrelevant degrees of freedom from the estimation problem. We evaluate the proposed method in two realistic indoor environments using real data collected from smartphones. In total, our dataset spans about 20 kilometers in distance walked and includes 13 users and four different mobile device types. Our results demonstrate that the filter requires an order of magnitude less particles than state-of-the-art approaches while maintaining an accuracy of a few meters. The proposed low-complexity solution not only enables indoor positioning on less powerful mobile devices, but also saves much-needed resources for location-based end-user applications which run on top of a localization service.}, +address = {New York, NY, USA}, +author = {Hilsenbeck, Sebastian and Bobkov, Dmytro and Schroth, Georg and Huitl, Robert and Steinbach, Eckehard}, +booktitle = {Proc. of the 2014 ACM Int. Joint Conf. on Pervasive and Ubiquitous Computing - UbiComp '14 Adjunct}, +doi = {10.1145/2632048.2636079}, +file = {:home/toni/Documents/literatur/fusion16/Graph-based Data Fusion of Pedometer and WiFi Measurements for Mobile Indoor Positioning.pdf:pdf}, +isbn = {9781450329682}, +keywords = {Graph-based Sensor Fusion,Indoor Navigation,Indoor Positioning,Location-based Services,Mobile Computing,Particle Filter,Ubiquitous Localization}, +IGNOREmonth = {sep}, +pages = {147--158}, +publisher = {ACM Press}, +title = {{Graph-based Data Fusion of Pedometer and WiFi Measurements for Mobile Indoor Positioning}}, +year = {2014} +} + + +@article{hotelling1933, + title={{Analysis of a Complex of Statistical Variables into Principal Components.}}, + author={Hotelling, Harold}, + journal={Journal of educational psychology}, + volume={24}, + number={6}, + pages={417}, + year={1933}, + publisher={Warwick \& York} +} + +@article{Thrun2003, +abstract = {This article describes a new algorithm for acquiring occupancy grid maps with mobile robots. Existing occupancy grid mapping algorithms decompose the high-dimensional mapping problem into a collection of one-dimensional problems, where the occupancy of each grid cell is estimated independently. This induces conflicts that may lead to inconsistent maps, even for noise-free sensors. This article shows how to solve the mapping problem in the original, high-dimensional space, thereby maintaining all dependencies between neighboring cells. As a result, maps generated by our approach are often more accurate than those generated using traditional techniques. Our approach relies on a statistical formulation of the mapping problem using forward models. It employs the expectation maximization algorithm for searching maps that maximize the likelihood of the sensor measurements.}, +author = {Thrun, Sebastian}, +doi = {10.1023/A:1025584807625}, +file = {:home/toni/Documents/literatur/fusion16/thrun.iros01-occmap.pdf:pdf}, +isbn = {0-7803-6612-3}, +issn = {09295593}, +journal = {Autonomous Robots}, +keywords = {Bayesian techniques,Mapping,Mobile robotics,Probabilistic inference,Robot navigation,SLAM}, +language = {en}, +number = {2}, +pages = {111--127}, +pmid = {563334}, +publisher = {Kluwer Academic Publishers}, +title = {{Learning Occupancy Grid Maps with Forward Sensor Models}}, +volume = {15}, +year = {2003} +} + +@article{Li2010, +abstract = {While recent years have witnessed noticeable development of indoor GIS, there is still a lack of clear consensus on the modeling principles that should support such applications. The objective of the research presented in this paper is to represent two-dimensional (2D) indoor spaces with a grid graph-based model that takes into account the structural and spatial properties of an indoor space. The model developed considers a built environment as a frame of reference at different levels of granularity using a grid graph-based representation. The advantage of the modeling approach is that it combines structural and topological properties as well as implicitly taking into account the metric of space, this being often overlooked by most existing indoor space models. Several types of indoor space analysis are employed to illustrate the potential of the proposed model, such as route and diffusion analysis, centrality and topological analysis.}, +author = {Li, Xiang and Claramunt, Christophe and Ray, Cyril}, +doi = {10.1016/j.compenvurbsys.2010.07.006}, +file = {:home/toni/.local/share/data/Mendeley Ltd./Mendeley Desktop/Downloaded/Li, Claramunt, Ray - 2010 - A grid graph-based model for the analysis of 2D indoor spaces.pdf:pdf}, +issn = {01989715}, +journal = {Computers, Environment and Urban Systems}, +keywords = {Grid graph-based representation,Indoor spaces,Network,Structural-based modeling}, +IGNOREmonth = {nov}, +number = {6}, +pages = {532--540}, +title = {{A grid graph-based model for the analysis of 2D indoor spaces}}, +volume = {34}, +year = {2010} +} + +@article{elfes1989using, + title={{Using Occupancy Grids for Mobile Robot Perception and Navigation}}, + author={Elfes, Alberto}, + journal={Computer}, + volume={22}, + number={6}, + pages={46--57}, + year={1989}, + publisher={IEEE} +} + +@article{GarciaPuyol2014, +abstract = {Pedestrian navigation is an important ingredient for efficient multimodal transportation, such as guidance within large transportation infrastructures. A requirement is accurate positioning of people in indoor multistory environments. To achieve this, maps of the environment play a very important role. FootSLAM is an algorithm based on the simultaneous localization and mapping (SLAM) principle that relies on human odometry, i.e., measurements of a pedestrian's steps, to build probabilistic maps of human motion for such environments and can be applied using crowdsourcing. In this paper, we extend FootSLAM to multistory buildings following a Bayesian derivation. Our approach employs a particle filter and partitions the map space into a grid of adjacent hexagonal prisms with eight faces. We model the vertical component of the odometry errors using an autoregressive integrated moving average (ARIMA) model and extend the geographic tree-based data structure that efficiently stores the probabilistic map, allowing real-time processing. We present the multistory FootSLAM maps that were created from three data sets collected in different buildings (one large office building and two university buildings). Hereby, the user was only carrying a single foot-mounted inertial measurement unit (IMU). We believe the resulting maps to be strong evidence of the robustness of FootSLAM. This paper raises the future possibility of crowdsourced indoor mapping and accurate navigation using other forms of human odometry, e.g., obtained with the low-cost and nonintrusive sensors of a handheld smartphone.}, +author = {{Garcia Puyol}, Maria and Bobkov, Dmytro and Robertson, Patrick and Jost, Thomas}, +doi = {10.1109/TITS.2014.2303115}, +file = {:home/toni/.local/share/data/Mendeley Ltd./Mendeley Desktop/Downloaded/Garcia Puyol et al. - 2014 - Pedestrian simultaneous localization and mapping in multistory buildings using inertial sensors.pdf:pdf}, +issn = {15249050}, +journal = {IEEE Transactions on Intelligent Transportation Systems}, +keywords = {Indoor pedestrian navigation,inertial navigation,multistory localization and mapping,simultaneous localization and mapping (SLAM)}, +IGNOREmonth = {aug}, +number = {4}, +pages = {1714--1727}, +shorttitle = {Intelligent Transportation Systems, IEEE Transacti}, +title = {{Pedestrian Simultaneous Localization and Mapping in Multistory Buildings using Inertial Sensors}}, +volume = {15}, +year = {2014} +} + +@article{Bandi2000, +abstract = {This paper presents an efficient and robust technique for generating global motion paths for a human model in virtual environments. Initially, a scene is discretized using raster hardware to generate an environment map. An obstacle-free cell path sub-optimal according to Manhattan metric is generated between any two cells. Unlike 2D techniques present in literature, the proposed algorithm works for complex 3D environments suitable for video games and architectural walk-throughs. For obstacle avoidance, the algorithm considers both physical dimensions of the human and actions such as jumping, bending, etc. Path smoothening is carried out to keep the cell path as closely as possible to Euclidean straight-line paths.}, +author = {Bandi, Srikanth and Thalmann, Daniel}, +doi = {10.1016/S0925-7721(99)00046-2}, +file = {:home/toni/.local/share/data/Mendeley Ltd./Mendeley Desktop/Downloaded/Bandi, Thalmann - 2000 - Path finding for human motion in virtual environments.pdf:pdf}, +issn = {09257721}, +journal = {Computational Geometry}, +keywords = {Cellular paths,Heuristic search,Obstacle avoidance,Path planning,Pathfinding,Virtual walk-throughs}, +mendeley-tags = {Pathfinding}, +number = {1-3}, +pages = {103--127}, +title = {{Path finding for human motion in virtual environments}}, +volume = {15}, +year = {2000} +} + +@inproceedings{tan2014agent, + title={Agent-based simulation of building evacuation using a grid graph-based model}, + author={Tan, Lu and Lin, Hui and Hu, Mingyuan and Che, Weitao}, + booktitle={IOP Conf. Series: Earth and Environmental Science}, + volume={18}, + number={1}, + year={2014}, + organization={IOP Publishing} +} + +@inproceedings{Sun2011, +abstract = {At present, application of GIS is in a process of transition from macro space to micro space, such as indoor space, a kind of micro environment that has a smaller scale than outdoor space. There have been some applications for indoor space, covering issues like path finding, emergency planning, object tracking, etc. Behind these applications, indoor spatial models are needed to illustrate how built environments are spatially represented. Although some modeling approaches have been proposed, most of them focus only on either structural or topological properties. In view of this problem, recently a grid graph-based modeling approach considering a built environment as a continuous framework is presented, which is able to combine both geometrical and structural properties. In this paper, we employ this approach to implement route analysis based on a hotel floor plan. The result might be applied to the planning for evacuation routes.}, +author = {Sun, Jing and Li, Xiang}, +booktitle = {Proc. - 2011 19th Int. Conf. on Geoinformatics, Geoinformatics 2011}, +doi = {10.1109/GeoInformatics.2011.5980680}, +isbn = {9781612848488}, +issn = {9781612848495}, +keywords = {evacuation planning,grid graph-based model,indoor space}, +IGNOREmonth = {jun}, +pages = {1--4}, +publisher = {IEEE}, +shorttitle = {Geoinformatics, 2011 19th Int. Conf.}, +title = {{Indoor Evacuation Routes Planning with a Grid Graph-based Model}}, +year = {2011} +} + +@inproceedings{Brogan2003, +abstract = {Pedestrian navigation is a complex function of human dynamics, a desired destination, and the presence of obstacles. People cannot stop and start instantaneously and their turning abilities are influenced by kinematic and dynamical constraints. A realistic model of human walking paths is an important development for entertainment applications and many classes of simulations. We present a novel behavioral model of path planning that extends previous models through its significant use of pedestrian performance statistics that were obtained during a suite of experiments. We develop an original interpretation of quantitative metrics for measuring a model’s accuracy, and use it to compare our path planning approach to a popular contemporary method. Results indicate that this new path planning model better fits natural human behavior than previous models.}, +author = {Brogan, D. C. and Johnson, N. L.}, +booktitle = {Proc. - IEEE Workshop on Program Comprehension}, +doi = {10.1109/CASA.2003.1199309}, +file = {:home/toni/Documents/literatur/Realistic human walking paths.pdf:pdf}, +isbn = {0769519342}, +issn = {10928138}, +keywords = {Air safety,Animation,Humans,Kinematics,Legged locomotion,Navigation,Path planning,Robots,Testing,Turning}, +pages = {94--101}, +publisher = {IEEE Comput. Soc}, +shorttitle = {Computer Animation and Social Agents, 2003. 16th I}, +title = {{Realistic human walking paths}}, +volume = {2003-Janua}, +year = {2003} +} + +@article{Cover1967, +abstract = {The nearest neighbor decision rule assigns to an unclassified sample point the classification of the nearest of a set of previously classified points. This rule is independent of the underlying joint distribution on the sample points and their classifications, and hence the probability of errorRof such a rule must be at least as great as the Bayes probability of errorR{\^{}}{\{}$\backslash$ast{\}}--the minimum probability of error over all decision rules taking underlying probability structure into account. However, in a large sample analysis, we will show in theM-category case thatR{\^{}}{\{}$\backslash$ast{\}} $\backslash$leq R $\backslash$leq R{\^{}}{\{}$\backslash$ast{\}}(2 --MR{\^{}}{\{}$\backslash$ast{\}}/(M-1)), where these bounds are the tightest possible, for all suitably smooth underlying distributions. Thus for any number of categories, the probability of error of the nearest neighbor rule is bounded above by twice the Bayes probability of error. In this sense, it may be said that half the classification information in an infinite sample set is contained in the nearest neighbor.}, +author = {Cover, T. M. and Hart, P. E.}, +doi = {10.1109/TIT.1967.1053964}, +isbn = {0018-9448}, +issn = {15579654}, +journal = {IEEE Transactions on Information Theory}, +keywords = {Pattern classification}, +IGNOREmonth = {jan}, +number = {1}, +pages = {21--27}, +pmid = {21919855}, +shorttitle = {Information Theory, IEEE Transactions on}, +title = {{Nearest Neighbor Pattern Classification}}, +volume = {13}, +year = {1967} +} + diff --git a/tex/gfx/build.sh b/tex/gfx/build.sh new file mode 100644 index 0000000..229c082 --- /dev/null +++ b/tex/gfx/build.sh @@ -0,0 +1,4 @@ +for file in *.gp +do + gnuplot $file; +done diff --git a/tex/make.sh b/tex/make.sh new file mode 100644 index 0000000..fabcb72 --- /dev/null +++ b/tex/make.sh @@ -0,0 +1,15 @@ +#!/bin/bash + +#PATH=$PATH:/mnt/data/texlive/bin/x86_64-linux/ +PATH=$PATH:/mnt/vm/programme/texlive/bin/x86_64-linux/ + +latex bare_conf.tex +bibtex bare_conf +latex bare_conf.tex +latex bare_conf.tex + +dvips bare_conf.dvi + +ps2pdf14 bare_conf.ps + +okular bare_conf.pdf& diff --git a/tex/misc/functions.tex b/tex/misc/functions.tex new file mode 100644 index 0000000..9a098c9 --- /dev/null +++ b/tex/misc/functions.tex @@ -0,0 +1,137 @@ + +\newcommand{\mAvgSquaredError}{\ensuremath{\overline{e}}} + +\newcommand{\mLogDistGamma}{\ensuremath{\gamma}} +\newcommand{\mLogDistTX}{TX} + +\newcommand{\mDongle}[1]{\ensuremath{D_{#1}}} +%\newcommand{\mDongle}{d} % dongle +\newcommand{\mBeacon}[1]{\ensuremath{B_{#1}}} % beacon + +\newcommand{\mRssi}{\ensuremath{s}} % client's signal-strength measurement +\newcommand{\mMdlRSSI}{\ensuremath{\varsigma}} % model's signal-strength + +\newcommand{\mPosAP}{\varrho} % char for access point position vector +\newcommand{\mPos}{\rho} % char for positions + + +\newcommand{\mPosVec}{\vec{\mPos}} % position vector +\newcommand{\mRssiVec}{\vec{s}} % client signal strength measurements + +\newcommand{\mState}{q} % state variable +\newcommand{\mStateVec}{\vec{q}} % state vector variable +\newcommand{\mObs}{o} % observation variable +\newcommand{\mObsVec}{\vec{o}} % observation vector variable +\newcommand{\mObsWifi}{\vec{o}_{\text{wifi}}} % wifi observation + +\newcommand{\mProb}{p} % char for probability + +\newcommand{\mMovingAvgWithSize}[1]{\ensuremath{\text{avg}_{#1}}} + +\newcommand{\mPressure}{\rho} +\newcommand{\mObsPressure}{\mPressure_\text{rel}} % symbol for observation pressure +\newcommand{\mStatePressure}{\hat{\mPressure}_\text{rel}} % symbol for state pressure + +\newcommand{\mHeading}{\theta} +\newcommand{\mObsHeading}{\Delta\mHeading} % symbol used for the observation heading +\newcommand{\mStateHeading}{\mHeading} % symbol used for the state heading + +\newcommand{\mSteps}{n_\text{steps}} +\newcommand{\mObsSteps}{\mSteps} + +\newcommand{\mNN}{\text{nn}} +\newcommand{\mKNN}{\text{knn}} +\newcommand{\fPos}[1]{\textbf{pos}(#1)} +\newcommand{\fDistance}[2]{\delta(#1, #2)} +\newcommand{\fWA}[1]{\text{wall}(#1)} +\newcommand{\fDD}[1]{\text{door}(#1)} +\newcommand{\fImp}[1]{\text{imp}(#1)} +\newcommand{\fNN}[2]{\text{nn}(#1, #2)} +\newcommand{\fLength}[2]{\text{d}(#1, #2)} + +%\newcommand{\mTarget}{\dot{v}} +\newcommand{\mVertexA}{v_i} +\newcommand{\mVertexB}{v_j} +\newcommand{\mEdgeAB}{e_{i,j}} +\newcommand{\mVertexDest}{v_\text{dest}} + +\newcommand{\mUsePath}{\kappa} + +\newcommand{\mStepSize}{s_\text{step}} + +%\newcommand{\docIBeacon}{iBeacon} + +% for equation references +\newcommand{\refeq}[1]{eq. \eqref{#1}} + +% add todo notes +\newcommand{\todo}[1]{% + \noindent% + \fcolorbox{black}{yellow}{% + \parbox[position]{0.45\textwidth}{% + \footnotesize% + {\bf TODO} #1% + }% + }% +} + +%\newcommand{\commentByFrank}[1]{} +%\newcommand{\commentByToni}[1]{} + +%comments +\newcommand{\commentByFrank}[1]{% + \noindent% + \fcolorbox{black}{cyan}{% + \parbox[position]{0.45\textwidth}{% + \footnotesize% + {\bf Frank:} #1% + }% + }% +} +\newcommand{\commentByLukas}[1]{% + \noindent% + \fcolorbox{black}{green}{% + \parbox[position]{0.45\textwidth}{% + \footnotesize% + {\bf Lukas:} #1% + }% + }% +} +\newcommand{\commentByToni}[1]{% + \noindent% + \fcolorbox{black}{red}{% + \parbox[position]{0.45\textwidth}{% + \footnotesize% + {\bf Toni:} #1% + }% + }% +} + +\newcommand{\docRSSI}{RSSI} +\newcommand{\docTX}{TX} +\newcommand{\docLogDist}{log-distance} + +%\newcommand{\docAP}{access-point} +%\newcommand{\docAPs}{access-points} + + + + +\newcommand{\R}{\mathbb{R}} +\newcommand{\N}{\mathbb{N}} + +\newcommand{\mPLE}{\ensuremath{\gamma}} % path-loss exponent +\newcommand{\mTXP}{\ensuremath{P_0}} % tx-power +\newcommand{\mWAF}{\ensuremath{\beta}} % wall attenuation factor + +\newcommand{\mMdlDist}{\ensuremath{d}} % distance used within propagation models + +%\newcommand{\mGraph}{\ensuremath{G}} +%\newcommand{\mVertices}{\ensuremath{V}} +%\newcommand{\mVertex}{\ensuremath{v}} +%\newcommand{\mVertexB}{\ensuremath{w}} +%\newcommand{\mEdges}{\ensuremath{E}} +%\newcommand{\mEdge}{\ensuremath{e}} + + + diff --git a/tex/misc/keywords.tex b/tex/misc/keywords.tex new file mode 100644 index 0000000..2d928f2 --- /dev/null +++ b/tex/misc/keywords.tex @@ -0,0 +1,31 @@ +% keyword macros +\newcommand{\docIBeacon}{iBeacon} + +% wifi naming +\newcommand{\wifiRSSI}{RSSI} +\newcommand{\wifiTxPower}{TX-Power} +\newcommand{\wifiPathLossExp}{PathLoss} + +\newcommand{\wifiPropLogScale}{Log-Scale} +\newcommand{\wifiPropLogScaleWalls}{Log-Scale-Walls} +\newcommand{\docLogDistance}{log-distance} +\newcommand{\docLogDistanceWalls}{wall-attenuation-factor} + + +% misc +\newcommand{\docTxPower}{TX-Power} +\newcommand{\docPathLossExp}{PathLoss} +\newcommand{\docPathLoss}{Pathloss} + +\newcommand{\docsAP}{AP} +\newcommand{\docAPshort}{AP} +\newcommand{\docAP}{access-point} +\newcommand{\docAPs}{access-points} + +\newcommand{\docWIFI}{Wi\hbox{-}Fi} +\newcommand{\docBeacon}{\Gls{Beacon}} +\newcommand{\docBeacons}{\Glspl{Beacon}} + +\newcommand{\docsRSSI}{RSSI} + +\newcommand{\docDSimplex}{downhill-simplex}