a lot!!! of changes
added main menu added debug display many debug widgets for plotting live data worked on android live sensors added offline-data sensor feeding some dummy data sensors worked on the map display added ui debug for grid-points, particles and weights added a cool dude to display the estimation added real filtering based on the Indoor components c++11 fixes for android compilation online and offline filtering support new resampling technique for testing map loading via dialog
29
Config.h
Normal file
@@ -0,0 +1,29 @@
|
||||
#ifndef CONFIG_H
|
||||
#define CONFIG_H
|
||||
|
||||
#include <string>
|
||||
#include <QDebug>
|
||||
|
||||
class Config {
|
||||
|
||||
public:
|
||||
|
||||
// notes
|
||||
// copy: scp -P 2222 /tmp/grid.dat kazu@192.168.24.11:/storage/sdcard1/YASMIN/maps/car/
|
||||
// all: scp -P 2222 -r /apps/android/workspace/YASMIN_DATA/* kazu@192.168.24.11:/storage/sdcard1/YASMIN/
|
||||
|
||||
/** get the directory where maps are stored */
|
||||
static inline std::string getMapDir() {
|
||||
#ifdef ANDROID
|
||||
// const std::string folder = getenv("EXTERNAL_STORAGE") + std::string("/YASMIN/maps/"); // this is NOT the sdcard?!
|
||||
// qDebug(folder.c_str());
|
||||
// return folder;
|
||||
return "/storage/sdcard1/YASMIN/maps/";
|
||||
#else
|
||||
return "/apps/android/workspace/YASMIN_DATA/maps/";
|
||||
#endif
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // CONFIG_H
|
||||
135
Controller.cpp
Normal file
@@ -0,0 +1,135 @@
|
||||
#include "Controller.h"
|
||||
|
||||
#include "ui/map/MapView.h"
|
||||
#include "ui/menu/MainMenu.h"
|
||||
#include "ui/MainWindow.h"
|
||||
#include "ui/dialog/LoadSetupDialog.h"
|
||||
#include "ui/debug/SensorDataWidget.h"
|
||||
|
||||
#include <Indoor/grid/factory/v2/GridFactory.h>
|
||||
#include <Indoor/grid/factory/v2/Importance.h>
|
||||
|
||||
#include <Indoor/floorplan/v2/Floorplan.h>
|
||||
#include <Indoor/floorplan/v2/FloorplanReader.h>
|
||||
#include <Indoor/Assertions.h>
|
||||
|
||||
#include "sensors/dummy/SensorFactoryDummy.h"
|
||||
#include "sensors/android/SensorFactoryAndroid.h"
|
||||
#include "sensors/offline/SensorFactoryOffline.h"
|
||||
|
||||
#include "nav/NavController.h"
|
||||
|
||||
Controller::Controller() {
|
||||
|
||||
// OpenGL setup
|
||||
// MUST happen before anything gets visible (= gets initialized)
|
||||
QSurfaceFormat format;
|
||||
format.setDepthBufferSize(16);
|
||||
QSurfaceFormat::setDefaultFormat(format);
|
||||
|
||||
// configure the to-be-used sensor factory
|
||||
//SensorFactory::set(new SensorFactoryDummy());
|
||||
//SensorFactory::set(new SensorFactoryOffline("/apps/android/workspace/YASMIN_DATA/offline/gyroacctestingfrank/nexus6/kleinerKreis_216steps_6runden_telefongerade.csv"));
|
||||
//SensorFactory::set(new SensorFactoryOffline("/apps/android/workspace/YASMIN_DATA/offline/gyroacctestingfrank/s3mini/kleinerKreis_225steps_6runden_telefongerade.csv"));
|
||||
//SensorFactory::set(new SensorFactoryOffline("/apps/android/workspace/YASMIN_DATA/offline/gyroacctestingfrank/s4/kleinerKreis_220steps_6runden_telefongeneigt.csv"));
|
||||
SensorFactory::set(new SensorFactoryOffline("/apps/android/workspace/YASMIN_DATA/offline/bergwerk/path4/nexus/vor/1454776525797.csv"));
|
||||
|
||||
|
||||
|
||||
|
||||
mainWindow = new MainWindow();
|
||||
|
||||
|
||||
Assert::isTrue(connect(mainWindow->getMainMenu(), &MainMenu::onLoadButton, this, &Controller::onLoadButton), "connect() failed");
|
||||
Assert::isTrue(connect(mainWindow->getMainMenu(), &MainMenu::onDebugButton, this, &Controller::onDebugButton), "connect() failed");
|
||||
Assert::isTrue(connect(mainWindow->getMainMenu(), &MainMenu::onStartButton, this, &Controller::onStartButton), "connect() failed");
|
||||
Assert::isTrue(connect(mainWindow->getMainMenu(), &MainMenu::onTransparentButton, this, &Controller::onTransparentButton), "connect() failed");
|
||||
Assert::isTrue(connect(mainWindow->getMainMenu(), &MainMenu::onCameraButton, this, &Controller::onCameraButton), "connect() failed");
|
||||
|
||||
// order is important! otherwise OpenGL fails!
|
||||
mainWindow->show();
|
||||
|
||||
|
||||
|
||||
// start all sensors
|
||||
SensorFactory::get().getAccelerometer().start();
|
||||
SensorFactory::get().getGyroscope().start();
|
||||
SensorFactory::get().getBarometer().start();
|
||||
SensorFactory::get().getWiFi().start();
|
||||
|
||||
}
|
||||
|
||||
MapView* Controller::getMapView() const {
|
||||
return mainWindow->getMapView();
|
||||
}
|
||||
|
||||
|
||||
void buildGridOnce(Grid<MyGridNode>* grid, Floorplan::IndoorMap* map, const std::string& saveFile) {
|
||||
GridFactory<MyGridNode> gf(*grid);
|
||||
gf.build(map);
|
||||
Importance::addImportance(*grid);
|
||||
std::ofstream out(saveFile, std::ofstream::binary);
|
||||
grid->write(out);
|
||||
out.close();
|
||||
}
|
||||
|
||||
void Controller::onLoadButton() {
|
||||
|
||||
// pick a map to load
|
||||
QDir dir = LoadSetupDialog::pickSetupFolder();
|
||||
|
||||
// cancelled?
|
||||
if (dir.path() == ".") { return; }
|
||||
|
||||
QFile fMap(dir.path() + "/map.xml");
|
||||
QFile fGrid(dir.path() + "/grid.dat");
|
||||
|
||||
Assert::isTrue(fMap.exists(), "map.xml missing");
|
||||
//Assert::isTrue(fGrid.exists(), "grid.dat missing");
|
||||
|
||||
fMap.open(QIODevice::ReadOnly);
|
||||
QString str = QString(fMap.readAll());
|
||||
im = Floorplan::Reader::readFromString(str.toStdString());
|
||||
|
||||
|
||||
|
||||
const std::string sGrid = fGrid.fileName().toStdString();
|
||||
std::ifstream inp(sGrid, std::ifstream::binary);
|
||||
//Assert::isTrue(inp.good(), "failed to open grid.dat");
|
||||
|
||||
// create a new, empty grid
|
||||
if (grid) {delete grid; grid = nullptr;}
|
||||
grid = new Grid<MyGridNode>(20);
|
||||
|
||||
// grid.dat empty? -> build one and save it
|
||||
if (!inp.good() || (inp.peek()&&0) || inp.eof()) {
|
||||
buildGridOnce(grid, im, sGrid);
|
||||
} else {
|
||||
grid->read(inp);
|
||||
}
|
||||
|
||||
// create a new navigator
|
||||
if (nav) {delete nav; nav = nullptr;}
|
||||
nav = new NavController(this, grid, im);
|
||||
|
||||
getMapView()->setMap(im);
|
||||
getMapView()->showGridImportance(grid);
|
||||
|
||||
|
||||
}
|
||||
|
||||
void Controller::onDebugButton() {
|
||||
mainWindow->getSensorDataWidget()->setVisible( !mainWindow->getSensorDataWidget()->isVisible() );
|
||||
}
|
||||
|
||||
void Controller::onStartButton() {
|
||||
nav->start();
|
||||
}
|
||||
|
||||
void Controller::onTransparentButton() {
|
||||
mainWindow->getMapView()->toggleRenderMode();
|
||||
}
|
||||
|
||||
void Controller::onCameraButton() {
|
||||
nav->toggleCamera();
|
||||
}
|
||||
50
Controller.h
Normal file
@@ -0,0 +1,50 @@
|
||||
#ifndef CONTROLLER_H
|
||||
#define CONTROLLER_H
|
||||
|
||||
class MainWindow;
|
||||
class MainMenu;
|
||||
class MapView;
|
||||
|
||||
class NavController;
|
||||
|
||||
#include <QObject>
|
||||
template <typename T> class Grid;
|
||||
class MyGridNode;
|
||||
|
||||
namespace Floorplan {
|
||||
class IndoorMap;
|
||||
}
|
||||
|
||||
class Controller : public QObject {
|
||||
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
|
||||
/** ctor */
|
||||
explicit Controller();
|
||||
|
||||
public:
|
||||
|
||||
MapView* getMapView() const;
|
||||
|
||||
private slots:
|
||||
|
||||
void onLoadButton();
|
||||
void onDebugButton();
|
||||
void onStartButton();
|
||||
|
||||
void onTransparentButton();
|
||||
void onCameraButton();
|
||||
|
||||
private:
|
||||
|
||||
MainWindow* mainWindow;
|
||||
|
||||
Grid<MyGridNode>* grid = nullptr;
|
||||
NavController* nav = nullptr;
|
||||
Floorplan::IndoorMap* im = nullptr;
|
||||
|
||||
};
|
||||
|
||||
#endif // CONTROLLER_H
|
||||
29
Settings.h
Normal file
@@ -0,0 +1,29 @@
|
||||
#ifndef SETTINGS_H
|
||||
#define SETTINGS_H
|
||||
|
||||
#include <Indoor/grid/GridPoint.h>
|
||||
|
||||
namespace Settings {
|
||||
|
||||
const int numParticles = 3000;
|
||||
|
||||
const float turnSigma = 3.5;
|
||||
|
||||
const float stepLength = 0.80;
|
||||
const float stepSigma = 0.1;
|
||||
|
||||
const float smartphoneAboveGround = 1.3;
|
||||
|
||||
const float offlineSensorSpeedup = 2.5;
|
||||
|
||||
|
||||
const GridPoint destination = GridPoint(70*100, 35*100, 0*100);
|
||||
|
||||
const float wifiSigma = 9.0;
|
||||
const float wifiTXP = -48;
|
||||
const float wifiEXP = 2.5;
|
||||
const float wifiWAF = -9.0;
|
||||
|
||||
}
|
||||
|
||||
#endif // SETTINGS_H
|
||||
224
main.cpp
@@ -6,6 +6,7 @@
|
||||
#include <QApplication>
|
||||
#include <QMainWindow>
|
||||
#include <QGridLayout>
|
||||
#include <QFile>
|
||||
|
||||
#include <Indoor/math/Interpolator.h>
|
||||
#include <Indoor/grid/factory/v2/Importance.h>
|
||||
@@ -14,7 +15,8 @@
|
||||
#include <Indoor/nav/dijkstra/DijkstraPath.h>
|
||||
|
||||
#include "sensors/SensorFactory.h"
|
||||
#include "map/MapView.h"
|
||||
#include "Controller.h"
|
||||
#include "ui/map/MapView.h"
|
||||
|
||||
#include <iostream>
|
||||
|
||||
@@ -24,29 +26,17 @@
|
||||
#include <Indoor/sensors/radio/WiFiGridEstimator.h>
|
||||
#include <Indoor/sensors/radio/model/WiFiModelLogDist.h>
|
||||
|
||||
class LeListener : public SensorListener<WiFiSensorData>, public SensorListener<AccelerometerData>, public SensorListener<StepData> {
|
||||
|
||||
public:
|
||||
void onSensorData(const WiFiSensorData& data) override {
|
||||
const std::string str = "\n" + data.asString();
|
||||
qDebug(str.c_str());
|
||||
}
|
||||
void onSensorData(const AccelerometerData& data) override {
|
||||
const std::string str = data.asString();
|
||||
qDebug(str.c_str());
|
||||
}
|
||||
void onSensorData(const StepData& data) override {
|
||||
qDebug("STEP!");
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
struct MyNode : public GridPoint, public GridNode, public WiFiGridNode<10> {
|
||||
|
||||
float imp;
|
||||
float navImportance;
|
||||
MyNode() {;}
|
||||
MyNode(const float x_cm, const float y_cm, const float z_cm) : GridPoint(x_cm, y_cm, z_cm) {;}
|
||||
|
||||
public:
|
||||
|
||||
static void staticSerialize(std::ostream& out) {
|
||||
WiFiGridNode::staticSerialize(out);
|
||||
}
|
||||
@@ -57,208 +47,30 @@ struct MyNode : public GridPoint, public GridNode, public WiFiGridNode<10> {
|
||||
|
||||
};
|
||||
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
|
||||
|
||||
int sizeOfNode = sizeof(MyNode);
|
||||
|
||||
std::vector<Point3> points = {
|
||||
Point3(1140,530,1060), Point3(1140,2100,1060), Point3(1140,2880,1060), Point3(1140,4442.21,1060), Point3(1190,4840,1060), Point3(1660,4840,890), Point3(1660,5040,890), Point3(1180,5040,720), Point3(1180,4840,720), Point3(1180,4460,720), Point3(2350,4460,720), Point3(4440,4440,720), Point3(5183.26,4280,720), Point3(5800,4280,550), Point3(6110,4280,380), Point3(7680,4280,380), Point3(7680,3860,190), Point3(7680,3400,0), Point3(7400,3400,0), Point3(7400,4030,0)
|
||||
};
|
||||
std::vector<Point3> path;
|
||||
|
||||
Interpolator<int, Point3> interpol;
|
||||
int ts = 0;
|
||||
Point3 last = points[0];
|
||||
for (Point3 p : points) {
|
||||
const float dist = p.getDistance(last);
|
||||
const float diffMS = (dist / 100.0f) / 1.5f * 1000;
|
||||
ts += diffMS;
|
||||
interpol.add(ts, p);
|
||||
last = p;
|
||||
path.push_back(p / 100.0f);
|
||||
}
|
||||
|
||||
|
||||
|
||||
//QGuiApplication app(argc, argv);
|
||||
QApplication app(argc, argv);
|
||||
|
||||
// OpenGL Setup
|
||||
QSurfaceFormat format;
|
||||
format.setDepthBufferSize(16);
|
||||
QSurfaceFormat::setDefaultFormat(format);
|
||||
Controller ctrl;
|
||||
|
||||
Point3 eye(40,42,1.8);
|
||||
ctrl.getMapView()->setLookEye(eye);
|
||||
ctrl.getMapView()->setLookDir(Point3(-1, 0, -0.1));
|
||||
|
||||
Floorplan::IndoorMap* im = Floorplan::Reader::readFromFile("/mnt/data/workspaces/IndoorMap/maps/SHL21.xml");
|
||||
|
||||
Grid<MyNode> grid(20);
|
||||
GridFactory<MyNode> gf(grid);
|
||||
|
||||
// build
|
||||
//gf.build(im);
|
||||
//Importance::addImportance(grid, 0);
|
||||
//std::ofstream out("/tmp/grid.dat");
|
||||
//grid.write(out); out.close();
|
||||
|
||||
// read
|
||||
std::ifstream inp("/tmp/grid.dat");
|
||||
grid.reset();
|
||||
grid.read(inp);
|
||||
|
||||
// estimate WiFi signal strengths
|
||||
WiFiModelLogDist mdlLogDist(-40.0f, 2.25f);
|
||||
WiFiGridEstimator::estimate(grid, mdlLogDist, im);
|
||||
|
||||
|
||||
|
||||
MapView* map = new MapView();
|
||||
map->setMinimumHeight(200);
|
||||
map->setMinimumWidth(200);
|
||||
map->setMap(im);
|
||||
//map->setPath(path);
|
||||
map->show();
|
||||
|
||||
|
||||
struct DijkstraMapper {
|
||||
Grid<MyNode>& grid;
|
||||
DijkstraMapper(Grid<MyNode>& grid) : grid(grid) {;}
|
||||
int getNumNeighbors(const MyNode& n) const {return grid.getNumNeighbors(n);}
|
||||
const MyNode* getNeighbor(const MyNode& n, const int idx) const {return &grid.getNeighbor(n, idx);}
|
||||
float getWeightBetween(const MyNode& n1, const MyNode& n2) const {return n1.getDistanceInCM(n2) / n2.imp;}
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
struct LeListener : public APIListener {
|
||||
|
||||
Grid<MyNode>& grid;
|
||||
Dijkstra<MyNode>& d;
|
||||
const DijkstraNode<MyNode>* dnEnd;
|
||||
MapView* map;
|
||||
|
||||
Point3 nextPos;
|
||||
Point3 pos1;
|
||||
Point3 pos2;
|
||||
|
||||
LeListener(Grid<MyNode>& grid, Dijkstra<MyNode>& d, const DijkstraNode<MyNode>* dnEnd, MapView* map) : grid(grid), d(d), dnEnd(dnEnd), map(map) {
|
||||
|
||||
|
||||
std::thread t(&LeListener::update, this);
|
||||
t.detach();
|
||||
|
||||
}
|
||||
|
||||
/** the currently estimated path to the target has changed */
|
||||
virtual void onPathUpdate(const std::vector<Point3>& curPath) override {
|
||||
|
||||
}
|
||||
|
||||
/** the currently estimated position has changed */
|
||||
virtual void onPositionUpdate(const Point3 pos) override {
|
||||
|
||||
nextPos = pos;
|
||||
|
||||
// update the path to the target
|
||||
const GridPoint xxx(pos.x, pos.y, pos.z);
|
||||
const DijkstraNode<MyNode>* dnStart = d.getNode( grid.getNearestNode(xxx) );
|
||||
const DijkstraPath<MyNode> dp(dnStart, dnEnd);
|
||||
map->setPath(dp);
|
||||
|
||||
}
|
||||
|
||||
void update() {
|
||||
|
||||
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(700));
|
||||
|
||||
const int transMS = 500;
|
||||
const int updateMS = 75;
|
||||
const float factor1 = ((float) updateMS / (float) transMS) * 0.7;
|
||||
const float factor2 = factor1 * 0.4f;
|
||||
const Point3 human(0, 0, 180);
|
||||
|
||||
while(true) {
|
||||
|
||||
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(updateMS));
|
||||
|
||||
// Point3 diff = (nextPos - pos1);
|
||||
// if (diff.length() > 30) {diff = diff.normalized() * 30;} else {diff *= factor1;}
|
||||
// pos1 += diff;
|
||||
// pos2 += diff*0.5;
|
||||
|
||||
|
||||
pos1 = pos1 * (1-factor1) + nextPos * (factor1); // fast update
|
||||
pos2 = pos2 * (1-factor2) + nextPos * (factor2); // slow update
|
||||
const Point3 dir = pos2 - pos1;
|
||||
|
||||
map->setLookAt((pos1+human) / 100.0f, (dir) / 100.0f);
|
||||
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
DummyAPI api("/mnt/data/workspaces/navindoor");
|
||||
api.setTarget(4);
|
||||
|
||||
|
||||
Dijkstra<MyNode> d;
|
||||
//GridPoint end(points.front().x, points.front().y, points.front().z);
|
||||
GridPoint end(api.getDst().x, api.getDst().y, api.getDst().z);
|
||||
d.build(&grid.getNearestNode(end), DijkstraMapper(grid));
|
||||
const DijkstraNode<MyNode>* dnEnd = d.getNode(grid.getNearestNode(end));
|
||||
|
||||
api.addListener(new LeListener(grid, d, dnEnd, map));
|
||||
api.setSpeed(2);
|
||||
api.startNavigation();
|
||||
|
||||
// auto run = [&] () {
|
||||
// //int ts = 0;
|
||||
// int ts = 97000;
|
||||
// while(ts < interpol.getMaxKey() && ts >= 0) {
|
||||
// std::this_thread::sleep_for(std::chrono::milliseconds(50));
|
||||
// //ts += 50;
|
||||
// ts -= 150;
|
||||
// const Point3 human(0, 0, 180);
|
||||
//// const Point3 pos0 = interpol.get(ts-500);
|
||||
//// const Point3 pos1 = interpol.get(ts+500);
|
||||
// const Point3 pos = interpol.get(ts);
|
||||
//// //const Point3 dir = Point3(-50000, -50000, 50000);//pos0 - pos;
|
||||
//// Point3 dir = pos1 - pos0; dir.z /= 2; // only slight down/up looking
|
||||
//// map->setLookAt((pos+human) / 100.0f, (dir) / 100.0f);
|
||||
|
||||
// GridPoint cur(pos.x, pos.y, pos.z);
|
||||
// const DijkstraNode<MyNode>* dnStart = d.getNode( grid.getNearestNode(cur) );
|
||||
// DijkstraPath<MyNode> dp(dnStart, dnEnd);
|
||||
// map->setPath(dp);
|
||||
|
||||
|
||||
//// Point3 next =
|
||||
//// dp.getFromStart(2).element->inCentimeter() +
|
||||
//// dp.getFromStart(4).element->inCentimeter() +
|
||||
//// dp.getFromStart(6).element->inCentimeter();
|
||||
//// next /= 3;
|
||||
//// const Point3 dir = pos - next ;
|
||||
// static Point3 lastPos;
|
||||
// lastPos = lastPos * 0.85 + pos * 0.15;
|
||||
|
||||
// const Point3 dir = lastPos - pos ;
|
||||
// map->setLookAt((pos+human) / 100.0f, (dir) / 100.0f);
|
||||
|
||||
// static float r = 0;
|
||||
// while(true) {
|
||||
// r += 0.01;
|
||||
// eye += Point3(-0.01, 0, 0);
|
||||
// ctrl.getMapView()->setLookEye(eye);
|
||||
// usleep(1000*50);
|
||||
// }
|
||||
// };
|
||||
|
||||
// std::thread t(run);
|
||||
|
||||
|
||||
// QQmlApplicationEngine engine;
|
||||
// engine.load(QUrl(QStringLiteral("qrc:/main.qml")));
|
||||
|
||||
return app.exec();
|
||||
|
||||
}
|
||||
|
||||
132
map/MapView.cpp
@@ -1,132 +0,0 @@
|
||||
#include "MapView.h"
|
||||
|
||||
#include <QGLShaderProgram>
|
||||
|
||||
#include "elements/Walls.h"
|
||||
#include "elements/Ground.h"
|
||||
#include "elements/Handrails.h"
|
||||
#include "elements/Stairs.h"
|
||||
#include "elements/Doors.h"
|
||||
#include "elements/Path.h"
|
||||
|
||||
// http://doc.qt.io/qt-5/qtopengl-cube-example.html
|
||||
|
||||
MapView::MapView(QWidget* parent) : QOpenGLWidget(parent) {
|
||||
|
||||
|
||||
};
|
||||
|
||||
void MapView::setMap(Floorplan::IndoorMap* map) {
|
||||
|
||||
for (Floorplan::Floor* floor : map->floors) {
|
||||
elements.push_back(new Ground(floor));
|
||||
elements.push_back(new Walls(floor));
|
||||
elements.push_back(new Handrails(floor));
|
||||
elements.push_back(new Stairs(floor));
|
||||
elements.push_back(new Doors(floor));
|
||||
}
|
||||
|
||||
this->path = new Path();
|
||||
elements.push_back(this->path);
|
||||
|
||||
}
|
||||
|
||||
void MapView::setPath(const std::vector<Point3>& path) {
|
||||
this->path->set(path);
|
||||
}
|
||||
|
||||
|
||||
void MapView::timerEvent(QTimerEvent *) {
|
||||
update();
|
||||
}
|
||||
|
||||
void MapView::initializeGL() {
|
||||
|
||||
initializeOpenGLFunctions();
|
||||
|
||||
glEnable(GL_DEPTH_TEST);
|
||||
glEnable(GL_CULL_FACE);
|
||||
|
||||
|
||||
|
||||
for (Renderable* r : elements) {
|
||||
r->initGL();
|
||||
}
|
||||
|
||||
timer.start(60, this);
|
||||
|
||||
}
|
||||
|
||||
void MapView::paintGL() {
|
||||
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
|
||||
draw();
|
||||
}
|
||||
|
||||
void MapView::resizeGL(int w, int h) {
|
||||
|
||||
// Calculate aspect ratio
|
||||
qreal aspect = qreal(w) / qreal(h ? h : 1);
|
||||
|
||||
// viewing frustrum [0:50] meter
|
||||
const qreal zNear = 0.02, zFar = 50, fov = 50.0;
|
||||
|
||||
// Reset projection
|
||||
matProject.setToIdentity();
|
||||
matProject.scale(-1, 1, 1);
|
||||
glCullFace(GL_FRONT);
|
||||
//matProject.scale(0.05, 0.05, 0.05);
|
||||
matProject.perspective(fov, aspect, zNear, zFar);
|
||||
//matProject.scale(-0.01, 0.01, 0.01);
|
||||
|
||||
}
|
||||
|
||||
void MapView::setLookAt(const Point3 pos_m, const Point3 dir) {
|
||||
QVector3D qDir(dir.x, dir.z, dir.y);
|
||||
QVector3D lookAt = QVector3D(pos_m.x, pos_m.z, pos_m.y);
|
||||
QVector3D eye = lookAt + qDir * 0.1;
|
||||
QVector3D up = QVector3D(0,1,0);
|
||||
matView.setToIdentity();
|
||||
//matView.scale(0.01, 0.01, 0.01);
|
||||
matView.lookAt(eye, lookAt, up);
|
||||
//matView.scale(0.99, 1, 1);
|
||||
//matView.translate(0.7, 0, 0);
|
||||
lightPos = eye + QVector3D(0.0, 4.0, 0.0);
|
||||
eyePos = eye;
|
||||
}
|
||||
|
||||
void MapView::draw() {
|
||||
|
||||
// clear everything
|
||||
glClearColor(0,0,0,1);
|
||||
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
|
||||
|
||||
//static float angularSpeed = 0;
|
||||
//angularSpeed += 1.5;
|
||||
|
||||
//texture->bind();
|
||||
//QVector3D rotationAxis(1,1,1);
|
||||
//QQuaternion rotation = QQuaternion::fromAxisAndAngle(rotationAxis, angularSpeed);
|
||||
|
||||
// Calculate model view transformation
|
||||
QMatrix4x4 matModel;
|
||||
//matModel.setToIdentity();
|
||||
//matModel.translate(0.0, 0.0, 0.0);
|
||||
//matModel.rotate(rotation);
|
||||
|
||||
for (Renderable* r : elements) {
|
||||
|
||||
QOpenGLShaderProgram& program = r->getProgram();
|
||||
program.bind();
|
||||
|
||||
// set the matrices
|
||||
program.setUniformValue("m_matrix", matModel);
|
||||
program.setUniformValue("mv_matrix", matView * matModel);
|
||||
program.setUniformValue("mvp_matrix", matProject * matView * matModel);
|
||||
program.setUniformValue("lightWorldPos", lightPos);
|
||||
program.setUniformValue("eyeWorldPos", eyePos);
|
||||
|
||||
r->render();
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
@@ -1,76 +0,0 @@
|
||||
#ifndef MAPVIEW_H
|
||||
#define MAPVIEW_H
|
||||
|
||||
#include <QOpenGLWidget>
|
||||
#include <QOpenGLFunctions>
|
||||
#include <QOpenGLShaderProgram>
|
||||
#include <QBasicTimer>
|
||||
|
||||
#include <Indoor/geo/Point3.h>
|
||||
#include <Indoor/nav/dijkstra/DijkstraPath.h>
|
||||
|
||||
#include "elements/Path.h"
|
||||
|
||||
namespace Floorplan {
|
||||
class IndoorMap;
|
||||
}
|
||||
|
||||
class Renderable;
|
||||
class Path;
|
||||
|
||||
|
||||
class MapView : public QOpenGLWidget, protected QOpenGLFunctions {
|
||||
|
||||
private:
|
||||
|
||||
QMatrix4x4 matProject;
|
||||
QMatrix4x4 matView;
|
||||
|
||||
QVector3D lightPos;
|
||||
QVector3D eyePos;
|
||||
|
||||
|
||||
QBasicTimer timer;
|
||||
|
||||
std::vector<Renderable*> elements;
|
||||
Path* path;
|
||||
|
||||
|
||||
|
||||
public:
|
||||
|
||||
MapView(QWidget* parent = 0);
|
||||
|
||||
/** set the map to display */
|
||||
void setMap(Floorplan::IndoorMap* map);
|
||||
|
||||
/** the position to look at */
|
||||
void setLookAt(const Point3 pos, const Point3 dir = Point3(-1, -1, 0.1));
|
||||
|
||||
|
||||
/** set the path to disply */
|
||||
void setPath(const std::vector<Point3>& path);
|
||||
|
||||
/** set the path to disply */
|
||||
template <typename Node> void setPath(const DijkstraPath<Node>& path) {
|
||||
this->path->set(path);
|
||||
}
|
||||
|
||||
|
||||
protected:
|
||||
|
||||
void timerEvent(QTimerEvent *e) Q_DECL_OVERRIDE;
|
||||
|
||||
void initializeGL();
|
||||
|
||||
void paintGL();
|
||||
|
||||
void resizeGL(int width, int height);
|
||||
|
||||
private:
|
||||
|
||||
void draw();
|
||||
|
||||
};
|
||||
|
||||
#endif // MAPVIEW_H
|
||||
@@ -1,40 +0,0 @@
|
||||
#ifndef RENDERABLE_H
|
||||
#define RENDERABLE_H
|
||||
|
||||
#include <QOpenGLShaderProgram>
|
||||
|
||||
class Renderable {
|
||||
|
||||
protected:
|
||||
|
||||
QOpenGLShaderProgram program;
|
||||
|
||||
public:
|
||||
|
||||
/** get the renderable's shader */
|
||||
QOpenGLShaderProgram& getProgram() {return program;}
|
||||
|
||||
/** render the renderable */
|
||||
void render() {
|
||||
program.bind();
|
||||
_render();
|
||||
}
|
||||
|
||||
|
||||
virtual void initGL() = 0;
|
||||
|
||||
virtual void _render() = 0;
|
||||
|
||||
protected:
|
||||
|
||||
/** helper method to build the shader */
|
||||
void loadShader(const QString& vertex, const QString& fragment) {
|
||||
if (!program.addShaderFromSourceFile(QOpenGLShader::Vertex, vertex)) {throw "1";}
|
||||
if (!program.addShaderFromSourceFile(QOpenGLShader::Fragment, fragment)) {throw "2";}
|
||||
if (!program.link()) {throw "3";}
|
||||
if (!program.bind()) {throw "4";}
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // RENDERABLE_H
|
||||
@@ -13,36 +13,36 @@ namespace std {
|
||||
|
||||
//}
|
||||
|
||||
template <typename T> string to_string(const T val) {
|
||||
template <typename T> inline string to_string(const T val) {
|
||||
stringstream ss;
|
||||
ss << val;
|
||||
return ss.str();
|
||||
}
|
||||
|
||||
template <typename T> T round(const T val) {
|
||||
template <typename T> inline T round(const T val) {
|
||||
return ::round(val);
|
||||
}
|
||||
|
||||
// http://stackoverflow.com/questions/19478687/no-member-named-stoi-in-namespace-std
|
||||
int stoi(const std::string& str) {
|
||||
inline int stoi(const std::string& str) {
|
||||
std::istringstream is(str);
|
||||
int val; is >> val; return val;
|
||||
}
|
||||
|
||||
// analog zu oben
|
||||
float stof(const std::string& str) {
|
||||
inline float stof(const std::string& str) {
|
||||
std::istringstream is(str);
|
||||
float val; is >> val; return val;
|
||||
}
|
||||
|
||||
// analog zu oben
|
||||
double stod(const std::string& str) {
|
||||
inline double stod(const std::string& str) {
|
||||
std::istringstream is(str);
|
||||
double val; is >> val; return val;
|
||||
}
|
||||
|
||||
// analog zu oben
|
||||
uint64_t stol(const std::string& str) {
|
||||
inline uint64_t stol(const std::string& str) {
|
||||
std::istringstream is(str);
|
||||
uint64_t val; is >> val; return val;
|
||||
}
|
||||
|
||||
149
nav/Filter.h
Normal file
@@ -0,0 +1,149 @@
|
||||
#ifndef FILTER_H
|
||||
#define FILTER_H
|
||||
|
||||
#include <KLib/math/filter/particles/ParticleFilter.h>
|
||||
|
||||
#include <KLib/math/filter/particles/estimation/ParticleFilterEstimationWeightedAverage.h>
|
||||
#include <KLib/math/filter/particles/estimation/ParticleFilterEstimationOrderedWeightedAverage.h>
|
||||
|
||||
#include <KLib/math/filter/particles/resampling/ParticleFilterResamplingSimple.h>
|
||||
#include <KLib/math/filter/particles/resampling/ParticleFilterResamplingPercent.h>
|
||||
|
||||
#include <Indoor/sensors/radio/WiFiProbabilityFree.h>
|
||||
#include <Indoor/sensors/radio/model/WiFiModelLogDistCeiling.h>
|
||||
#include <Indoor/sensors/radio/WiFiProbabilityFree.h>
|
||||
|
||||
#include <Indoor/grid/walk/v2/modules/WalkModuleHeadingControl.h>
|
||||
#include <Indoor/grid/walk/v2/modules/WalkModuleNodeImportance.h>
|
||||
#include <Indoor/grid/walk/v2/modules/WalkModuleFavorZ.h>
|
||||
#include <Indoor/grid/walk/v2/modules/WalkModuleButterActivity.h>
|
||||
#include <Indoor/grid/walk/v2/modules/WalkModuleFollowDestination.h>
|
||||
|
||||
#include "State.h"
|
||||
#include "Node.h"
|
||||
|
||||
#include "../Settings.h"
|
||||
|
||||
class PFInit : public K::ParticleFilterInitializer<MyState> {
|
||||
|
||||
private:
|
||||
|
||||
Grid<MyGridNode>* grid;
|
||||
|
||||
public:
|
||||
|
||||
PFInit(Grid<MyGridNode>* grid) : grid(grid) {
|
||||
|
||||
}
|
||||
|
||||
virtual void initialize(std::vector<K::Particle<MyState>>& particles) override {
|
||||
|
||||
std::minstd_rand gen;
|
||||
std::uniform_int_distribution<int> distIdx(0, grid->getNumNodes()-1);
|
||||
std::uniform_real_distribution<float> distHead(0, 2*M_PI);
|
||||
|
||||
for (K::Particle<MyState>& 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
|
||||
}
|
||||
|
||||
// // fix position + heading
|
||||
// for (K::Particle<MyState>& p : particles) {
|
||||
// const int idx = 9000;
|
||||
// const MyGridNode& node = (*grid)[idx];
|
||||
// p.state.position = node;
|
||||
// p.state.heading.direction = Heading(0);
|
||||
// }
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
class PFTrans : public K::ParticleFilterTransition<MyState, MyControl> {
|
||||
|
||||
public:
|
||||
|
||||
Grid<MyGridNode>* grid;
|
||||
GridWalker<MyGridNode, MyState> walker;
|
||||
|
||||
WalkModuleFavorZ<MyGridNode, MyState> modFavorZ;
|
||||
WalkModuleHeadingControl<MyGridNode, MyState, MyControl> modHeading;
|
||||
WalkModuleNodeImportance<MyGridNode, MyState> modImportance;
|
||||
WalkModuleButterActivity<MyGridNode, MyState> modBarometer;
|
||||
WalkModuleFollowDestination<MyGridNode, MyState> modDestination;
|
||||
|
||||
std::minstd_rand gen;
|
||||
|
||||
public:
|
||||
|
||||
PFTrans(Grid<MyGridNode>* grid, MyControl* ctrl) : grid(grid), modHeading(ctrl, Settings::turnSigma), modDestination(*grid) {
|
||||
|
||||
walker.addModule(&modFavorZ);
|
||||
walker.addModule(&modHeading);
|
||||
walker.addModule(&modImportance);
|
||||
walker.addModule(&modBarometer);
|
||||
walker.addModule(&modDestination);
|
||||
|
||||
if (Settings::destination != GridPoint(0,0,0)) {
|
||||
modDestination.setDestination(grid->getNodeFor(Settings::destination));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
void transition(std::vector<K::Particle<MyState>>& particles, const MyControl* control) override {
|
||||
|
||||
std::normal_distribution<float> noise(0, Settings::stepSigma);
|
||||
|
||||
for (K::Particle<MyState>& p : particles) {
|
||||
const float dist_m = std::abs(control->numStepsSinceLastTransition * Settings::stepLength + noise(gen));
|
||||
p.state = walker.getDestination(*grid, p.state, dist_m);
|
||||
}
|
||||
|
||||
((MyControl*)control)->resetAfterTransition();
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
class PFEval : public K::ParticleFilterEvaluation<MyState, MyObservation> {
|
||||
|
||||
WiFiModelLogDistCeiling& wifiModel;
|
||||
WiFiObserverFree wiFiProbability;
|
||||
|
||||
public:
|
||||
|
||||
PFEval(WiFiModelLogDistCeiling& wifiModel) : wifiModel(wifiModel), wiFiProbability(Settings::wifiSigma, wifiModel) {
|
||||
|
||||
}
|
||||
|
||||
double evaluation(std::vector<K::Particle<MyState>>& particles, const MyObservation& _observation) override {
|
||||
|
||||
double sum = 0;
|
||||
|
||||
// smartphone is 1.3 meter above ground
|
||||
const Point3 person(0,0,Settings::smartphoneAboveGround);
|
||||
|
||||
// local copy!! observation might be changed async outside!! (will really produces crashes!)
|
||||
const MyObservation observation = _observation;
|
||||
|
||||
for (K::Particle<MyState>& p : particles) {
|
||||
const double pWiFi = wiFiProbability.getProbability(p.state.position.inMeter()+person, observation.currentTime, observation.wifi);
|
||||
const double pGPS = 1;
|
||||
const double prob = pWiFi * pGPS;
|
||||
p.weight = prob;
|
||||
sum += prob;
|
||||
}
|
||||
|
||||
return sum;
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
#endif // FILTER_H
|
||||
299
nav/NavController.h
Normal file
@@ -0,0 +1,299 @@
|
||||
#ifndef NAVCONTROLLER_H
|
||||
#define NAVCONTROLLER_H
|
||||
|
||||
#include "../sensors/AccelerometerSensor.h"
|
||||
#include "../sensors/GyroscopeSensor.h"
|
||||
#include "../sensors/BarometerSensor.h"
|
||||
#include "../sensors/WiFiSensor.h"
|
||||
#include "../sensors/SensorFactory.h"
|
||||
#include "../sensors/StepSensor.h"
|
||||
#include "../sensors/TurnSensor.h"
|
||||
|
||||
#include "../ui/debug/SensorDataWidget.h"
|
||||
#include "../ui/map/MapView.h"
|
||||
|
||||
#include <Indoor/Assertions.h>
|
||||
#include <thread>
|
||||
|
||||
#include "State.h"
|
||||
#include "Filter.h"
|
||||
#include "Controller.h"
|
||||
|
||||
#include <KLib/misc/gnuplot/Gnuplot.h>
|
||||
#include <KLib/misc/gnuplot/GnuplotSplot.h>
|
||||
#include <KLib/misc/gnuplot/GnuplotSplotElementPoints.h>
|
||||
#include <KLib/misc/gnuplot/GnuplotSplotElementLines.h>
|
||||
|
||||
#include "Settings.h"
|
||||
#include "RegionalResampling.h"
|
||||
|
||||
Q_DECLARE_METATYPE(const void*)
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
class NavController :
|
||||
public SensorListener<AccelerometerData>,
|
||||
public SensorListener<GyroscopeData>,
|
||||
public SensorListener<BarometerData>,
|
||||
public SensorListener<WiFiMeasurements>,
|
||||
public SensorListener<GPSData>,
|
||||
public SensorListener<StepData>,
|
||||
public SensorListener<TurnData> {
|
||||
|
||||
private:
|
||||
|
||||
Controller* mainController;
|
||||
Grid<MyGridNode>* grid;
|
||||
WiFiModelLogDistCeiling wifiModel;
|
||||
Floorplan::IndoorMap* im;
|
||||
|
||||
MyObservation curObs;
|
||||
MyControl curCtrl;
|
||||
|
||||
bool running = false;
|
||||
std::thread tUpdate;
|
||||
std::thread tDisplay;
|
||||
|
||||
std::unique_ptr<K::ParticleFilter<MyState, MyControl, MyObservation>> pf;
|
||||
|
||||
public:
|
||||
|
||||
virtual ~NavController() {
|
||||
if (running) {stop();}
|
||||
}
|
||||
|
||||
NavController(Controller* mainController, Grid<MyGridNode>* grid, Floorplan::IndoorMap* im) : mainController(mainController), grid(grid), wifiModel(im), im(im) {
|
||||
|
||||
wifiModel.loadAPs(im, Settings::wifiTXP, Settings::wifiEXP, Settings::wifiWAF);
|
||||
|
||||
SensorFactory::get().getAccelerometer().addListener(this);
|
||||
SensorFactory::get().getGyroscope().addListener(this);
|
||||
SensorFactory::get().getBarometer().addListener(this);
|
||||
SensorFactory::get().getWiFi().addListener(this);
|
||||
SensorFactory::get().getSteps().addListener(this);
|
||||
SensorFactory::get().getTurns().addListener(this);
|
||||
|
||||
std::unique_ptr<K::ParticleFilterInitializer<MyState>> init(new PFInit(grid));
|
||||
|
||||
//std::unique_ptr<K::ParticleFilterEstimationWeightedAverage<MyState>> estimation(new K::ParticleFilterEstimationWeightedAverage<MyState>());
|
||||
std::unique_ptr<K::ParticleFilterEstimationOrderedWeightedAverage<MyState>> estimation(new K::ParticleFilterEstimationOrderedWeightedAverage<MyState>(0.1));
|
||||
|
||||
//std::unique_ptr<K::ParticleFilterResamplingSimple<MyState>> resample(new K::ParticleFilterResamplingSimple<MyState>());
|
||||
//std::unique_ptr<K::ParticleFilterResamplingPercent<MyState>> resample(new K::ParticleFilterResamplingPercent<MyState>(0.10));
|
||||
std::unique_ptr<RegionalResampling> resample(new RegionalResampling());
|
||||
|
||||
|
||||
std::unique_ptr<K::ParticleFilterEvaluation<MyState, MyObservation>> eval(new PFEval(wifiModel));
|
||||
std::unique_ptr<K::ParticleFilterTransition<MyState, MyControl>> transition(new PFTrans(grid, &curCtrl));
|
||||
|
||||
pf = std::unique_ptr<K::ParticleFilter<MyState, MyControl, MyObservation>>(new K::ParticleFilter<MyState, MyControl, MyObservation>(Settings::numParticles, std::move(init)));
|
||||
pf->setTransition(std::move(transition));
|
||||
pf->setEvaluation(std::move(eval));
|
||||
pf->setEstimation(std::move(estimation));
|
||||
pf->setResampling(std::move(resample));
|
||||
|
||||
pf->setNEffThreshold(1.0);
|
||||
|
||||
}
|
||||
|
||||
void start() {
|
||||
Assert::isFalse(running, "already started!");
|
||||
running = true;
|
||||
tUpdate = std::thread(&NavController::update, this);
|
||||
tDisplay = std::thread(&NavController::display, this);
|
||||
}
|
||||
|
||||
void stop() {
|
||||
Assert::isTrue(running, "not started!");
|
||||
running = false;
|
||||
tUpdate.join();
|
||||
tDisplay.join();
|
||||
}
|
||||
|
||||
void onSensorData(Sensor<AccelerometerData>* sensor, const Timestamp ts, const AccelerometerData& data) override {
|
||||
(void) sensor;
|
||||
curObs.currentTime = ts;
|
||||
}
|
||||
|
||||
void onSensorData(Sensor<GyroscopeData>* sensor, const Timestamp ts, const GyroscopeData& data) override {
|
||||
(void) sensor;
|
||||
curObs.currentTime = ts;
|
||||
}
|
||||
|
||||
void onSensorData(Sensor<BarometerData>* sensor, const Timestamp ts, const BarometerData& data) override {
|
||||
(void) sensor;
|
||||
curObs.currentTime = ts;
|
||||
}
|
||||
|
||||
void onSensorData(Sensor<WiFiMeasurements>* sensor, const Timestamp ts, const WiFiMeasurements& data) override {
|
||||
(void) sensor;
|
||||
(void) ts;
|
||||
curObs.currentTime = ts;
|
||||
curObs.wifi = data;
|
||||
}
|
||||
|
||||
void onSensorData(Sensor<GPSData>* sensor, const Timestamp ts, const GPSData& data) override {
|
||||
(void) sensor;
|
||||
(void) ts;
|
||||
curObs.currentTime = ts;
|
||||
curObs.gps = data;
|
||||
}
|
||||
|
||||
void onSensorData(Sensor<StepData>* sensor, const Timestamp ts, const StepData& data) override {
|
||||
(void) sensor;
|
||||
(void) ts;
|
||||
curObs.currentTime = ts;
|
||||
curCtrl.numStepsSinceLastTransition += data.stepsSinceLastEvent; // set to zero after each transition
|
||||
}
|
||||
|
||||
void onSensorData(Sensor<TurnData>* sensor, const Timestamp ts, const TurnData& data) override {
|
||||
(void) sensor;
|
||||
(void) ts;
|
||||
curObs.currentTime = ts;
|
||||
curCtrl.turnSinceLastTransition_rad += data.radSinceLastEvent; // set to zero after each transition
|
||||
}
|
||||
|
||||
int cameraMode = 0;
|
||||
void toggleCamera() {
|
||||
cameraMode = (cameraMode + 1) % 3;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
/** particle-filter update loop */
|
||||
void update() {
|
||||
|
||||
Timestamp lastTransition;
|
||||
|
||||
while(running) {
|
||||
|
||||
// // fixed update rate based on the systems time -> LIVE! even for offline data
|
||||
// const Timestamp ts1 = Timestamp::fromUnixTime();
|
||||
// doUpdate();
|
||||
// const Timestamp ts2 = Timestamp::fromUnixTime();
|
||||
// const Timestamp needed = ts2-ts1;
|
||||
// const Timestamp sleep = Timestamp::fromMS(500) - needed;
|
||||
// std::this_thread::sleep_for(std::chrono::milliseconds(sleep.ms()));
|
||||
|
||||
// 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 > Timestamp::fromMS(500)) {
|
||||
doUpdate();
|
||||
lastTransition = curObs.currentTime;
|
||||
} else {
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(10));
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
MyState curEst;
|
||||
//MyState lastEst;
|
||||
|
||||
void doUpdate() {
|
||||
|
||||
//lastEst = curEst;
|
||||
curEst = pf->update(&curCtrl, curObs);
|
||||
|
||||
// hacky.. but we need to call this one from the main thread!
|
||||
//mainController->getMapView()->showParticles(pf->getParticles());
|
||||
qRegisterMetaType<const void*>();
|
||||
Assert::isTrue(QMetaObject::invokeMethod(mainController->getMapView(), "showParticles", Qt::QueuedConnection, Q_ARG(const void*, &pf->getParticles())), "call failed");
|
||||
|
||||
|
||||
PFTrans* trans = (PFTrans*)pf->getTransition();
|
||||
const MyGridNode* node = grid->getNodePtrFor(curEst.position);
|
||||
if (node) {
|
||||
const DijkstraPath<MyGridNode> path = trans->modDestination.getShortestPath(*node);
|
||||
// mainController->getMapView()->showGridImportance();
|
||||
Assert::isTrue(QMetaObject::invokeMethod(mainController->getMapView(), "setPath", Qt::QueuedConnection, Q_ARG(const void*, &path)), "call failed");
|
||||
}
|
||||
|
||||
/*
|
||||
static K::Gnuplot gp;
|
||||
K::GnuplotSplot plot;
|
||||
K::GnuplotSplotElementLines lines; plot.add(&lines);
|
||||
K::GnuplotSplotElementPoints points; plot.add(&points);
|
||||
K::GnuplotSplotElementPoints best; plot.add(&best); best.setPointSize(2); best.setColorHex("#0000ff");
|
||||
|
||||
for (const K::Particle<MyState>& p : pf->getParticles()) {
|
||||
const Point3 pos = p.state.position.inMeter();
|
||||
points.add(K::GnuplotPoint3(pos.x, pos.y, pos.z));
|
||||
}
|
||||
|
||||
for (const Floorplan::Floor* f : im->floors) {
|
||||
for (const Floorplan::FloorOutlinePolygon* polygon : f->outline) {
|
||||
for (int i = 0; i < polygon->poly.points.size(); ++i) {
|
||||
const Point2 p1 = polygon->poly.points[i];
|
||||
const Point2 p2 = polygon->poly.points[(i+1)%polygon->poly.points.size()];
|
||||
K::GnuplotPoint3 gp1(p1.x, p1.y, f->atHeight);
|
||||
K::GnuplotPoint3 gp2(p2.x, p2.y, f->atHeight);
|
||||
lines.addSegment(gp1, gp2);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
K::GnuplotPoint3 gpBest(curEst.position.x_cm/100.0f, curEst.position.y_cm/100.0f, curEst.position.z_cm/100.0f);
|
||||
best.add(gpBest);
|
||||
|
||||
gp.draw(plot);
|
||||
gp.flush();
|
||||
*/
|
||||
|
||||
|
||||
}
|
||||
|
||||
const int display_ms = 50;
|
||||
|
||||
/** UI update loop */
|
||||
void display() {
|
||||
while(running) {
|
||||
doDisplay();
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(display_ms));
|
||||
}
|
||||
}
|
||||
|
||||
Point3 curPosFast;
|
||||
Point3 curPosSlow;
|
||||
|
||||
|
||||
|
||||
void doDisplay() {
|
||||
|
||||
const float kappa1 = display_ms / 1000.0f;
|
||||
const float kappa2 = kappa1 * 0.7;
|
||||
|
||||
const float myHeight_m = 1.80;
|
||||
|
||||
curPosFast = curPosFast * (1-kappa1) + curEst.position.inMeter() * (kappa1);
|
||||
curPosSlow = curPosSlow * (1-kappa2) + curEst.position.inMeter() * (kappa2);
|
||||
|
||||
const Point3 dir = (curPosFast - curPosSlow).normalized();
|
||||
const Point3 dir2 = Point3(dir.x, dir.y, -0.2).normalized();
|
||||
|
||||
if (cameraMode == 0) {
|
||||
mainController->getMapView()->setLookAt(curPosFast + Point3(0,0,myHeight_m), dir);
|
||||
} else if (cameraMode == 1) {
|
||||
mainController->getMapView()->setLookAt(curPosFast + Point3(0,0,myHeight_m) - dir2*4, dir2);
|
||||
} else if (cameraMode == 2) {
|
||||
const Point3 spectator = curPosFast + Point3(0,0,20) - dir*15;
|
||||
const Point3 spectatorDir = (curPosFast - spectator).normalized();
|
||||
mainController->getMapView()->setLookEye(spectator);
|
||||
mainController->getMapView()->setLookDir(spectatorDir);
|
||||
}
|
||||
|
||||
mainController->getMapView()->setCurrentEstimation(curPosFast, dir);
|
||||
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // NAVCONTROLLER_H
|
||||
29
nav/Node.h
Normal file
@@ -0,0 +1,29 @@
|
||||
#ifndef NODE_H
|
||||
#define NODE_H
|
||||
|
||||
#include <Indoor/grid/Grid.h>
|
||||
#include <Indoor/sensors/radio/WiFiGridNode.h>
|
||||
|
||||
struct MyGridNode : public GridNode, public GridPoint {//, public WiFiGridNode<10> {
|
||||
|
||||
float navImportance;
|
||||
float getNavImportance() const { return navImportance; }
|
||||
|
||||
/** 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);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // NODE_H
|
||||
68
nav/RegionalResampling.h
Normal file
@@ -0,0 +1,68 @@
|
||||
#ifndef REGIONALRESAMPLING_H
|
||||
#define REGIONALRESAMPLING_H
|
||||
|
||||
#include <KLib/math/filter/particles/ParticleFilter.h>
|
||||
#include "State.h"
|
||||
|
||||
class RegionalResampling : public K::ParticleFilterResampling<MyState> {
|
||||
|
||||
public:
|
||||
|
||||
float maxDist = 12.5;
|
||||
|
||||
RegionalResampling() {;}
|
||||
|
||||
void resample(std::vector<K::Particle<MyState>>& particles) override {
|
||||
|
||||
Point3 sum;
|
||||
for (const K::Particle<MyState>& p : particles) {
|
||||
sum += p.state.position.inMeter();
|
||||
}
|
||||
const Point3 avg = sum / particles.size();
|
||||
|
||||
std::vector<K::Particle<MyState>> next;
|
||||
for (const K::Particle<MyState>& p : particles) {
|
||||
const float dist = p.state.position.inMeter().getDistance(avg);
|
||||
if (rand() % 6 != 0) {continue;}
|
||||
if (dist < maxDist) {next.push_back(p);}
|
||||
}
|
||||
|
||||
// cumulate
|
||||
std::vector<K::Particle<MyState>> copy = particles;
|
||||
double cumWeight = 0;
|
||||
for ( K::Particle<MyState>& p : copy) {
|
||||
cumWeight += p.weight;
|
||||
p.weight = cumWeight;
|
||||
}
|
||||
|
||||
// draw missing particles
|
||||
const int missing = particles.size() - next.size();
|
||||
for (int i = 0; i < missing; ++i) {
|
||||
next.push_back(draw(copy, cumWeight));
|
||||
}
|
||||
|
||||
std::swap(next, particles);
|
||||
|
||||
}
|
||||
|
||||
std::minstd_rand gen;
|
||||
|
||||
/** draw one particle according to its weight from the copy vector */
|
||||
const K::Particle<MyState>& draw(std::vector<K::Particle<MyState>>& copy, const double cumWeight) {
|
||||
|
||||
// generate random values between [0:cumWeight]
|
||||
std::uniform_real_distribution<float> dist(0, cumWeight);
|
||||
|
||||
// draw a random value between [0:cumWeight]
|
||||
const float rand = dist(gen);
|
||||
|
||||
// search comparator (cumWeight is ordered -> use binary search)
|
||||
auto comp = [] (const K::Particle<MyState>& s, const float d) {return s.weight < d;};
|
||||
auto it = std::lower_bound(copy.begin(), copy.end(), rand, comp);
|
||||
return *it;
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // REGIONALRESAMPLING_H
|
||||
77
nav/State.h
Normal file
@@ -0,0 +1,77 @@
|
||||
#ifndef STATE_H
|
||||
#define STATE_H
|
||||
|
||||
#include <Indoor/grid/walk/v2/GridWalker.h>
|
||||
#include <Indoor/grid/walk/v2/modules/WalkModuleButterActivity.h>
|
||||
#include <Indoor/grid/walk/v2/modules/WalkModuleHeadingControl.h>
|
||||
#include <Indoor/grid/walk/v2/modules/WalkModuleNodeImportance.h>
|
||||
#include <Indoor/grid/walk/v2/modules/WalkModuleFavorZ.h>
|
||||
|
||||
#include <Indoor/sensors/radio/WiFiMeasurements.h>
|
||||
#include <Indoor/sensors/gps/GPSData.h>
|
||||
|
||||
struct MyState : public WalkState, public WalkStateFavorZ, public WalkStateHeading, public WalkStateBarometerActivity {
|
||||
|
||||
|
||||
/** 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;
|
||||
|
||||
/** 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;
|
||||
|
||||
/** reset the control-data after each transition */
|
||||
void resetAfterTransition() {
|
||||
turnSinceLastTransition_rad = 0;
|
||||
numStepsSinceLastTransition = 0;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // STATE_H
|
||||
21
qml.qrc
@@ -1,8 +1,23 @@
|
||||
<RCC>
|
||||
<qresource prefix="/">
|
||||
<file>res/gl/fragment1.glsl</file>
|
||||
<file>res/gl/fragmentLine.glsl</file>
|
||||
<file>res/gl/fragmentTexSimple.glsl</file>
|
||||
<file>res/gl/vertex1.glsl</file>
|
||||
<file>res/gl/tex/floor1.jpg</file>
|
||||
<file>res/gl/tex/wall1.jpg</file>
|
||||
<file>res/gl/fragmentTex.glsl</file>
|
||||
<file>res/gl/tex/arrows.png</file>
|
||||
<file>res/gl/tex/door2.jpg</file>
|
||||
<file>res/gl/tex/door2_normal.jpg</file>
|
||||
<file>res/gl/tex/floor4.jpg</file>
|
||||
<file>res/gl/tex/floor4_normal.jpg</file>
|
||||
<file>res/icons/load.svg</file>
|
||||
<file>res/icons/run.svg</file>
|
||||
<file>res/icons/route.svg</file>
|
||||
<file>res/icons/bug.svg</file>
|
||||
<file>res/gl/fragmentColorPoint.glsl</file>
|
||||
<file>res/gl/tex/wall3_normal.jpg</file>
|
||||
<file>res/gl/tex/wall3.jpg</file>
|
||||
<file>res/gl/tex/empty_normals.jpg</file>
|
||||
<file>res/icons/cube.svg</file>
|
||||
<file>res/icons/camera.svg</file>
|
||||
</qresource>
|
||||
</RCC>
|
||||
|
||||
25
res/gl/fragmentColorPoint.glsl
Normal file
@@ -0,0 +1,25 @@
|
||||
#ifdef GL_ES
|
||||
// Set default precision to medium
|
||||
precision mediump int;
|
||||
precision mediump float;
|
||||
#endif
|
||||
|
||||
// interpolated values
|
||||
//varying vec3 v_WorldPos;
|
||||
//varying vec3 v_normal;
|
||||
//varying vec2 v_texcoord;
|
||||
varying vec3 v_color;
|
||||
|
||||
void main() {
|
||||
|
||||
// set point color
|
||||
gl_FragColor = vec4(v_color, 1.0);
|
||||
|
||||
#ifdef GL_ES
|
||||
|
||||
// set point size
|
||||
gl_PointSize = 3.0;
|
||||
|
||||
#endif
|
||||
|
||||
}
|
||||
@@ -22,7 +22,7 @@ void main() {
|
||||
// diffuse fragment color
|
||||
|
||||
vec4 ambient = texture2D(texDiffuse, v_texcoord);
|
||||
vec4 diffuse = ambient * vec4(0.8, 0.6, 0.35, 1.0);
|
||||
vec4 diffuse = ambient * vec4(0.8, 0.8, 0.8, 1.0);
|
||||
vec4 specular = vec4(1,1,1,1);
|
||||
|
||||
// get the normal from the normal map
|
||||
@@ -46,12 +46,12 @@ void main() {
|
||||
// vec3 h = normalize(lightDir + eyeDir);
|
||||
// float intSpec = max(dot(h, normal), 0.0);
|
||||
// float specularIntensity = pow(intSpec, 2.0);
|
||||
float specularIntensity = pow(max(0.0, dot(eyeDir, reflect(-lightDir, normal))), 16);
|
||||
float specularIntensity = pow(max(0.0, dot(eyeDir, reflect(-lightDir, normal))), 16.0);
|
||||
|
||||
|
||||
// distance between fragment and light (in meter)
|
||||
float distToLight_m = length(lightWorldPos - v_WorldPos);
|
||||
float lightInt = clamp(1.0 / (distToLight_m / 10.0), 0.0, 1.0);
|
||||
float lightInt = 1.0;//clamp(1.0 / (distToLight_m / 10.0), 0.0, 1.0);
|
||||
|
||||
// Set fragment color from texture
|
||||
vec4 finalColor =
|
||||
@@ -60,6 +60,7 @@ void main() {
|
||||
clamp(specular * specularIntensity, 0.0, 1.0) * 1.0;
|
||||
|
||||
gl_FragColor = clamp(finalColor, 0.0, 1.0);
|
||||
gl_FragColor.a = 0.4;
|
||||
|
||||
// FOG
|
||||
//float mixing = pow((1.0 - v_CamPos.z * 3.0), 2);
|
||||
|
||||
BIN
res/gl/tex/empty_normals.jpg
Normal file
|
After Width: | Height: | Size: 998 B |
BIN
res/gl/tex/wall3.jpg
Executable file
|
After Width: | Height: | Size: 26 KiB |
BIN
res/gl/tex/wall3_normal.jpg
Executable file
|
After Width: | Height: | Size: 56 KiB |
@@ -12,6 +12,7 @@ attribute vec3 a_position;
|
||||
attribute vec3 a_normal;
|
||||
attribute vec2 a_texcoord;
|
||||
attribute vec3 a_tangent;
|
||||
attribute vec3 a_color;
|
||||
|
||||
varying vec3 v_WorldPos;
|
||||
varying vec3 v_CamPos;
|
||||
@@ -20,6 +21,8 @@ varying vec3 v_normal;
|
||||
varying vec2 v_texcoord;
|
||||
varying mat3 normalMat;
|
||||
|
||||
varying vec3 v_color;
|
||||
|
||||
void main() {
|
||||
|
||||
|
||||
@@ -29,7 +32,7 @@ void main() {
|
||||
v_CamPos = vec3(mv_matrix * vec4(a_position, 1.0));
|
||||
v_normal = a_normal;//normalize(vec3(mv_matrix * vec4(a_normal, 0.0)));
|
||||
v_texcoord = a_texcoord;
|
||||
|
||||
v_color = a_color;
|
||||
|
||||
|
||||
// http://www.opengl-tutorial.org/intermediate-tutorials/tutorial-13-normal-mapping/
|
||||
|
||||
57
res/icons/bug.svg
Normal file
@@ -0,0 +1,57 @@
|
||||
<?xml version="1.0" encoding="iso-8859-1"?>
|
||||
<!-- Generator: Adobe Illustrator 16.0.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
|
||||
<!DOCTYPE svg PUBLIC "-//W3C//DTD SVG 1.1//EN" "http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd">
|
||||
<svg version="1.1" id="Capa_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
|
||||
width="456.828px" height="456.828px" viewBox="0 0 456.828 456.828" style="enable-background:new 0 0 456.828 456.828;"
|
||||
xml:space="preserve">
|
||||
<g>
|
||||
<g>
|
||||
<path d="M451.383,247.54c-3.606-3.617-7.898-5.427-12.847-5.427h-63.953v-83.939l49.396-49.394
|
||||
c3.614-3.615,5.428-7.898,5.428-12.85c0-4.947-1.813-9.229-5.428-12.847c-3.614-3.616-7.898-5.424-12.847-5.424
|
||||
s-9.233,1.809-12.847,5.424l-49.396,49.394H107.923L58.529,83.083c-3.617-3.616-7.898-5.424-12.847-5.424
|
||||
c-4.952,0-9.233,1.809-12.85,5.424c-3.617,3.617-5.424,7.9-5.424,12.847c0,4.952,1.807,9.235,5.424,12.85l49.394,49.394v83.939
|
||||
H18.273c-4.949,0-9.231,1.81-12.847,5.427C1.809,251.154,0,255.442,0,260.387c0,4.949,1.809,9.237,5.426,12.848
|
||||
c3.616,3.617,7.898,5.431,12.847,5.431h63.953c0,30.447,5.522,56.53,16.56,78.224l-57.67,64.809
|
||||
c-3.237,3.81-4.712,8.234-4.425,13.275c0.284,5.037,2.235,9.273,5.852,12.703c3.617,3.045,7.707,4.571,12.275,4.571
|
||||
c5.33,0,9.897-1.991,13.706-5.995l52.246-59.102l4.285,4.004c2.664,2.479,6.801,5.564,12.419,9.274
|
||||
c5.617,3.71,11.897,7.423,18.842,11.143c6.95,3.71,15.23,6.852,24.84,9.418c9.614,2.573,19.273,3.86,28.98,3.86V169.034h36.547
|
||||
V424.85c9.134,0,18.363-1.239,27.688-3.717c9.328-2.471,17.135-5.232,23.418-8.278c6.275-3.049,12.47-6.519,18.555-10.42
|
||||
c6.092-3.901,10.089-6.612,11.991-8.138c1.909-1.526,3.333-2.762,4.284-3.71l56.534,56.243c3.433,3.617,7.707,5.424,12.847,5.424
|
||||
c5.141,0,9.422-1.807,12.854-5.424c3.607-3.617,5.421-7.902,5.421-12.851s-1.813-9.232-5.421-12.847l-59.388-59.669
|
||||
c12.755-22.651,19.13-50.251,19.13-82.796h63.953c4.949,0,9.236-1.81,12.847-5.427c3.614-3.614,5.432-7.898,5.432-12.847
|
||||
C456.828,255.445,455.011,251.158,451.383,247.54z"/>
|
||||
<path d="M293.081,31.27c-17.795-17.795-39.352-26.696-64.667-26.696c-25.319,0-46.87,8.901-64.668,26.696
|
||||
c-17.795,17.797-26.691,39.353-26.691,64.667h182.716C319.771,70.627,310.876,49.067,293.081,31.27z"/>
|
||||
</g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
</svg>
|
||||
|
After Width: | Height: | Size: 2.4 KiB |
8
res/icons/camera.svg
Normal file
@@ -0,0 +1,8 @@
|
||||
<?xml version='1.0' encoding='iso-8859-1'?>
|
||||
<!DOCTYPE svg PUBLIC '-//W3C//DTD SVG 1.1//EN' 'http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd'>
|
||||
<svg version="1.1" xmlns="http://www.w3.org/2000/svg" viewBox="0 0 223.708 223.708" xmlns:xlink="http://www.w3.org/1999/xlink" enable-background="new 0 0 223.708 223.708">
|
||||
<g>
|
||||
<path d="m222.399,60.893c-1.276-1.782-3.314-2.863-5.505-2.922l-20.248-.539 2.301-7.406c1.147-3.692-0.916-7.615-4.607-8.762l-124.146-38.574c-3.694-1.151-7.614,0.916-8.761,4.607l-19.287,62.073c-1.147,3.692 0.916,7.615 4.607,8.762l25.148,7.814-4.154,13.37c-0.551,1.773-0.375,3.692 0.489,5.335 0.864,1.643 2.345,2.875 4.118,3.426l11.424,3.55-28.371,45.868c-4.106-1.812-8.639-2.825-13.407-2.825h-35c-3.866,0-7,3.134-7,7v52.667c0,3.866 3.134,7 7,7h35c18.38,0 33.333-14.953 33.333-33.333 0-8.571-3.254-16.395-8.588-22.307 0.132-0.174 0.265-0.347 0.382-0.536l30.459-49.243 14.876,4.622c0.692,0.215 1.391,0.317 2.079,0.317 2.985,0 5.75-1.925 6.683-4.925l4.154-13.37 45.52,14.144c0.679,0.211 1.379,0.315 2.077,0.315 1.125,0 2.244-0.271 3.258-0.805 1.643-0.864 2.875-2.345 3.426-4.118l2.301-7.406 16.989,11.031c1.149,0.746 2.476,1.129 3.813,1.129 0.801,0 1.606-0.138 2.379-0.417 2.062-0.745 3.655-2.413 4.305-4.506l13.946-44.883c0.651-2.093 0.283-4.371-0.993-6.153zm-208.399,107.776h9.333v38.667h-9.333v-38.667zm28,38.667h-4.667v-38.667h4.667c10.66,0 19.333,8.673 19.333,19.333s-8.673,19.334-19.333,19.334zm67.932-102.243l-26.739-8.309 2.077-6.685 26.739,8.309-2.077,6.685zm58.436-3.833l-110.776-34.421 15.133-48.703 110.776,34.42-2.967,9.549-9.199,29.604c0,0.002-0.001,0.003-0.001,0.005l-2.966,9.546zm30.452-2.313l-12.543-8.144 6.053-19.481 14.95,.398-8.46,27.227z"/>
|
||||
<path d="m74.084,51.697c-1.84,0-3.65,0.75-4.95,2.05-1.3,1.31-2.05,3.11-2.05,4.95s0.75,3.65 2.05,4.95c1.3,1.31 3.11,2.05 4.95,2.05 1.84,0 3.65-0.74 4.95-2.05 1.3-1.3 2.05-3.11 2.05-4.95s-0.75-3.64-2.05-4.95c-1.3-1.3-3.11-2.05-4.95-2.05z"/>
|
||||
</g>
|
||||
</svg>
|
||||
|
After Width: | Height: | Size: 1.9 KiB |
44
res/icons/cube.svg
Normal file
@@ -0,0 +1,44 @@
|
||||
<?xml version="1.0" encoding="iso-8859-1"?>
|
||||
<!-- Generator: Adobe Illustrator 18.0.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
|
||||
<!DOCTYPE svg PUBLIC "-//W3C//DTD SVG 1.1//EN" "http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd">
|
||||
<svg version="1.1" id="Capa_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
|
||||
viewBox="0 0 305.092 305.092" style="enable-background:new 0 0 305.092 305.092;" xml:space="preserve">
|
||||
<g>
|
||||
<path d="M305.092,7.501c0-4.143-3.357-7.5-7.5-7.5H49.008c-2.074,0-3.951,0.842-5.309,2.202L2.203,43.698
|
||||
C0.842,45.056,0,46.933,0,49.007v248.584c0,4.142,3.357,7.5,7.5,7.5h248.584c2.039,0,3.885-0.816,5.238-2.137
|
||||
c0.021-0.02,0.045-0.038,0.066-0.06l41.508-41.508c0.01-0.011,0.02-0.022,0.029-0.033c1.338-1.354,2.166-3.215,2.166-5.271V7.501z
|
||||
M290.092,248.583h-26.508V52.113l26.508-26.507V248.583z M279.484,263.583l-15.9,15.9v-15.9H279.484z M41.508,25.606v15.9h-15.9
|
||||
L41.508,25.606z M15,56.507h26.508v196.469L15,279.483V56.507z M248.584,290.091H25.607l26.508-26.508h196.469V290.091z
|
||||
M248.584,248.583H56.508V56.507h192.076V248.583z M252.979,41.507H56.508V15.001h222.979L252.979,41.507z"/>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
</svg>
|
||||
|
After Width: | Height: | Size: 1.3 KiB |
43
res/icons/load.svg
Normal file
@@ -0,0 +1,43 @@
|
||||
<?xml version="1.0" encoding="iso-8859-1"?>
|
||||
<!-- Generator: Adobe Illustrator 19.0.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
|
||||
<svg version="1.1" id="Capa_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
|
||||
viewBox="0 0 49 49" style="enable-background:new 0 0 49 49;" xml:space="preserve">
|
||||
<g>
|
||||
<rect x="27.5" y="5" width="6" height="10"/>
|
||||
<path d="M39.914,0H0.5v49h48V8.586L39.914,0z M10.5,2h26v16h-26V2z M39.5,47h-31V26h31V47z"/>
|
||||
<path d="M13.5,32h7c0.553,0,1-0.447,1-1s-0.447-1-1-1h-7c-0.553,0-1,0.447-1,1S12.947,32,13.5,32z"/>
|
||||
<path d="M13.5,36h10c0.553,0,1-0.447,1-1s-0.447-1-1-1h-10c-0.553,0-1,0.447-1,1S12.947,36,13.5,36z"/>
|
||||
<path d="M26.5,36c0.27,0,0.52-0.11,0.71-0.29c0.18-0.19,0.29-0.45,0.29-0.71s-0.11-0.521-0.29-0.71c-0.37-0.37-1.04-0.37-1.41,0
|
||||
c-0.19,0.189-0.3,0.439-0.3,0.71c0,0.27,0.109,0.52,0.29,0.71C25.979,35.89,26.229,36,26.5,36z"/>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
</svg>
|
||||
|
After Width: | Height: | Size: 1.1 KiB |
91
res/icons/route.svg
Normal file
@@ -0,0 +1,91 @@
|
||||
<?xml version="1.0" encoding="iso-8859-1"?>
|
||||
<!-- Generator: Adobe Illustrator 19.0.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
|
||||
<svg version="1.1" id="Capa_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
|
||||
viewBox="0 0 60 60" style="enable-background:new 0 0 60 60;" xml:space="preserve">
|
||||
<g>
|
||||
<path d="M35.493,24h2c0.553,0,1-0.447,1-1s-0.447-1-1-1h-2c-0.553,0-1,0.447-1,1S34.94,24,35.493,24z"/>
|
||||
<path d="M31.995,31c-0.433-0.001-0.854-0.078-1.252-0.23c-0.512-0.195-1.093,0.062-1.291,0.578
|
||||
c-0.196,0.516,0.063,1.094,0.578,1.291c0.626,0.238,1.285,0.36,1.963,0.361h0.357c0.553,0,1-0.447,1-1s-0.447-1-1-1H31.995z"/>
|
||||
<path d="M29.621,24.676c0.181,0,0.363-0.049,0.528-0.151c0.443-0.276,0.933-0.445,1.454-0.503c0.549-0.061,0.945-0.555,0.885-1.104
|
||||
s-0.551-0.941-1.104-0.885c-0.822,0.091-1.594,0.357-2.294,0.794c-0.469,0.292-0.611,0.909-0.319,1.378
|
||||
C28.961,24.509,29.287,24.676,29.621,24.676z"/>
|
||||
<path d="M35.993,40c-0.086,0-0.171,0.002-0.256,0.006c-0.552,0.022-0.98,0.488-0.958,1.04c0.021,0.538,0.465,0.959,0.998,0.959
|
||||
c0.014,0,0.028,0,0.042-0.001L37.778,42c0.553,0,1-0.447,1-1s-0.447-1-1-1H35.993z"/>
|
||||
<path d="M43.493,24c0.553,0,1-0.447,1-1s-0.447-1-1-1h-2c-0.553,0-1,0.447-1,1s0.447,1,1,1H43.493z"/>
|
||||
<path d="M47.778,40c-0.553,0-1,0.447-1,1s0.447,1,1,1h2c0.553,0,1-0.447,1-1s-0.447-1-1-1H47.778z"/>
|
||||
<path d="M51.351,32c0-0.553-0.447-1-1-1h-2c-0.553,0-1,0.447-1,1s0.447,1,1,1h2C50.903,33,51.351,32.553,51.351,32z"/>
|
||||
<path d="M41.778,42h2c0.553,0,1-0.447,1-1s-0.447-1-1-1h-2c-0.553,0-1,0.447-1,1S41.226,42,41.778,42z"/>
|
||||
<path d="M45.351,32c0-0.553-0.447-1-1-1h-2c-0.553,0-1,0.447-1,1s0.447,1,1,1h2C44.903,33,45.351,32.553,45.351,32z"/>
|
||||
<path d="M36.351,31c-0.553,0-1,0.447-1,1s0.447,1,1,1h2c0.553,0,1-0.447,1-1s-0.447-1-1-1H36.351z"/>
|
||||
<path d="M24.064,58h-2c-0.553,0-1,0.447-1,1s0.447,1,1,1h2c0.553,0,1-0.447,1-1S24.616,58,24.064,58z"/>
|
||||
<path d="M18.064,58h-2c-0.553,0-1,0.447-1,1s0.447,1,1,1h2c0.553,0,1-0.447,1-1S18.616,58,18.064,58z"/>
|
||||
<path d="M52.604,54.517c-0.539-0.121-1.074,0.217-1.195,0.756c-0.115,0.51-0.338,0.979-0.663,1.392
|
||||
c-0.341,0.434-0.267,1.063,0.168,1.404c0.184,0.144,0.401,0.214,0.617,0.214c0.297,0,0.59-0.131,0.787-0.382
|
||||
c0.504-0.64,0.864-1.396,1.042-2.188C53.481,55.173,53.143,54.638,52.604,54.517z"/>
|
||||
<path d="M51.531,52.719c0.216,0,0.435-0.07,0.617-0.214c0.435-0.342,0.509-0.971,0.168-1.404c-0.503-0.639-1.152-1.167-1.879-1.528
|
||||
c-0.497-0.247-1.095-0.044-1.341,0.45c-0.246,0.495-0.044,1.095,0.45,1.341c0.463,0.229,0.877,0.566,1.197,0.974
|
||||
C50.941,52.588,51.234,52.719,51.531,52.719z"/>
|
||||
<path d="M47.065,50c0-0.553-0.447-1-1-1h-2c-0.553,0-1,0.447-1,1s0.447,1,1,1h2C46.617,51,47.065,50.553,47.065,50z"/>
|
||||
<path d="M47.993,58h-1.93c-0.553,0-1,0.447-1,1s0.447,1,1,1l1.971-0.001l0.029-1v1c0.553,0,0.965-0.447,0.965-1
|
||||
C49.028,58.447,48.546,58,47.993,58z"/>
|
||||
<path d="M59.426,35.632c-0.088-0.546-0.603-0.919-1.146-0.829c-0.546,0.087-0.917,0.601-0.829,1.146
|
||||
c0.028,0.178,0.044,0.359,0.042,0.552c0,0.336-0.048,0.668-0.142,0.988c-0.155,0.53,0.148,1.086,0.679,1.241
|
||||
c0.094,0.027,0.188,0.04,0.281,0.04c0.433,0,0.832-0.282,0.96-0.719c0.147-0.503,0.222-1.024,0.222-1.543
|
||||
C59.495,36.22,59.473,35.925,59.426,35.632z"/>
|
||||
<path d="M28.029,29.855c0.524-0.173,0.81-0.738,0.638-1.263c-0.115-0.351-0.174-0.718-0.174-1.088
|
||||
c0.001-0.151,0.01-0.302,0.028-0.449c0.069-0.548-0.319-1.049-0.867-1.117c-0.565-0.063-1.049,0.321-1.117,0.867
|
||||
c-0.028,0.226-0.043,0.456-0.044,0.694c0,0.588,0.092,1.166,0.273,1.718c0.139,0.421,0.53,0.688,0.95,0.688
|
||||
C27.82,29.905,27.926,29.89,28.029,29.855z"/>
|
||||
<path d="M56.746,31.738c-0.714-0.414-1.494-0.657-2.317-0.722c-0.549-0.04-1.032,0.367-1.075,0.919
|
||||
c-0.043,0.551,0.368,1.032,0.919,1.075c0.522,0.041,1.017,0.195,1.47,0.458c0.158,0.092,0.331,0.135,0.501,0.135
|
||||
c0.345,0,0.681-0.179,0.866-0.498C57.387,32.628,57.224,32.016,56.746,31.738z"/>
|
||||
<path d="M55.345,39.729C54.916,39.909,54.462,40,53.993,40h-0.215c-0.553,0-1,0.447-1,1s0.447,1,1,1h0.215
|
||||
c0.736,0,1.451-0.144,2.125-0.427c0.51-0.214,0.749-0.8,0.535-1.309C56.44,39.755,55.85,39.515,55.345,39.729z"/>
|
||||
<path d="M32.555,44.839c0.099-0.514,0.307-0.989,0.619-1.413c0.327-0.444,0.232-1.07-0.213-1.398
|
||||
c-0.445-0.326-1.07-0.232-1.398,0.213c-0.489,0.666-0.817,1.413-0.973,2.222c-0.104,0.542,0.251,1.066,0.794,1.171
|
||||
c0.063,0.012,0.127,0.018,0.189,0.018C32.043,45.65,32.462,45.317,32.555,44.839z"/>
|
||||
<path d="M34.122,50.594c0.38,0,0.742-0.217,0.91-0.584c0.229-0.503,0.009-1.096-0.493-1.325c-0.469-0.215-0.894-0.538-1.228-0.936
|
||||
c-0.356-0.423-0.986-0.478-1.409-0.122c-0.423,0.355-0.478,0.986-0.122,1.409c0.524,0.623,1.19,1.131,1.927,1.467
|
||||
C33.842,50.564,33.983,50.594,34.122,50.594z"/>
|
||||
<path d="M30.064,58h-2c-0.553,0-1,0.447-1,1s0.447,1,1,1h2c0.553,0,1-0.447,1-1S30.616,58,30.064,58z"/>
|
||||
<path d="M36.064,58h-2c-0.553,0-1,0.447-1,1s0.447,1,1,1h2c0.553,0,1-0.447,1-1S36.616,58,36.064,58z"/>
|
||||
<path d="M41.065,50c0-0.553-0.447-1-1-1h-2c-0.553,0-1,0.447-1,1s0.447,1,1,1h2C40.617,51,41.065,50.553,41.065,50z"/>
|
||||
<path d="M42.064,58h-2c-0.553,0-1,0.447-1,1s0.447,1,1,1h2c0.553,0,1-0.447,1-1S42.616,58,42.064,58z"/>
|
||||
<path d="M21.021,28.977C18.75,26.412,15.722,25,12.493,25s-6.257,1.412-8.527,3.977c-4.612,5.211-4.612,13.688,0,18.899
|
||||
l8.527,9.633l8.527-9.633C25.633,42.665,25.633,34.188,21.021,28.977z M12.493,43c-3.309,0-6-2.691-6-6s2.691-6,6-6s6,2.691,6,6
|
||||
S15.802,43,12.493,43z"/>
|
||||
<path d="M48.747,24.507l6.464-7.286c3.478-3.92,3.478-10.296,0-14.216C53.491,1.067,51.195,0,48.746,0
|
||||
c-2.448,0-4.744,1.067-6.464,3.005c-3.477,3.92-3.477,10.296,0,14.216L48.747,24.507z M48.993,4c3.032,0,5.5,2.468,5.5,5.5
|
||||
s-2.468,5.5-5.5,5.5s-5.5-2.468-5.5-5.5S45.961,4,48.993,4z"/>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
</svg>
|
||||
|
After Width: | Height: | Size: 5.7 KiB |
51
res/icons/run.svg
Normal file
@@ -0,0 +1,51 @@
|
||||
<?xml version="1.0" encoding="iso-8859-1"?>
|
||||
<!-- Generator: Adobe Illustrator 16.0.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
|
||||
<!DOCTYPE svg PUBLIC "-//W3C//DTD SVG 1.1//EN" "http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd">
|
||||
<svg version="1.1" id="Capa_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
|
||||
width="948.112px" height="948.112px" viewBox="0 0 948.112 948.112" style="enable-background:new 0 0 948.112 948.112;"
|
||||
xml:space="preserve">
|
||||
<g>
|
||||
<g>
|
||||
<path d="M39.068,674.506c-26.1,5-43.2,30.2-38.2,56.301c4.4,23,24.6,39,47.2,39c3,0,6.1-0.301,9.1-0.9l198-38
|
||||
c11.3-2.2,21.4-8.3,28.6-17.3l85-107.2l-28.399-14.5c-21-10.6-35.601-29.8-40.601-53.1l-80.2,101.1L39.068,674.506z"/>
|
||||
<circle cx="744.268" cy="151.106" r="105.4"/>
|
||||
<path d="M514.268,124.706c-11.1-11.4-21.399-15.9-32.699-15.9c-4.101,0-8.2,0.6-12.601,1.6l-180.899,42.9
|
||||
c-25,5.9-40.4,31-34.5,55.9c5.1,21.4,24.1,35.8,45.2,35.8c3.601,0,7.2-0.4,10.801-1.3l154.1-36.5c10,11.1,60.1,65.4,69.2,75l0,0
|
||||
c-63.7,68.2-127.4,136.3-191.101,204.5c-1,1.101-1.899,2.2-2.8,3.3c-18.6,23.7-12.899,60.9,15.101,75l33.899,17.301l161.4,82.399
|
||||
l-101.4,164.3c-13.899,22.601-6.899,52.2,15.7,66.2c7.9,4.9,16.6,7.2,25.2,7.2l0,0c16.1,0,31.899-8.1,41-22.8l128.8-208.7
|
||||
c7.1-11.5,9-25.4,5.3-38.3c-3.7-13-12.6-23.8-24.7-29.9l-132.3-67.3l139.101-148.8l105,89c8.699,7.399,19.399,11,30,11
|
||||
c11.399,0,22.8-4.2,31.699-12.4l120.5-112.3c18.801-17.5,19.9-46.9,2.4-65.7c-9.2-9.8-21.6-14.8-34-14.8
|
||||
c-11.3,0-22.7,4.1-31.6,12.4l-90.2,83.9C779.768,377.806,553.768,165.206,514.268,124.706z"/>
|
||||
</g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
<g>
|
||||
</g>
|
||||
</svg>
|
||||
|
After Width: | Height: | Size: 1.8 KiB |
@@ -2,18 +2,7 @@
|
||||
#define ACCELEROMETERSENSOR_H
|
||||
|
||||
#include "Sensor.h"
|
||||
|
||||
struct AccelerometerData {
|
||||
float x;
|
||||
float y;
|
||||
float z;
|
||||
AccelerometerData(const float x, const float y, const float z) : x(x), y(y), z(z) {;}
|
||||
std::string asString() const {
|
||||
std::stringstream ss;
|
||||
ss << "(" << x << "," << y << "," << z << ")";
|
||||
return ss.str();
|
||||
}
|
||||
};
|
||||
#include <Indoor/sensors/imu/AccelerometerData.h>
|
||||
|
||||
class AccelerometerSensor : public Sensor<AccelerometerData> {
|
||||
|
||||
|
||||
11
sensors/BarometerSensor.h
Normal file
@@ -0,0 +1,11 @@
|
||||
#ifndef BAROMETERSENSOR_H
|
||||
#define BAROMETERSENSOR_H
|
||||
|
||||
#include "Sensor.h"
|
||||
#include <Indoor/sensors/pressure/BarometerData.h>
|
||||
|
||||
class BarometerSensor : public Sensor<BarometerData> {
|
||||
|
||||
};
|
||||
|
||||
#endif // BAROMETERSENSOR_H
|
||||
11
sensors/GyroscopeSensor.h
Normal file
@@ -0,0 +1,11 @@
|
||||
#ifndef GYROSCOPESENSOR_H
|
||||
#define GYROSCOPESENSOR_H
|
||||
|
||||
#include "Sensor.h"
|
||||
#include <Indoor/sensors/imu/GyroscopeData.h>
|
||||
|
||||
class GyroscopeSensor : public Sensor<GyroscopeData> {
|
||||
|
||||
};
|
||||
|
||||
#endif // GYROSCOPESENSOR_H
|
||||
@@ -3,6 +3,9 @@
|
||||
|
||||
#include <vector>
|
||||
#include <QObject>
|
||||
#include <Indoor/data/Timestamp.h>
|
||||
|
||||
template <typename T> class Sensor;
|
||||
|
||||
/** listen for sensor events */
|
||||
template <typename T> class SensorListener {
|
||||
@@ -10,7 +13,7 @@ template <typename T> class SensorListener {
|
||||
public:
|
||||
|
||||
/** incoming sensor data */
|
||||
virtual void onSensorData(const T& data) = 0;
|
||||
virtual void onSensorData(Sensor<T>* sensor, const Timestamp ts, const T& data) = 0;
|
||||
|
||||
};
|
||||
|
||||
@@ -38,9 +41,17 @@ public:
|
||||
protected:
|
||||
|
||||
/** inform all attached listeners */
|
||||
void informListeners(const T& sensorData) const {
|
||||
void informListeners(const T& sensorData) {
|
||||
const Timestamp now = Timestamp::fromRunningTime();
|
||||
for (SensorListener<T>* l : listeners) {
|
||||
l->onSensorData(sensorData);
|
||||
l->onSensorData(this, now, sensorData);
|
||||
}
|
||||
}
|
||||
|
||||
/** inform all attached listeners. call this if you know the timestamp */
|
||||
void informListeners(const Timestamp ts, const T& sensorData) {
|
||||
for (SensorListener<T>* l : listeners) {
|
||||
l->onSensorData(this, ts, sensorData);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -12,36 +12,69 @@
|
||||
#include "dummy/AccelerometerSensorDummy.h"
|
||||
#include "android/AccelerometerSensorAndroid.h"
|
||||
|
||||
#include "GyroscopeSensor.h"
|
||||
#include "android/GyroscopeSensorAndroid.h"
|
||||
#include "dummy/GyroscopeSensorDummy.h"
|
||||
|
||||
#include "BarometerSensor.h"
|
||||
#include "android/BarometerSensorAndroid.h"
|
||||
#include "dummy/BarometerSensorDummy.h"
|
||||
|
||||
#include "StepSensor.h"
|
||||
#include "TurnSensor.h"
|
||||
|
||||
|
||||
|
||||
class SensorFactory {
|
||||
|
||||
private:
|
||||
|
||||
/** this one is a dirty hack, as static class member variables do not work header-only */
|
||||
static SensorFactory** getPtr() {
|
||||
static SensorFactory* ptr = nullptr;
|
||||
return &ptr;
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
/** set the to-be-used sensor-fatory */
|
||||
static void set(SensorFactory* fac) {
|
||||
Assert::isNull(*getPtr(), "set() was already called. currentely this is not intended");
|
||||
*getPtr() = fac;
|
||||
}
|
||||
|
||||
/** get the currently configured sensory factory */
|
||||
static SensorFactory& get() {
|
||||
Assert::isNotNull(*getPtr(), "call set() first to set an actual factory instance!");
|
||||
return **getPtr();
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
/** get the WiFi sensor */
|
||||
static WiFiSensor& getWiFi() {
|
||||
#ifdef ANDROID
|
||||
return WiFiSensorAndroid::get();
|
||||
#else
|
||||
return WiFiSensorDummy::get();
|
||||
#endif
|
||||
}
|
||||
virtual WiFiSensor& getWiFi() = 0;
|
||||
|
||||
/** get the Accelerometer sensor */
|
||||
static AccelerometerSensor& getAccelerometer() {
|
||||
#ifdef ANDROID
|
||||
return AccelerometerSensorAndroid::get();
|
||||
#else
|
||||
return AccelerometerSensorDummy::get();
|
||||
#endif
|
||||
}
|
||||
virtual AccelerometerSensor& getAccelerometer() = 0;
|
||||
|
||||
/** get the Gyroscope sensor */
|
||||
virtual GyroscopeSensor& getGyroscope() = 0;
|
||||
|
||||
/** get the Barometer sensor */
|
||||
virtual BarometerSensor& getBarometer() = 0;
|
||||
|
||||
/** get the Step sensor */
|
||||
static StepSensor& getSteps() {
|
||||
StepSensor& getSteps() {
|
||||
static StepSensor steps(getAccelerometer());
|
||||
return steps;
|
||||
}
|
||||
|
||||
/** get the Turn sensor */
|
||||
TurnSensor& getTurns() {
|
||||
static TurnSensor turns(getAccelerometer(), getGyroscope());
|
||||
return turns;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // SENSORFACTORY_H
|
||||
|
||||
@@ -1,66 +1,46 @@
|
||||
#ifndef STEPSENSOR_H
|
||||
#define STEPSENSOR_H
|
||||
|
||||
|
||||
#include "../misc/fixc11.h"
|
||||
#include <Indoor/sensors/imu/StepDetection.h>
|
||||
#include "AccelerometerSensor.h"
|
||||
#include "Sensor.h"
|
||||
|
||||
|
||||
struct StepData {
|
||||
;
|
||||
const int stepsSinceLastEvent = 0;
|
||||
StepData(const int stepsSinceLastEvent) : stepsSinceLastEvent(stepsSinceLastEvent) {;}
|
||||
};
|
||||
|
||||
class StepSensor : public Sensor<StepData>, public SensorListener<AccelerometerData> {
|
||||
/**
|
||||
* step-sensor detects steps from the accelerometer
|
||||
*/
|
||||
class StepSensor : public SensorListener<AccelerometerData>, public Sensor<StepData> {
|
||||
|
||||
private:
|
||||
|
||||
AccelerometerSensor& acc;
|
||||
StepDetection sd;
|
||||
|
||||
public:
|
||||
|
||||
/** hidden ctor. use singleton */
|
||||
StepSensor(AccelerometerSensor& acc) : acc(acc) {
|
||||
;
|
||||
}
|
||||
|
||||
void start() override {
|
||||
StepSensor(AccelerometerSensor& acc) {
|
||||
acc.addListener(this);
|
||||
acc.start();
|
||||
}
|
||||
|
||||
void stop() override {
|
||||
throw "todo";
|
||||
virtual void start() override {
|
||||
//
|
||||
}
|
||||
|
||||
virtual void onSensorData(const AccelerometerData& data) override {
|
||||
parse(data);
|
||||
virtual void stop() override {
|
||||
//
|
||||
}
|
||||
|
||||
|
||||
protected:
|
||||
|
||||
const float threshold = 11.0;
|
||||
const int blockTime = 25;
|
||||
int block = 0;
|
||||
|
||||
void parse(const AccelerometerData& data) {
|
||||
|
||||
const float x = data.x;
|
||||
const float y = data.y;
|
||||
const float z = data.z;
|
||||
|
||||
const float mag = std::sqrt( (x*x) + (y*y) + (z*z) );
|
||||
|
||||
if (block > 0) {
|
||||
--block;
|
||||
} else if (mag > threshold) {
|
||||
informListeners(StepData());
|
||||
block = blockTime;
|
||||
virtual void onSensorData(Sensor<AccelerometerData>* sensor, const Timestamp ts, const AccelerometerData& data) override {
|
||||
(void) sensor;
|
||||
const bool step = sd.add(ts, data);
|
||||
if (step) {
|
||||
informListeners(ts, StepData(1));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
#endif // STEPSENSOR_H
|
||||
|
||||
53
sensors/TurnSensor.h
Normal file
@@ -0,0 +1,53 @@
|
||||
#ifndef TURNSENSOR_H
|
||||
#define TURNSENSOR_H
|
||||
|
||||
#include <Indoor/sensors/imu/TurnDetection.h>
|
||||
#include "AccelerometerSensor.h"
|
||||
#include "GyroscopeSensor.h"
|
||||
|
||||
struct TurnData {
|
||||
float radSinceLastEvent;
|
||||
float radSinceStart;
|
||||
TurnData() : radSinceLastEvent(0), radSinceStart(0) {;}
|
||||
};
|
||||
|
||||
class TurnSensor : public SensorListener<AccelerometerData>, public SensorListener<GyroscopeData>, public Sensor<TurnData> {
|
||||
|
||||
private:
|
||||
|
||||
TurnDetection turn;
|
||||
TurnData data;
|
||||
|
||||
public:
|
||||
|
||||
/** ctor */
|
||||
TurnSensor(AccelerometerSensor& acc, GyroscopeSensor& gyro) {
|
||||
acc.addListener(this);
|
||||
gyro.addListener(this);
|
||||
}
|
||||
|
||||
void start() override {
|
||||
//
|
||||
}
|
||||
|
||||
void stop() override {
|
||||
//
|
||||
}
|
||||
|
||||
virtual void onSensorData(Sensor<AccelerometerData>* sensor, const Timestamp ts, const AccelerometerData& data) override {
|
||||
(void) sensor;
|
||||
turn.addAccelerometer(ts, data);
|
||||
}
|
||||
|
||||
virtual void onSensorData(Sensor<GyroscopeData>* sensor, const Timestamp ts, const GyroscopeData& data) override {
|
||||
(void) sensor;
|
||||
const float rad = turn.addGyroscope(ts, data);
|
||||
this->data.radSinceLastEvent = rad;
|
||||
this->data.radSinceStart += rad;
|
||||
informListeners(ts, this->data);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
#endif // TURNSENSOR_H
|
||||
@@ -1,35 +1,36 @@
|
||||
#ifndef WIFISENSOR_H
|
||||
#define WIFISENSOR_H
|
||||
|
||||
#include "../misc/fixc11.h"
|
||||
#include <string>
|
||||
#include <sstream>
|
||||
#include "Sensor.h"
|
||||
#include <Indoor/sensors/radio/WiFiMeasurements.h>
|
||||
|
||||
//struct WiFiSensorDataEntry {
|
||||
// std::string bssid;
|
||||
// float rssi;
|
||||
// WiFiSensorDataEntry(const std::string& bssid, const float rssi) : bssid(bssid), rssi(rssi) {;}
|
||||
// std::string asString() const {
|
||||
// std::stringstream ss;
|
||||
// ss << bssid << '\t' << (int)rssi;
|
||||
// return ss.str();
|
||||
// }
|
||||
//};
|
||||
|
||||
|
||||
struct WiFiSensorDataEntry {
|
||||
std::string bssid;
|
||||
float rssi;
|
||||
WiFiSensorDataEntry(const std::string& bssid, const float rssi) : bssid(bssid), rssi(rssi) {;}
|
||||
std::string asString() const {
|
||||
std::stringstream ss;
|
||||
ss << bssid << '\t' << (int)rssi;
|
||||
return ss.str();
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
struct WiFiSensorData {
|
||||
std::vector<WiFiSensorDataEntry> entries;
|
||||
std::string asString() const {
|
||||
std::stringstream ss;
|
||||
for(const WiFiSensorDataEntry& e : entries) {ss << e.asString() << '\n';}
|
||||
return ss.str();
|
||||
}
|
||||
};
|
||||
//struct WiFiSensorData {
|
||||
// std::vector<WiFiSensorDataEntry> entries;
|
||||
// std::string asString() const {
|
||||
// std::stringstream ss;
|
||||
// for(const WiFiSensorDataEntry& e : entries) {ss << e.asString() << '\n';}
|
||||
// return ss.str();
|
||||
// }
|
||||
//};
|
||||
|
||||
|
||||
/** interface for all wifi sensors */
|
||||
class WiFiSensor : public Sensor<WiFiSensorData> {
|
||||
class WiFiSensor : public Sensor<WiFiMeasurements> {
|
||||
|
||||
protected:
|
||||
|
||||
|
||||
@@ -51,6 +51,6 @@ public:
|
||||
|
||||
};
|
||||
|
||||
#endif ANDROID
|
||||
#endif // ANDROID
|
||||
|
||||
#endif // ACCELEROMETERSENSORANDROID_H
|
||||
|
||||
55
sensors/android/BarometerSensorAndroid.h
Normal file
@@ -0,0 +1,55 @@
|
||||
#ifndef BAROMETERSENSORANDROID_H
|
||||
#define BAROMETERSENSORANDROID_H
|
||||
|
||||
#ifdef ANDROID
|
||||
|
||||
#include <sstream>
|
||||
|
||||
#include "../BarometerSensor.h"
|
||||
|
||||
#include <QtSensors/QPressureSensor>
|
||||
|
||||
#include "../AccelerometerSensor.h"
|
||||
|
||||
class BarometerSensorAndroid : public BarometerSensor {
|
||||
|
||||
private:
|
||||
|
||||
QPressureSensor baro;
|
||||
|
||||
/** hidden ctor. use singleton */
|
||||
BarometerSensorAndroid() {
|
||||
;
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
/** singleton access */
|
||||
static BarometerSensorAndroid& get() {
|
||||
static BarometerSensorAndroid baro;
|
||||
return baro;
|
||||
}
|
||||
|
||||
void start() override {
|
||||
|
||||
auto onSensorData = [&] () {
|
||||
BarometerData data(baro.reading()->pressure());
|
||||
informListeners(data);
|
||||
};
|
||||
|
||||
baro.connect(&baro, &QPressureSensor::readingChanged, onSensorData);
|
||||
baro.start();
|
||||
|
||||
}
|
||||
|
||||
void stop() override {
|
||||
throw "TODO";
|
||||
}
|
||||
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
#endif // BAROMETERSENSORANDROID_H
|
||||
59
sensors/android/GyroscopeSensorAndroid.h
Normal file
@@ -0,0 +1,59 @@
|
||||
#ifndef GYROSCOPESENSORANDROID_H
|
||||
#define GYROSCOPESENSORANDROID_H
|
||||
|
||||
#ifdef ANDROID
|
||||
|
||||
#include <sstream>
|
||||
|
||||
#include "../GyroscopeSensor.h"
|
||||
|
||||
#include <QtSensors/QGyroscope>
|
||||
|
||||
#include "../AccelerometerSensor.h"
|
||||
|
||||
class GyroscopeSensorAndroid : public GyroscopeSensor {
|
||||
|
||||
private:
|
||||
|
||||
QGyroscope gyro;
|
||||
|
||||
/** hidden ctor. use singleton */
|
||||
GyroscopeSensorAndroid() {
|
||||
;
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
/** singleton access */
|
||||
static GyroscopeSensorAndroid& get() {
|
||||
static GyroscopeSensorAndroid gyro;
|
||||
return gyro;
|
||||
}
|
||||
|
||||
float degToRad(const float deg) {
|
||||
return deg / 180.0f * M_PI;
|
||||
}
|
||||
|
||||
void start() override {
|
||||
|
||||
auto onSensorData = [&] () {
|
||||
GyroscopeData data(degToRad(gyro.reading()->x()), degToRad(gyro.reading()->y()), degToRad(gyro.reading()->z()));
|
||||
informListeners(data);
|
||||
};
|
||||
|
||||
gyro.connect(&gyro, &QGyroscope::readingChanged, onSensorData);
|
||||
gyro.start();
|
||||
|
||||
}
|
||||
|
||||
void stop() override {
|
||||
throw "TODO";
|
||||
}
|
||||
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif // ANDROID
|
||||
|
||||
#endif // GYROSCOPESENSORANDROID_H
|
||||
41
sensors/android/SensorFactoryAndroid.h
Normal file
@@ -0,0 +1,41 @@
|
||||
#ifndef SENSORFACTORYANDROID_H
|
||||
#define SENSORFACTORYANDROID_H
|
||||
|
||||
#ifdef ANDROID
|
||||
|
||||
#include "../SensorFactory.h"
|
||||
|
||||
#include "WiFiSensorAndroid.h"
|
||||
#include "AccelerometerSensorAndroid.h"
|
||||
#include "GyroscopeSensorAndroid.h"
|
||||
#include "BarometerSensorAndroid.h"
|
||||
|
||||
/**
|
||||
* sensor factory that provides real hardware sensors from
|
||||
* an android smartphone that fire real data values
|
||||
*/
|
||||
class SensorFactoryAndroid : public SensorFactory {
|
||||
|
||||
public:
|
||||
|
||||
WiFiSensor& getWiFi() override {
|
||||
return WiFiSensorAndroid::get();
|
||||
}
|
||||
|
||||
AccelerometerSensor& getAccelerometer() override {
|
||||
return AccelerometerSensorAndroid::get();
|
||||
}
|
||||
|
||||
GyroscopeSensor& getGyroscope() override {
|
||||
return GyroscopeSensorAndroid::get();
|
||||
}
|
||||
|
||||
BarometerSensor& getBarometer() override {
|
||||
return BarometerSensorAndroid::get();
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
#endif // SENSORFACTORYANDROID_H
|
||||
20
sensors/android/WiFiSensorAndroid.cpp
Normal file
@@ -0,0 +1,20 @@
|
||||
#ifdef ANDROID
|
||||
|
||||
#include "WiFiSensorAndroid.h"
|
||||
|
||||
extern "C" {
|
||||
|
||||
/** called after each successful WiFi scan */
|
||||
JNIEXPORT void JNICALL Java_indoor_java_WiFi_onScanComplete(JNIEnv* env, jobject jobj, jbyteArray arrayID) {
|
||||
(void) env; (void) jobj;
|
||||
jsize length = env->GetArrayLength(arrayID);
|
||||
jboolean isCopy;
|
||||
jbyte* data = env->GetByteArrayElements(arrayID, &isCopy);
|
||||
std::string str((char*)data, length);
|
||||
env->ReleaseByteArrayElements(arrayID, data, JNI_ABORT);
|
||||
WiFiSensorAndroid::get().handle(str);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
#endif
|
||||
@@ -40,7 +40,7 @@ public:
|
||||
void handle(const std::string& data) {
|
||||
|
||||
// to-be-constructed sensor data
|
||||
WiFiSensorData sensorData;
|
||||
WiFiMeasurements sensorData;
|
||||
|
||||
// parse each mac->rssi entry
|
||||
for (int i = 0; i < (int)data.length(); i += 17+1+2) {
|
||||
@@ -49,7 +49,7 @@ public:
|
||||
const int8_t pad1 = data[i+18];
|
||||
const int8_t pad2 = data[i+19];
|
||||
if (pad1 != 0 || pad2 != 0) {Debug::error("padding error within WiFi scan result");}
|
||||
sensorData.entries.push_back(WiFiSensorDataEntry(bssid, rssi));
|
||||
sensorData.entries.push_back(WiFiMeasurement(AccessPoint(bssid), rssi));
|
||||
}
|
||||
|
||||
// call listeners
|
||||
@@ -60,20 +60,7 @@ public:
|
||||
};
|
||||
|
||||
|
||||
extern "C" {
|
||||
|
||||
/** called after each successful WiFi scan */
|
||||
JNIEXPORT void JNICALL Java_indoor_java_WiFi_onScanComplete(JNIEnv* env, jobject jobj, jbyteArray arrayID) {
|
||||
(void) env; (void) jobj;
|
||||
jsize length = env->GetArrayLength(arrayID);
|
||||
jboolean isCopy;
|
||||
jbyte* data = env->GetByteArrayElements(arrayID, &isCopy);
|
||||
std::string str((char*)data, length);
|
||||
env->ReleaseByteArrayElements(arrayID, data, JNI_ABORT);
|
||||
WiFiSensorAndroid::get().handle(str);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
@@ -2,9 +2,17 @@
|
||||
#define ACCELEROMETERSENSORDUMMY_H
|
||||
|
||||
#include "../AccelerometerSensor.h"
|
||||
#include "RandomSensor.h"
|
||||
#include <random>
|
||||
|
||||
class AccelerometerSensorDummy : public AccelerometerSensor {
|
||||
class AccelerometerSensorDummy : public RandomSensor<AccelerometerData, AccelerometerSensor> {
|
||||
|
||||
private:
|
||||
|
||||
/** hidden ctor */
|
||||
AccelerometerSensorDummy() : RandomSensor(Timestamp::fromMS(10)) {
|
||||
;
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
@@ -14,13 +22,25 @@ public:
|
||||
return acc;
|
||||
}
|
||||
|
||||
void start() override {
|
||||
//throw "todo";
|
||||
protected:
|
||||
|
||||
std::minstd_rand gen;
|
||||
std::uniform_real_distribution<float> distNoise = std::uniform_real_distribution<float>(-0.5, +0.5);
|
||||
|
||||
AccelerometerData getRandomEntry() override {
|
||||
|
||||
const Timestamp ts = Timestamp::fromRunningTime();
|
||||
const float Hz = 1.6;
|
||||
const float intensity = 2.0;
|
||||
|
||||
const float x = distNoise(gen);
|
||||
const float y = distNoise(gen);
|
||||
const float z = 9.81 + std::sin(ts.sec()*2*M_PI*Hz) * intensity + distNoise(gen);
|
||||
|
||||
return AccelerometerData(x,y,z);
|
||||
|
||||
}
|
||||
|
||||
void stop() override {
|
||||
throw "todo";
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
43
sensors/dummy/BarometerSensorDummy.h
Normal file
@@ -0,0 +1,43 @@
|
||||
#ifndef BAROMETERSENSORDUMMY_H
|
||||
#define BAROMETERSENSORDUMMY_H
|
||||
|
||||
#include "../BarometerSensor.h"
|
||||
#include "RandomSensor.h"
|
||||
#include <random>
|
||||
|
||||
class BarometerSensorDummy : public RandomSensor<BarometerData, BarometerSensor> {
|
||||
|
||||
private:
|
||||
|
||||
std::thread thread;
|
||||
|
||||
/** hidden ctor */
|
||||
BarometerSensorDummy() : RandomSensor(Timestamp::fromMS(100)) {
|
||||
;
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
/** singleton access */
|
||||
static BarometerSensorDummy& get() {
|
||||
static BarometerSensorDummy baro;
|
||||
return baro;
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
std::minstd_rand gen;
|
||||
std::uniform_real_distribution<float> distNoise = std::uniform_real_distribution<float>(-0.09, +0.09);
|
||||
|
||||
BarometerData getRandomEntry() override {
|
||||
|
||||
const Timestamp ts = Timestamp::fromRunningTime();
|
||||
|
||||
const float hPa = 930 + std::sin(ts.sec()) * 0.5 + distNoise(gen);
|
||||
return BarometerData(hPa);
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // BAROMETERSENSORDUMMY_H
|
||||
48
sensors/dummy/GyroscopeSensorDummy.h
Normal file
@@ -0,0 +1,48 @@
|
||||
#ifndef GYROSCOPESENSORDUMMY_H
|
||||
#define GYROSCOPESENSORDUMMY_H
|
||||
|
||||
#include "../GyroscopeSensor.h"
|
||||
#include "RandomSensor.h"
|
||||
#include <random>
|
||||
|
||||
class GyroscopeSensorDummy : public RandomSensor<GyroscopeData, GyroscopeSensor> {
|
||||
|
||||
private:
|
||||
|
||||
/** hidden ctor */
|
||||
GyroscopeSensorDummy() : RandomSensor(Timestamp::fromMS(10)) {
|
||||
;
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
/** singleton access */
|
||||
static GyroscopeSensorDummy& get() {
|
||||
static GyroscopeSensorDummy gyro;
|
||||
return gyro;
|
||||
}
|
||||
|
||||
|
||||
protected:
|
||||
|
||||
std::minstd_rand gen;
|
||||
std::uniform_real_distribution<float> distNoise = std::uniform_real_distribution<float>(-0.1, +0.1);
|
||||
|
||||
GyroscopeData getRandomEntry() override {
|
||||
|
||||
const Timestamp ts = Timestamp::fromRunningTime();
|
||||
|
||||
const float Hz = 0.1;
|
||||
const float intensity = 0.35;
|
||||
|
||||
const float x = distNoise(gen);
|
||||
const float y = distNoise(gen);
|
||||
const float z = std::sin(ts.sec()*2*M_PI*Hz) * intensity + distNoise(gen);
|
||||
|
||||
return GyroscopeData(x,y,z);
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // GYROSCOPESENSORDUMMY_H
|
||||
56
sensors/dummy/RandomSensor.h
Normal file
@@ -0,0 +1,56 @@
|
||||
#ifndef RANDOMSENSOR_H
|
||||
#define RANDOMSENSOR_H
|
||||
|
||||
#include <thread>
|
||||
#include <Indoor/data/Timestamp.h>
|
||||
#include <Indoor/Assertions.h>
|
||||
|
||||
template <typename Element, typename BaseClass> class RandomSensor : public BaseClass {
|
||||
|
||||
private:
|
||||
|
||||
std::thread thread;
|
||||
bool running = false;
|
||||
Timestamp interval;
|
||||
|
||||
public:
|
||||
|
||||
RandomSensor(const Timestamp interval) : interval(interval) {
|
||||
;
|
||||
}
|
||||
|
||||
void start() override {
|
||||
Assert::isFalse(running, "sensor allready running!");
|
||||
running = true;
|
||||
thread = std::thread(&RandomSensor::run, this);
|
||||
}
|
||||
|
||||
void stop() override {
|
||||
Assert::isTrue(running, "sensor not yet running!");
|
||||
running = false;
|
||||
thread.join();
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
/** subclasses must provide a random entry here */
|
||||
virtual Element getRandomEntry() = 0;
|
||||
|
||||
private:
|
||||
|
||||
void run() {
|
||||
|
||||
while(running) {
|
||||
|
||||
const Element rnd = getRandomEntry();
|
||||
Sensor<Element>::informListeners(rnd);
|
||||
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(interval.ms()));
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // RANDOMSENSOR_H
|
||||
36
sensors/dummy/SensorFactoryDummy.h
Normal file
@@ -0,0 +1,36 @@
|
||||
#ifndef SENSORFACTORYDUMMY_H
|
||||
#define SENSORFACTORYDUMMY_H
|
||||
|
||||
#include "../SensorFactory.h"
|
||||
|
||||
#include "WiFiSensorDummy.h"
|
||||
#include "AccelerometerSensorDummy.h"
|
||||
#include "GyroscopeSensorDummy.h"
|
||||
#include "BarometerSensorDummy.h"
|
||||
|
||||
/**
|
||||
* sensor factory that provides sensors that fire dummy data
|
||||
*/
|
||||
class SensorFactoryDummy : public SensorFactory {
|
||||
|
||||
public:
|
||||
|
||||
WiFiSensor& getWiFi() override {
|
||||
return WiFiSensorDummy::get();
|
||||
}
|
||||
|
||||
AccelerometerSensor& getAccelerometer() override {
|
||||
return AccelerometerSensorDummy::get();
|
||||
}
|
||||
|
||||
GyroscopeSensor& getGyroscope() override {
|
||||
return GyroscopeSensorDummy::get();
|
||||
}
|
||||
|
||||
BarometerSensor& getBarometer() override {
|
||||
return BarometerSensorDummy::get();
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // SENSORFACTORYDUMMY_H
|
||||
@@ -54,6 +54,12 @@ private:
|
||||
aps.push_back(DummyAP("00:00:00:00:00:01", Point2(0, 0)));
|
||||
aps.push_back(DummyAP("00:00:00:00:00:02", Point2(20, 0)));
|
||||
aps.push_back(DummyAP("00:00:00:00:00:03", Point2(10, 20)));
|
||||
aps.push_back(DummyAP("00:00:00:00:00:04", Point2(10, 30)));
|
||||
aps.push_back(DummyAP("00:00:00:00:00:05", Point2(10, 40)));
|
||||
aps.push_back(DummyAP("00:00:00:00:00:06", Point2(10, 50)));
|
||||
aps.push_back(DummyAP("00:00:00:00:00:07", Point2(10, 60)));
|
||||
aps.push_back(DummyAP("00:00:00:00:00:08", Point2(10, 70)));
|
||||
aps.push_back(DummyAP("00:00:00:00:00:09", Point2(10, 80)));
|
||||
|
||||
float deg = 0;
|
||||
|
||||
@@ -73,11 +79,11 @@ private:
|
||||
const float y = cy + std::cos(deg) * rad;
|
||||
|
||||
// construct scan data
|
||||
WiFiSensorData scan;
|
||||
WiFiMeasurements scan;
|
||||
for (DummyAP& ap : aps) {
|
||||
const float dist = ap.pos.getDistance(Point2(x, y));
|
||||
const float rssi = LogDistanceModel::distanceToRssi(-40, 1.5, dist);
|
||||
scan.entries.push_back(WiFiSensorDataEntry(ap.mac, rssi));
|
||||
scan.entries.push_back(WiFiMeasurement(AccessPoint(ap.mac), rssi));
|
||||
}
|
||||
|
||||
// call
|
||||
|
||||
@@ -1,15 +1,38 @@
|
||||
#ifndef WIFISENSORLINUX_H
|
||||
#define WIFISENSORLINUX_H
|
||||
|
||||
#ifdef LINUX_DESKTOP
|
||||
|
||||
#include "../WiFiSensor.h"
|
||||
#include <thread>
|
||||
|
||||
extern "C" {
|
||||
#include "WiFiSensorLinuxC.h"
|
||||
}
|
||||
|
||||
class WiFiSensorLinux : public WiFiSensor {
|
||||
|
||||
private:
|
||||
|
||||
std::vector<uint32_t> freqs = {2412, 2417, 2422, 2427, 2432, 2437, 2442, 2447, 2452, 2457, 2462, 2467, 2472};
|
||||
bool running;
|
||||
std::thread thread;
|
||||
|
||||
int ifIdx;
|
||||
wifiState state;
|
||||
|
||||
private:
|
||||
|
||||
WiFiSensorLinux() {
|
||||
|
||||
ifIdx = wifiGetInterfaceIndex("wlp3s0");
|
||||
if (ifIdx == 0) {throw Exception("wifi interface not found!");}
|
||||
|
||||
int ret = wifiGetDriver(&state);
|
||||
if (ret != 0) {throw Exception("wifi driver not found!");}
|
||||
|
||||
std::cout << "if: " << ifIdx << std::endl;
|
||||
|
||||
}
|
||||
|
||||
public:
|
||||
@@ -21,13 +44,59 @@ public:
|
||||
}
|
||||
|
||||
void start() override {
|
||||
|
||||
running = true;
|
||||
thread = std::thread(&WiFiSensorLinux::run, this);
|
||||
}
|
||||
|
||||
void stop() override {
|
||||
running = false;
|
||||
thread.join();
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
void run() {
|
||||
|
||||
wifiScanResult result;
|
||||
wifiChannels channels;
|
||||
channels.frequencies = freqs.data();
|
||||
channels.numUsed = freqs.size();
|
||||
|
||||
|
||||
|
||||
while(running) {
|
||||
|
||||
int ret;
|
||||
|
||||
// trigger a scan
|
||||
ret = wifiTriggerScan(&state, ifIdx, &channels);
|
||||
if (ret != 0) {
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||
continue;
|
||||
}
|
||||
|
||||
// fetch scan result (blocks)
|
||||
ret = wifiGetScanResult(&state, ifIdx, &result);
|
||||
|
||||
// convert to our format
|
||||
const Timestamp ts = Timestamp::fromUnixTime();
|
||||
WiFiMeasurements data;
|
||||
|
||||
for (int i = 0; i < result.numUsed; ++i) {
|
||||
const std::string mac = result.entries[i].mac;
|
||||
const int rssi = result.entries[i].rssi;
|
||||
data.entries.push_back(WiFiMeasurement(AccessPoint(mac), rssi));
|
||||
}
|
||||
|
||||
// and call the listeners
|
||||
informListeners(ts, data);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
#endif // WIFISENSORLINUX_H
|
||||
|
||||
376
sensors/linux/WiFiSensorLinuxC.c
Normal file
@@ -0,0 +1,376 @@
|
||||
#ifdef LINUX_DESKTOP
|
||||
|
||||
#include "WiFiSensorLinuxC.h"
|
||||
|
||||
struct trigger_results {
|
||||
int done;
|
||||
int aborted;
|
||||
};
|
||||
|
||||
|
||||
struct handler_args { // For family_handler() and nl_get_multicast_id().
|
||||
const char *group;
|
||||
int id;
|
||||
};
|
||||
|
||||
|
||||
static int error_handler(struct sockaddr_nl *nla, struct nlmsgerr *err, void *arg) {
|
||||
// Callback for errors.
|
||||
printf("error_handler() called.\n");
|
||||
int *ret = (int*)arg;
|
||||
*ret = err->error;
|
||||
return NL_STOP;
|
||||
}
|
||||
|
||||
|
||||
static int finish_handler(struct nl_msg *msg, void *arg) {
|
||||
// Callback for NL_CB_FINISH.
|
||||
int *ret = (int*)arg;
|
||||
*ret = 0;
|
||||
return NL_SKIP;
|
||||
}
|
||||
|
||||
|
||||
static int ack_handler(struct nl_msg *msg, void *arg) {
|
||||
// Callback for NL_CB_ACK.
|
||||
int *ret = (int*)arg;
|
||||
*ret = 0;
|
||||
return NL_STOP;
|
||||
}
|
||||
|
||||
|
||||
static int no_seq_check(struct nl_msg *msg, void *arg) {
|
||||
// Callback for NL_CB_SEQ_CHECK.
|
||||
return NL_OK;
|
||||
}
|
||||
|
||||
|
||||
static int family_handler(struct nl_msg *msg, void *arg) {
|
||||
// Callback for NL_CB_VALID within nl_get_multicast_id(). From http://sourcecodebrowser.com/iw/0.9.14/genl_8c.html.
|
||||
struct handler_args *grp = arg;
|
||||
struct nlattr *tb[CTRL_ATTR_MAX + 1];
|
||||
struct genlmsghdr *gnlh = nlmsg_data(nlmsg_hdr(msg));
|
||||
struct nlattr *mcgrp;
|
||||
int rem_mcgrp;
|
||||
|
||||
nla_parse(tb, CTRL_ATTR_MAX, genlmsg_attrdata(gnlh, 0), genlmsg_attrlen(gnlh, 0), NULL);
|
||||
|
||||
if (!tb[CTRL_ATTR_MCAST_GROUPS]) return NL_SKIP;
|
||||
|
||||
nla_for_each_nested(mcgrp, tb[CTRL_ATTR_MCAST_GROUPS], rem_mcgrp) { // This is a loop.
|
||||
struct nlattr *tb_mcgrp[CTRL_ATTR_MCAST_GRP_MAX + 1];
|
||||
|
||||
nla_parse(tb_mcgrp, CTRL_ATTR_MCAST_GRP_MAX, nla_data(mcgrp), nla_len(mcgrp), NULL);
|
||||
|
||||
if (!tb_mcgrp[CTRL_ATTR_MCAST_GRP_NAME] || !tb_mcgrp[CTRL_ATTR_MCAST_GRP_ID]) continue;
|
||||
if (strncmp((const char*)nla_data(tb_mcgrp[CTRL_ATTR_MCAST_GRP_NAME]), grp->group,
|
||||
nla_len(tb_mcgrp[CTRL_ATTR_MCAST_GRP_NAME]))) {
|
||||
continue;
|
||||
}
|
||||
|
||||
grp->id = nla_get_u32(tb_mcgrp[CTRL_ATTR_MCAST_GRP_ID]);
|
||||
break;
|
||||
}
|
||||
|
||||
return NL_SKIP;
|
||||
}
|
||||
|
||||
|
||||
int nl_get_multicast_id(struct nl_sock *sock, const char *family, const char *group) {
|
||||
// From http://sourcecodebrowser.com/iw/0.9.14/genl_8c.html.
|
||||
struct nl_msg *msg;
|
||||
struct nl_cb *cb;
|
||||
int ret, ctrlid;
|
||||
struct handler_args grp = { .group = group, .id = -ENOENT, };
|
||||
|
||||
msg = nlmsg_alloc();
|
||||
if (!msg) return -ENOMEM;
|
||||
|
||||
cb = nl_cb_alloc(NL_CB_DEFAULT);
|
||||
if (!cb) {
|
||||
ret = -ENOMEM;
|
||||
goto out_fail_cb;
|
||||
}
|
||||
|
||||
ctrlid = genl_ctrl_resolve(sock, "nlctrl");
|
||||
|
||||
genlmsg_put(msg, 0, 0, ctrlid, 0, 0, CTRL_CMD_GETFAMILY, 0);
|
||||
|
||||
ret = -ENOBUFS;
|
||||
NLA_PUT_STRING(msg, CTRL_ATTR_FAMILY_NAME, family);
|
||||
|
||||
ret = nl_send_auto_complete(sock, msg);
|
||||
if (ret < 0) goto out;
|
||||
|
||||
ret = 1;
|
||||
|
||||
nl_cb_err(cb, NL_CB_CUSTOM, error_handler, &ret);
|
||||
nl_cb_set(cb, NL_CB_ACK, NL_CB_CUSTOM, ack_handler, &ret);
|
||||
nl_cb_set(cb, NL_CB_VALID, NL_CB_CUSTOM, family_handler, &grp);
|
||||
|
||||
while (ret > 0) nl_recvmsgs(sock, cb);
|
||||
|
||||
if (ret == 0) ret = grp.id;
|
||||
|
||||
nla_put_failure:
|
||||
out:
|
||||
nl_cb_put(cb);
|
||||
out_fail_cb:
|
||||
nlmsg_free(msg);
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
void mac_addr_n2a(char *mac_addr, unsigned char *arg) {
|
||||
// From http://git.kernel.org/cgit/linux/kernel/git/jberg/iw.git/tree/util.c.
|
||||
int i, l;
|
||||
|
||||
l = 0;
|
||||
for (i = 0; i < 6; i++) {
|
||||
if (i == 0) {
|
||||
sprintf(mac_addr+l, "%02x", arg[i]);
|
||||
l += 2;
|
||||
} else {
|
||||
sprintf(mac_addr+l, ":%02x", arg[i]);
|
||||
l += 3;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void print_ssid(unsigned char *ie, int ielen) {
|
||||
uint8_t len;
|
||||
uint8_t *data;
|
||||
int i;
|
||||
|
||||
while (ielen >= 2 && ielen >= ie[1]) {
|
||||
if (ie[0] == 0 && ie[1] >= 0 && ie[1] <= 32) {
|
||||
len = ie[1];
|
||||
data = ie + 2;
|
||||
for (i = 0; i < len; i++) {
|
||||
if (isprint(data[i]) && data[i] != ' ' && data[i] != '\\') printf("%c", data[i]);
|
||||
else if (data[i] == ' ' && (i != 0 && i != len -1)) printf(" ");
|
||||
else printf("\\x%.2x", data[i]);
|
||||
}
|
||||
break;
|
||||
}
|
||||
ielen -= ie[1] + 2;
|
||||
ie += ie[1] + 2;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static int callback_trigger(struct nl_msg *msg, void *arg) {
|
||||
// Called by the kernel when the scan is done or has been aborted.
|
||||
struct genlmsghdr *gnlh = nlmsg_data(nlmsg_hdr(msg));
|
||||
struct trigger_results *results = arg;
|
||||
|
||||
//printf("Got something.\n");
|
||||
//printf("%d\n", arg);
|
||||
//nl_msg_dump(msg, stdout);
|
||||
|
||||
if (gnlh->cmd == NL80211_CMD_SCAN_ABORTED) {
|
||||
printf("Got NL80211_CMD_SCAN_ABORTED.\n");
|
||||
results->done = 1;
|
||||
results->aborted = 1;
|
||||
} else if (gnlh->cmd == NL80211_CMD_NEW_SCAN_RESULTS) {
|
||||
printf("Got NL80211_CMD_NEW_SCAN_RESULTS.\n");
|
||||
results->done = 1;
|
||||
results->aborted = 0;
|
||||
} // else probably an uninteresting multicast message.
|
||||
|
||||
return NL_SKIP;
|
||||
}
|
||||
|
||||
// called by the kernel for each detected AP
|
||||
static int callback_dump(struct nl_msg *msg, void *arg) {
|
||||
|
||||
// user data
|
||||
struct wifiScanResult* res = arg;
|
||||
struct wifiScanResultEntry* entry = &(res->entries[res->numUsed]);
|
||||
++res->numUsed;
|
||||
|
||||
struct genlmsghdr *gnlh = nlmsg_data(nlmsg_hdr(msg));
|
||||
char mac_addr[20];
|
||||
struct nlattr *tb[NL80211_ATTR_MAX + 1];
|
||||
struct nlattr *bss[NL80211_BSS_MAX + 1];
|
||||
static struct nla_policy bss_policy[NL80211_BSS_MAX + 1] = {
|
||||
[NL80211_BSS_TSF] = { .type = NLA_U64 },
|
||||
[NL80211_BSS_FREQUENCY] = { .type = NLA_U32 },
|
||||
[NL80211_BSS_BSSID] = { },
|
||||
[NL80211_BSS_BEACON_INTERVAL] = { .type = NLA_U16 },
|
||||
[NL80211_BSS_CAPABILITY] = { .type = NLA_U16 },
|
||||
[NL80211_BSS_INFORMATION_ELEMENTS] = { },
|
||||
[NL80211_BSS_SIGNAL_MBM] = { .type = NLA_U32 },
|
||||
[NL80211_BSS_SIGNAL_UNSPEC] = { .type = NLA_U8 },
|
||||
[NL80211_BSS_STATUS] = { .type = NLA_U32 },
|
||||
[NL80211_BSS_SEEN_MS_AGO] = { .type = NLA_U32 },
|
||||
[NL80211_BSS_BEACON_IES] = { },
|
||||
};
|
||||
|
||||
// Parse and error check.
|
||||
nla_parse(tb, NL80211_ATTR_MAX, genlmsg_attrdata(gnlh, 0), genlmsg_attrlen(gnlh, 0), NULL);
|
||||
if (!tb[NL80211_ATTR_BSS]) {
|
||||
printf("bss info missing!\n");
|
||||
return NL_SKIP;
|
||||
}
|
||||
if (nla_parse_nested(bss, NL80211_BSS_MAX, tb[NL80211_ATTR_BSS], bss_policy)) {
|
||||
printf("failed to parse nested attributes!\n");
|
||||
return NL_SKIP;
|
||||
}
|
||||
if (!bss[NL80211_BSS_BSSID]) return NL_SKIP;
|
||||
if (!bss[NL80211_BSS_INFORMATION_ELEMENTS]) return NL_SKIP;
|
||||
|
||||
// signal-strength
|
||||
int mBm = nla_get_s32(bss[NL80211_BSS_SIGNAL_MBM]);
|
||||
entry->rssi = mBm / 100;
|
||||
|
||||
// mac-address
|
||||
mac_addr_n2a(entry->mac, (unsigned char*)nla_data(bss[NL80211_BSS_BSSID]));
|
||||
|
||||
// Start printing.
|
||||
// mac_addr_n2a(mac_addr, (unsigned char*)nla_data(bss[NL80211_BSS_BSSID]));
|
||||
// printf("%s, ", mac_addr);
|
||||
// printf("%d MHz, ", nla_get_u32(bss[NL80211_BSS_FREQUENCY]));
|
||||
// print_ssid((unsigned char*)nla_data(bss[NL80211_BSS_INFORMATION_ELEMENTS]), nla_len(bss[NL80211_BSS_INFORMATION_ELEMENTS]));
|
||||
// printf("%f dB", mBm/100.0f);
|
||||
// printf("\n");
|
||||
|
||||
return NL_SKIP;
|
||||
}
|
||||
|
||||
|
||||
|
||||
int wifiGetDriver(struct wifiState* state) {
|
||||
|
||||
// open nl80211 socket to kernel.
|
||||
state->socket = nl_socket_alloc();
|
||||
genl_connect(state->socket);
|
||||
|
||||
state->mcid = nl_get_multicast_id(state->socket, "nl80211", "scan");
|
||||
nl_socket_add_membership(state->socket, state->mcid); // Without this, callback_trigger() won't be called.
|
||||
|
||||
state->driverID = genl_ctrl_resolve(state->socket, "nl80211");
|
||||
|
||||
return 0;
|
||||
|
||||
}
|
||||
|
||||
int wifiCleanup(struct wifiState* state) {
|
||||
|
||||
nl_socket_drop_membership(state->socket, state->mcid); // No longer need this.
|
||||
nl_socket_free(state->socket);
|
||||
|
||||
}
|
||||
|
||||
int wifiGetScanResult(struct wifiState* state, int interfaceIndex, struct wifiScanResult* res) {
|
||||
|
||||
// reset the result. very important!
|
||||
res->numUsed = 0;
|
||||
|
||||
// new message
|
||||
struct nl_msg *msg = nlmsg_alloc();
|
||||
|
||||
// configure message
|
||||
genlmsg_put(msg, 0, 0, state->driverID, 0, NLM_F_DUMP, NL80211_CMD_GET_SCAN, 0);
|
||||
nla_put_u32(msg, NL80211_ATTR_IFINDEX, interfaceIndex);
|
||||
|
||||
// add the to-be-called function for each detected AP
|
||||
nl_socket_modify_cb(state->socket, NL_CB_VALID, NL_CB_CUSTOM, callback_dump, res);
|
||||
|
||||
// send
|
||||
int ret = nl_send_auto(state->socket, msg);
|
||||
printf("NL80211_CMD_GET_SCAN sent %d bytes to the kernel.\n", ret);
|
||||
|
||||
// get answer (potential error-code)
|
||||
ret = nl_recvmsgs_default(state->socket);
|
||||
nlmsg_free(msg);
|
||||
if (ret < 0) { printf("ERROR: nl_recvmsgs_default() returned %d (%s).\n", ret, nl_geterror(-ret)); return ret; }
|
||||
|
||||
}
|
||||
|
||||
int wifiTriggerScan(struct wifiState* state, int interfaceIndex, struct wifiChannels* channels) {
|
||||
|
||||
// Starts the scan and waits for it to finish. Does not return until the scan is done or has been aborted.
|
||||
struct trigger_results results = { .done = 0, .aborted = 0 };
|
||||
struct nl_msg *msg;
|
||||
struct nl_cb *cb;
|
||||
struct nl_msg *freqs_to_scan;
|
||||
int err;
|
||||
int ret;
|
||||
|
||||
// Allocate the messages and callback handler.
|
||||
msg = nlmsg_alloc();
|
||||
if (!msg) {
|
||||
printf("ERROR: Failed to allocate netlink message for msg.\n");
|
||||
return -ENOMEM;
|
||||
}
|
||||
freqs_to_scan = nlmsg_alloc();
|
||||
if (!freqs_to_scan) {
|
||||
printf("ERROR: Failed to allocate netlink message for ssids_to_scan.\n");
|
||||
nlmsg_free(msg);
|
||||
return -ENOMEM;
|
||||
}
|
||||
cb = nl_cb_alloc(NL_CB_DEFAULT);
|
||||
if (!cb) {
|
||||
printf("ERROR: Failed to allocate netlink callbacks.\n");
|
||||
nlmsg_free(msg);
|
||||
nlmsg_free(freqs_to_scan);
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
// Setup the messages and callback handler.
|
||||
genlmsg_put(msg, 0, 0, state->driverID, 0, 0, NL80211_CMD_TRIGGER_SCAN, 0); // Setup which command to run.
|
||||
nla_put_u32(msg, NL80211_ATTR_IFINDEX, interfaceIndex); // Add message attribute, which interface to use.
|
||||
|
||||
|
||||
// limit to-be-scanned channels?
|
||||
if (channels->numUsed > 0) {
|
||||
for (int i = 0; i < channels->numUsed; ++i) { nla_put_u32(freqs_to_scan, 0, channels->frequencies[i]); }
|
||||
nla_put_nested(msg, NL80211_ATTR_SCAN_FREQUENCIES, freqs_to_scan);
|
||||
}
|
||||
nlmsg_free(freqs_to_scan);
|
||||
|
||||
|
||||
|
||||
nl_cb_set(cb, NL_CB_VALID, NL_CB_CUSTOM, callback_trigger, &results); // Add the callback.
|
||||
nl_cb_err(cb, NL_CB_CUSTOM, error_handler, &err);
|
||||
nl_cb_set(cb, NL_CB_FINISH, NL_CB_CUSTOM, finish_handler, &err);
|
||||
nl_cb_set(cb, NL_CB_ACK, NL_CB_CUSTOM, ack_handler, &err);
|
||||
nl_cb_set(cb, NL_CB_SEQ_CHECK, NL_CB_CUSTOM, no_seq_check, NULL); // No sequence checking for multicast messages.
|
||||
|
||||
// Send NL80211_CMD_TRIGGER_SCAN to start the scan. The kernel may reply with NL80211_CMD_NEW_SCAN_RESULTS on
|
||||
// success or NL80211_CMD_SCAN_ABORTED if another scan was started by another process.
|
||||
err = 1;
|
||||
ret = nl_send_auto(state->socket, msg); // Send the message.
|
||||
printf("NL80211_CMD_TRIGGER_SCAN sent %d bytes to the kernel.\n", ret);
|
||||
printf("Waiting for scan to complete...\n");
|
||||
while (err > 0) ret = nl_recvmsgs(state->socket, cb); // First wait for ack_handler(). This helps with basic errors.
|
||||
if (err < 0) {
|
||||
printf("WARNING: err has a value of %d.\n", err);
|
||||
}
|
||||
if (ret < 0) {
|
||||
printf("ERROR: nl_recvmsgs() returned %d (%s).\n", ret, nl_geterror(-ret));
|
||||
return ret;
|
||||
}
|
||||
while (!results.done) nl_recvmsgs(state->socket, cb); // Now wait until the scan is done or aborted.
|
||||
if (results.aborted) {
|
||||
printf("ERROR: Kernel aborted scan.\n");
|
||||
return 1;
|
||||
}
|
||||
printf("Scan is done.\n");
|
||||
|
||||
// Cleanup.
|
||||
nlmsg_free(msg);
|
||||
nl_cb_put(cb);
|
||||
|
||||
return 0;
|
||||
|
||||
}
|
||||
|
||||
int wifiGetInterfaceIndex(const char *name) {
|
||||
return if_nametoindex(name);
|
||||
}
|
||||
|
||||
|
||||
#endif
|
||||
49
sensors/linux/WiFiSensorLinuxC.h
Normal file
@@ -0,0 +1,49 @@
|
||||
#ifndef WIFISENSORLINUXC_H
|
||||
#define WIFISENSORLINUXC_H
|
||||
|
||||
#ifdef LINUX_DESKTOP
|
||||
|
||||
#include <errno.h>
|
||||
#include <netlink/errno.h>
|
||||
#include <netlink/netlink.h>
|
||||
#include <netlink/genl/genl.h>
|
||||
#include <netlink/genl/ctrl.h>
|
||||
#include <linux/nl80211.h>
|
||||
#include <net/if.h>
|
||||
|
||||
struct wifiChannels {
|
||||
uint32_t* frequencies; // array of frequencies
|
||||
uint32_t numUsed; // number of array elements
|
||||
};
|
||||
|
||||
struct wifiScanResultEntry {
|
||||
char mac[17];
|
||||
int rssi;
|
||||
};
|
||||
|
||||
struct wifiScanResult {
|
||||
struct wifiScanResultEntry entries[128];
|
||||
int numUsed;
|
||||
};
|
||||
|
||||
struct wifiState {
|
||||
struct nl_sock* socket;
|
||||
int driverID;
|
||||
int mcid;
|
||||
};
|
||||
|
||||
/** get the driver used for scanning */
|
||||
int wifiGetDriver(struct wifiState* state);
|
||||
|
||||
/** convert interface name to index number. 0 if interface is not present */
|
||||
int wifiGetInterfaceIndex(const char* name);
|
||||
|
||||
/** trigger a scan on the given channels / the provided interface */
|
||||
int wifiTriggerScan(struct wifiState* state, int interfaceIndex, struct wifiChannels* channels);
|
||||
|
||||
/** blocking get the result of a triggered scan */
|
||||
int wifiGetScanResult(struct wifiState* state, int interfaceIndex, struct wifiScanResult* res);
|
||||
|
||||
#ifdef LINUX_DESKTOP
|
||||
|
||||
#endif // WIFISENSORLINUXC_H
|
||||
110
sensors/offline/AllInOneSensor.h
Normal file
@@ -0,0 +1,110 @@
|
||||
#ifndef ALLINONESENSOR_H
|
||||
#define ALLINONESENSOR_H
|
||||
|
||||
#include "Settings.h"
|
||||
#include <string>
|
||||
#include "../WiFiSensor.h"
|
||||
#include "../AccelerometerSensor.h"
|
||||
#include "../GyroscopeSensor.h"
|
||||
#include "../BarometerSensor.h"
|
||||
#include <Indoor/sensors/offline/OfflineAndroid.h>
|
||||
|
||||
class AllInOneSensor :
|
||||
public WiFiSensor, public AccelerometerSensor, public GyroscopeSensor, public BarometerSensor,
|
||||
public OfflineAndroidListener {
|
||||
|
||||
private:
|
||||
|
||||
std::string file;
|
||||
bool running = false;
|
||||
std::thread thread;
|
||||
|
||||
public:
|
||||
|
||||
AllInOneSensor(const std::string& file) : file(file) {
|
||||
;
|
||||
}
|
||||
|
||||
void start() {
|
||||
if (running) {return;}
|
||||
running = true;
|
||||
thread = std::thread(&AllInOneSensor::run, this);
|
||||
}
|
||||
|
||||
void stop() {
|
||||
if (!running) {return;}
|
||||
running = false;
|
||||
thread.join();
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
virtual void onGyroscope(const Timestamp _ts, const GyroscopeData data) override {
|
||||
const Timestamp ts = relativeTS(_ts);
|
||||
handbrake(ts);
|
||||
GyroscopeSensor::informListeners(ts, data);
|
||||
}
|
||||
|
||||
virtual void onAccelerometer(const Timestamp _ts, const AccelerometerData data) override {
|
||||
const Timestamp ts = relativeTS(_ts);
|
||||
handbrake(ts);
|
||||
AccelerometerSensor::informListeners(ts, data);
|
||||
}
|
||||
|
||||
virtual void onGravity(const Timestamp ts, const AccelerometerData data) override {
|
||||
(void) ts;
|
||||
(void) data;
|
||||
}
|
||||
|
||||
virtual void onWiFi(const Timestamp _ts, const WiFiMeasurements data) override {
|
||||
const Timestamp ts = relativeTS(_ts);
|
||||
handbrake(ts);
|
||||
WiFiMeasurements copy = data;
|
||||
for (WiFiMeasurement& m : copy.entries) {m.ts = ts;} // make each timestmap also relative
|
||||
WiFiSensor::informListeners(ts, copy);
|
||||
}
|
||||
|
||||
virtual void onBarometer(const Timestamp _ts, const BarometerData data) override {
|
||||
const Timestamp ts = relativeTS(_ts);
|
||||
handbrake(ts);
|
||||
BarometerSensor::informListeners(ts, data);
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
Timestamp baseTS;
|
||||
Timestamp relativeTS(const Timestamp ts) {
|
||||
if (baseTS.isZero()) {baseTS = ts;}
|
||||
return ts - baseTS;
|
||||
}
|
||||
|
||||
/** handbrake for the offline-parser to ensure realtime events */
|
||||
Timestamp startSensorTS;
|
||||
Timestamp startSystemTS;
|
||||
|
||||
void handbrake(const Timestamp ts) {
|
||||
if (startSensorTS.isZero()) {startSensorTS = ts;}
|
||||
if (startSystemTS.isZero()) {startSystemTS = Timestamp::fromUnixTime();}
|
||||
const Timestamp runtimeOfflineData = ts - startSensorTS;;
|
||||
const Timestamp runtimeSystemTime = (Timestamp::fromUnixTime() - startSystemTS) * Settings::offlineSensorSpeedup;
|
||||
const Timestamp diff = (runtimeOfflineData - runtimeSystemTime);
|
||||
if (diff > Timestamp::fromMS(0)) {
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(diff.ms()));
|
||||
}
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
/**
|
||||
* file-parsing runs in a background thread
|
||||
* the parsing is manually slowed down via handbrake()
|
||||
* which blocks during the event callbacks
|
||||
*/
|
||||
void run() {
|
||||
OfflineAndroid parser;
|
||||
parser.parse(file, this);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // ALLINONESENSOR_H
|
||||
43
sensors/offline/SensorFactoryOffline.h
Normal file
@@ -0,0 +1,43 @@
|
||||
#ifndef SENSORFACTORYOFFLINE_H
|
||||
#define SENSORFACTORYOFFLINE_H
|
||||
|
||||
#include <thread>
|
||||
|
||||
#include "../SensorFactory.h"
|
||||
#include "AllInOneSensor.h"
|
||||
#include <Indoor/sensors/offline/OfflineAndroid.h>
|
||||
|
||||
/**
|
||||
* factory class that provides sensors that fire events from offline data
|
||||
*/
|
||||
class SensorFactoryOffline : public SensorFactory {
|
||||
|
||||
private:
|
||||
|
||||
AllInOneSensor allInOne;
|
||||
|
||||
public:
|
||||
|
||||
SensorFactoryOffline(const std::string& file) : allInOne(file) {
|
||||
;
|
||||
}
|
||||
|
||||
WiFiSensor& getWiFi() override {
|
||||
return allInOne;
|
||||
}
|
||||
|
||||
AccelerometerSensor& getAccelerometer() override {
|
||||
return allInOne;
|
||||
}
|
||||
|
||||
GyroscopeSensor& getGyroscope() override {
|
||||
return allInOne;
|
||||
}
|
||||
|
||||
BarometerSensor& getBarometer() override {
|
||||
return allInOne;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // SENSORFACTORYOFFLINE_H
|
||||
90
ui/Icons.h
Normal file
@@ -0,0 +1,90 @@
|
||||
#ifndef ICONS_H
|
||||
#define ICONS_H
|
||||
|
||||
#include "../misc/fixc11.h"
|
||||
|
||||
#include <QIcon>
|
||||
#include <QImage>
|
||||
#include <QPainter>
|
||||
#include <QRgb>
|
||||
|
||||
#include <QtSvg/QSvgRenderer>
|
||||
|
||||
#include <unordered_map>
|
||||
|
||||
class Icons {
|
||||
|
||||
public:
|
||||
|
||||
|
||||
static const QPixmap& getPixmap(const std::string& name, const int size = 32) {
|
||||
|
||||
// caching
|
||||
static std::unordered_map<std::string, QPixmap> cache;
|
||||
|
||||
// try to get the image from the cache
|
||||
const std::string cacheKey = std::to_string(size) + name;
|
||||
auto it = cache.find(cacheKey);
|
||||
|
||||
// not in cache?
|
||||
if (it == cache.end()) {
|
||||
|
||||
// build
|
||||
const QColor fill = Qt::transparent;
|
||||
const std::string file = "://res/icons/" + name + ".svg";
|
||||
QSvgRenderer renderer(QString(file.c_str()));
|
||||
QPixmap pm(size, size);
|
||||
pm.fill(fill);
|
||||
QPainter painter(&pm);
|
||||
renderer.render(&painter, pm.rect());
|
||||
|
||||
// add to cache
|
||||
cache[cacheKey] = pm;
|
||||
|
||||
}
|
||||
|
||||
// done
|
||||
return cache[cacheKey];
|
||||
|
||||
}
|
||||
|
||||
static const QPixmap& getPixmapColored(const std::string& name, const QColor color, const int size = 32) {
|
||||
|
||||
// caching
|
||||
static std::unordered_map<std::string, QPixmap> cache;
|
||||
|
||||
// try to get the image from the cache
|
||||
const QString hex = color.name();
|
||||
const std::string cacheKey = hex.toStdString() + "_" + std::to_string(size) + "_" + name;
|
||||
auto it = cache.find(cacheKey);
|
||||
|
||||
// not in cache?
|
||||
if (it == cache.end()) {
|
||||
|
||||
// copy
|
||||
QPixmap colored = getPixmap(name, size);
|
||||
QPainter painter(&colored);
|
||||
painter.setCompositionMode(QPainter::CompositionMode_SourceIn);
|
||||
painter.fillRect(colored.rect(), color);
|
||||
painter.end();
|
||||
|
||||
// add to cache
|
||||
cache[cacheKey] = colored;
|
||||
|
||||
}
|
||||
|
||||
// done
|
||||
return cache[cacheKey];
|
||||
|
||||
}
|
||||
|
||||
static QIcon getIcon(const std::string& name, const int size = 32) {
|
||||
|
||||
return QIcon(getPixmap(name, size));
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
#endif // ICONS_H
|
||||
35
ui/MainWindow.cpp
Normal file
@@ -0,0 +1,35 @@
|
||||
#include "MainWindow.h"
|
||||
|
||||
#include <QResizeEvent>
|
||||
|
||||
#include "map/MapView.h"
|
||||
#include "menu/MainMenu.h"
|
||||
#include "debug/SensorDataWidget.h"
|
||||
|
||||
|
||||
MainWindow::MainWindow(QWidget *parent) : QWidget(parent) {
|
||||
|
||||
setMinimumHeight(500);
|
||||
setMinimumWidth(500);
|
||||
|
||||
mapView = new MapView(this);
|
||||
mainMenu = new MainMenu(this);
|
||||
sensorWidget = new SensorDataWidget(this);
|
||||
|
||||
//sensorWidget->setVisible(false);
|
||||
showMaximized();
|
||||
|
||||
}
|
||||
|
||||
void MainWindow::resizeEvent(QResizeEvent* event) {
|
||||
|
||||
const int w = event->size().width();
|
||||
const int h = event->size().height();
|
||||
|
||||
mapView->setGeometry(0,0,w,h);
|
||||
mainMenu->setGeometry(0,0,w,64);
|
||||
sensorWidget->setGeometry(0,64,w,h-64);
|
||||
|
||||
}
|
||||
|
||||
|
||||
43
ui/MainWindow.h
Normal file
@@ -0,0 +1,43 @@
|
||||
#ifndef MAINWINDOW_H
|
||||
#define MAINWINDOW_H
|
||||
|
||||
#include <QWidget>
|
||||
|
||||
class MapView;
|
||||
class MainMenu;
|
||||
class SensorDataWidget;
|
||||
|
||||
class MainWindow : public QWidget {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
|
||||
/** ctor */
|
||||
explicit MainWindow(QWidget *parent = 0);
|
||||
|
||||
private:
|
||||
|
||||
MapView* mapView = nullptr;
|
||||
MainMenu* mainMenu = nullptr;
|
||||
SensorDataWidget* sensorWidget = nullptr;
|
||||
|
||||
public:
|
||||
|
||||
MapView* getMapView() const {return mapView;}
|
||||
MainMenu* getMainMenu() const {return mainMenu;}
|
||||
SensorDataWidget* getSensorDataWidget() const {return sensorWidget;}
|
||||
|
||||
|
||||
// void setMapView(QWidget* widget) {mapView = widget; mapView->setParent(this);}
|
||||
// void setMainMenu(QWidget* widget) {mainMenu = widget; mainMenu->setParent(this);}
|
||||
// void setSensorWidget(QWidget* widget) {sensorWidget = widget; sensorWidget->setParent(this);}
|
||||
|
||||
signals:
|
||||
|
||||
public slots:
|
||||
|
||||
void resizeEvent(QResizeEvent* event);
|
||||
|
||||
};
|
||||
|
||||
#endif // MAINWINDOW_H
|
||||
49
ui/debug/PlotTurns.cpp
Normal file
@@ -0,0 +1,49 @@
|
||||
#include "PlotTurns.h"
|
||||
#include <QPainter>
|
||||
|
||||
PlotTurns::PlotTurns(QWidget *parent) : QWidget(parent) {
|
||||
|
||||
setMinimumWidth(96);
|
||||
setMinimumHeight(96);
|
||||
|
||||
resize(96, 96);
|
||||
|
||||
// setMaximumWidth(64);
|
||||
// setMaximumHeight(64);
|
||||
|
||||
}
|
||||
|
||||
void PlotTurns::add(const Timestamp ts, const TurnData& data) {
|
||||
(void) ts;
|
||||
this->data = data;
|
||||
static int i = 0;
|
||||
if (++i % 4 == 0) {
|
||||
QMetaObject::invokeMethod(this, "update", Qt::QueuedConnection);
|
||||
}
|
||||
}
|
||||
|
||||
void PlotTurns::paintEvent(QPaintEvent* evt) {
|
||||
|
||||
(void) evt;
|
||||
QPainter p(this);
|
||||
|
||||
const float s = std::min(width(), height());
|
||||
const float s1 = s / 1.9;
|
||||
|
||||
const float cx = width() / 2;
|
||||
const float cy = height() / 2;
|
||||
|
||||
const float x1 = cx + std::cos(data.radSinceStart-M_PI_2) * s1;
|
||||
const float y1 = cy + std::sin(data.radSinceStart-M_PI_2) * s1;
|
||||
|
||||
p.fillRect(0,0,width(),height(),QColor(255,255,255,192));
|
||||
p.setPen(Qt::black);
|
||||
p.drawRect(0,0,width()-1,height()-1);
|
||||
|
||||
const QPen pen(Qt::black, 2);
|
||||
p.setPen(pen);
|
||||
p.drawLine(cx, cy, x1, y1);
|
||||
|
||||
p.end();
|
||||
|
||||
}
|
||||
30
ui/debug/PlotTurns.h
Normal file
@@ -0,0 +1,30 @@
|
||||
#ifndef PLOTTURNS_H
|
||||
#define PLOTTURNS_H
|
||||
|
||||
#include <QWidget>
|
||||
#include "../sensors/TurnSensor.h"
|
||||
#include <Indoor/data/Timestamp.h>
|
||||
|
||||
class PlotTurns : public QWidget {
|
||||
|
||||
Q_OBJECT
|
||||
|
||||
private:
|
||||
|
||||
TurnData data;
|
||||
|
||||
public:
|
||||
|
||||
explicit PlotTurns(QWidget *parent = 0);
|
||||
|
||||
void add(const Timestamp ts, const TurnData& data);
|
||||
|
||||
signals:
|
||||
|
||||
public slots:
|
||||
|
||||
void paintEvent(QPaintEvent*);
|
||||
|
||||
};
|
||||
|
||||
#endif // PLOTTURNS_H
|
||||
53
ui/debug/PlotWiFiScan.cpp
Normal file
@@ -0,0 +1,53 @@
|
||||
#include "../misc/fixc11.h"
|
||||
#include "PlotWiFiScan.h"
|
||||
|
||||
#include <QPainter>
|
||||
#include <QStaticText>
|
||||
|
||||
PlotWiFiScan::PlotWiFiScan(QWidget *parent) : QWidget(parent) {
|
||||
|
||||
setMinimumWidth(96);
|
||||
setMinimumHeight(96);
|
||||
|
||||
//setAutoFillBackground(false);
|
||||
|
||||
}
|
||||
|
||||
void PlotWiFiScan::add(const Timestamp ts, const WiFiMeasurements& data) {
|
||||
(void) ts;
|
||||
this->data = data;
|
||||
QMetaObject::invokeMethod(this, "update", Qt::QueuedConnection);
|
||||
}
|
||||
|
||||
void PlotWiFiScan::paintEvent(QPaintEvent* evt) {
|
||||
|
||||
(void) evt;
|
||||
QPainter p(this);
|
||||
|
||||
const int x0 = 4; const int xw = 150;
|
||||
const int y0 = 3;
|
||||
const int lh = 13;
|
||||
|
||||
int x = x0;
|
||||
int y = y0;
|
||||
|
||||
|
||||
p.fillRect(0,0,width(),height(),QColor(255,255,255,192));
|
||||
p.setPen(Qt::black);
|
||||
p.drawRect(0,0,width()-1,height()-1);
|
||||
|
||||
const QFont font("Arial", 9);
|
||||
p.setFont(font);
|
||||
p.setPen(Qt::black);
|
||||
|
||||
for (const WiFiMeasurement& m : data.entries) {
|
||||
const std::string& mac = m.getAP().getMAC().asString();
|
||||
std::string str = mac + ": " + std::to_string((int)m.getRSSI());
|
||||
p.drawStaticText(x, y, QStaticText(str.c_str()));
|
||||
y += lh;
|
||||
if (y > 90) {y = y0; x += xw;}
|
||||
}
|
||||
|
||||
p.end();
|
||||
|
||||
}
|
||||
30
ui/debug/PlotWiFiScan.h
Normal file
@@ -0,0 +1,30 @@
|
||||
#ifndef PLOTWIFISCAN_H
|
||||
#define PLOTWIFISCAN_H
|
||||
|
||||
#include <QWidget>
|
||||
#include "../sensors/WiFiSensor.h"
|
||||
|
||||
class PlotWiFiScan : public QWidget {
|
||||
|
||||
Q_OBJECT
|
||||
|
||||
private:
|
||||
|
||||
WiFiMeasurements data;
|
||||
|
||||
public:
|
||||
|
||||
/** ctor */
|
||||
explicit PlotWiFiScan(QWidget *parent = 0);
|
||||
|
||||
void add(const Timestamp ts, const WiFiMeasurements& data);
|
||||
|
||||
signals:
|
||||
|
||||
public slots:
|
||||
|
||||
void paintEvent(QPaintEvent*);
|
||||
|
||||
};
|
||||
|
||||
#endif // PLOTWIFISCAN_H
|
||||
217
ui/debug/SensorDataWidget.cpp
Normal file
@@ -0,0 +1,217 @@
|
||||
#include "../misc/fixc11.h"
|
||||
#include "SensorDataWidget.h"
|
||||
|
||||
#include "plot/PlottWidget.h"
|
||||
#include <QGridLayout>
|
||||
#include <QColor>
|
||||
|
||||
#include "../sensors/SensorFactory.h"
|
||||
#include "PlotTurns.h"
|
||||
#include "PlotWiFiScan.h"
|
||||
|
||||
|
||||
template <typename Data> void removeOld(Data& data, const Timestamp limit) {
|
||||
if (data.size() < 2) {return;}
|
||||
while ( (data.back().key - data.front().key) > limit.ms()) {
|
||||
data.remove(0);
|
||||
}
|
||||
}
|
||||
|
||||
template <int num> class PlotXLines : public PlotWidget {
|
||||
|
||||
protected:
|
||||
|
||||
QColor colors[4] = {QColor(255,0,0), QColor(0,192,0), QColor(0,0,255), QColor(0,0,0)};
|
||||
LinePlot line[num];
|
||||
|
||||
public:
|
||||
|
||||
PlotXLines(QWidget* parent) : PlotWidget(parent) {
|
||||
for (int i = 0; i < num; ++i) {
|
||||
pc.addPlot(&line[i]);
|
||||
line[i].setColor(colors[i]);
|
||||
}
|
||||
}
|
||||
|
||||
void addLineNode(const Timestamp ts, const float y, const int idx) {
|
||||
LinePlot& lp = line[idx];
|
||||
lp.getData().add(ts.ms(), y);
|
||||
}
|
||||
|
||||
Timestamp lastRefresh;
|
||||
bool needsRefresh(const Timestamp ts) {
|
||||
const Timestamp diff = ts - lastRefresh;
|
||||
return (diff > Timestamp::fromMS(100));
|
||||
}
|
||||
|
||||
|
||||
void refresh(const Timestamp ts) {
|
||||
|
||||
// ensure event from main-thread using queued-connection
|
||||
QMetaObject::invokeMethod(this, "update", Qt::QueuedConnection);
|
||||
|
||||
lastRefresh = ts;
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
class PlotAcc : public PlotXLines<3> {
|
||||
|
||||
protected:
|
||||
|
||||
PointPlot steps;
|
||||
|
||||
public:
|
||||
|
||||
PlotAcc(QWidget* parent) : PlotXLines(parent) {
|
||||
steps.setColor(colors[2]);
|
||||
steps.setPointSize(8);
|
||||
pc.addPlot(&steps);
|
||||
const float s = 4.2;
|
||||
const float ref = 9.81;
|
||||
pc.setValRange(Range(ref-s, ref+s));
|
||||
}
|
||||
|
||||
void addStep(const Timestamp ts) {
|
||||
steps.getData().add(ts.ms(), 9.81);
|
||||
}
|
||||
|
||||
void add(const Timestamp ts, const AccelerometerData& data) {
|
||||
addLineNode(ts, data.x, 0);
|
||||
addLineNode(ts, data.y, 1);
|
||||
addLineNode(ts, data.z, 2);
|
||||
if (needsRefresh(ts)) {
|
||||
limit();
|
||||
refresh(ts);
|
||||
}
|
||||
}
|
||||
|
||||
void limit() {
|
||||
const Timestamp limit = Timestamp::fromMS(3000);
|
||||
removeOld(line[0].getData(), limit);
|
||||
removeOld(line[1].getData(), limit);
|
||||
removeOld(line[2].getData(), limit);
|
||||
removeOld(steps.getData(), limit - Timestamp::fromMS(100)); // remove steps a little before. prevents errors
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
class PlotGyro : public PlotXLines<3> {
|
||||
|
||||
public:
|
||||
|
||||
PlotGyro(QWidget* parent) : PlotXLines(parent) {
|
||||
const float s = 1;
|
||||
const float ref = 0;
|
||||
pc.setValRange(Range(ref-s, ref+s));
|
||||
}
|
||||
|
||||
void add(const Timestamp ts, const GyroscopeData& data) {
|
||||
addLineNode(ts, data.x, 0);
|
||||
addLineNode(ts, data.y, 1);
|
||||
addLineNode(ts, data.z, 2);
|
||||
if (needsRefresh(ts)) {
|
||||
limit();
|
||||
refresh(ts);
|
||||
}
|
||||
}
|
||||
|
||||
void limit() {
|
||||
const Timestamp limit = Timestamp::fromMS(3000);
|
||||
removeOld(line[0].getData(), limit);
|
||||
removeOld(line[1].getData(), limit);
|
||||
removeOld(line[2].getData(), limit);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
class PlotBaro : public PlotXLines<1> {
|
||||
|
||||
public:
|
||||
|
||||
PlotBaro(QWidget* parent) : PlotXLines(parent) {
|
||||
|
||||
}
|
||||
|
||||
void add(const Timestamp ts, const BarometerData& data) {
|
||||
addLineNode(ts, data.hPa, 0);
|
||||
if (needsRefresh(ts)) {
|
||||
limit();
|
||||
refresh(ts);
|
||||
}
|
||||
const float s = 0.5;
|
||||
const float ref = line[0].getData().front().val;
|
||||
pc.setValRange(Range(ref-s, ref+s));
|
||||
}
|
||||
|
||||
void limit() {
|
||||
removeOld(line[0].getData(), Timestamp::fromMS(8000));
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
class PlotTurn : public QWidget {
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
SensorDataWidget::SensorDataWidget(QWidget* parent) : QWidget(parent) {
|
||||
|
||||
QGridLayout* lay = new QGridLayout(this);
|
||||
|
||||
plotGyro = new PlotGyro(this);
|
||||
plotAcc = new PlotAcc(this);
|
||||
plotBaro = new PlotBaro(this);
|
||||
plotTurn = new PlotTurns(this);
|
||||
plotWiFi = new PlotWiFiScan(this);
|
||||
|
||||
lay->addWidget(plotGyro, 0, 0, 1, 4, Qt::AlignTop);
|
||||
lay->addWidget(plotAcc, 1, 0, 1, 4, Qt::AlignTop);
|
||||
lay->addWidget(plotBaro, 2, 0, 1, 4, Qt::AlignTop);
|
||||
lay->addWidget(plotTurn, 3, 0, 1, 1, Qt::AlignTop);
|
||||
lay->addWidget(plotWiFi, 3, 1, 1, 3, Qt::AlignTop);
|
||||
|
||||
SensorFactory::get().getAccelerometer().addListener(this);
|
||||
SensorFactory::get().getGyroscope().addListener(this);
|
||||
SensorFactory::get().getBarometer().addListener(this);
|
||||
SensorFactory::get().getSteps().addListener(this);
|
||||
SensorFactory::get().getTurns().addListener(this);
|
||||
SensorFactory::get().getWiFi().addListener(this);
|
||||
|
||||
//setAutoFillBackground(false);
|
||||
|
||||
}
|
||||
|
||||
void SensorDataWidget::onSensorData(Sensor<AccelerometerData>* sensor, const Timestamp ts, const AccelerometerData& data) {
|
||||
(void) sensor;
|
||||
((PlotAcc*)plotAcc)->add(ts, data);
|
||||
}
|
||||
|
||||
void SensorDataWidget::onSensorData(Sensor<StepData>* sensor, const Timestamp ts, const StepData& data) {
|
||||
(void) sensor;
|
||||
(void) data;
|
||||
((PlotAcc*)plotAcc)->addStep(ts);
|
||||
}
|
||||
|
||||
void SensorDataWidget::onSensorData(Sensor<GyroscopeData>* sensor, const Timestamp ts, const GyroscopeData& data) {
|
||||
(void) sensor;
|
||||
((PlotGyro*)plotGyro)->add(ts, data);
|
||||
}
|
||||
|
||||
void SensorDataWidget::onSensorData(Sensor<BarometerData>* sensor, const Timestamp ts, const BarometerData& data) {
|
||||
(void) sensor;
|
||||
((PlotBaro*)plotBaro)->add(ts, data);
|
||||
}
|
||||
|
||||
void SensorDataWidget::onSensorData(Sensor<TurnData>* sensor, const Timestamp ts, const TurnData& data) {
|
||||
(void) sensor;
|
||||
((PlotTurns*)plotTurn)->add(ts, data);
|
||||
}
|
||||
|
||||
void SensorDataWidget::onSensorData(Sensor<WiFiMeasurements>* sensor, const Timestamp ts, const WiFiMeasurements& data) {
|
||||
(void) sensor;
|
||||
((PlotWiFiScan*)plotWiFi)->add(ts, data);
|
||||
}
|
||||
|
||||
53
ui/debug/SensorDataWidget.h
Normal file
@@ -0,0 +1,53 @@
|
||||
#ifndef SENSORDATAWIDGET_H
|
||||
#define SENSORDATAWIDGET_H
|
||||
|
||||
#include "../misc/fixc11.h"
|
||||
#include "plot/PlottWidget.h"
|
||||
|
||||
#include <QWidget>
|
||||
|
||||
#include "../sensors/AccelerometerSensor.h"
|
||||
#include "../sensors/GyroscopeSensor.h"
|
||||
#include "../sensors/BarometerSensor.h"
|
||||
#include "../sensors/StepSensor.h"
|
||||
#include "../sensors/TurnSensor.h"
|
||||
#include "../sensors/WiFiSensor.h"
|
||||
|
||||
class PlotWidget;
|
||||
|
||||
/** debug display for sensor data */
|
||||
class SensorDataWidget :
|
||||
public QWidget,
|
||||
public SensorListener<AccelerometerData>,
|
||||
public SensorListener<GyroscopeData>,
|
||||
public SensorListener<BarometerData>,
|
||||
public SensorListener<StepData>,
|
||||
public SensorListener<TurnData>,
|
||||
public SensorListener<WiFiMeasurements> {
|
||||
|
||||
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
|
||||
SensorDataWidget(QWidget* parent);
|
||||
|
||||
void onSensorData(Sensor<AccelerometerData>* sensor, const Timestamp ts, const AccelerometerData& data) override;
|
||||
void onSensorData(Sensor<GyroscopeData>* sensor, const Timestamp ts, const GyroscopeData& data) override;
|
||||
void onSensorData(Sensor<BarometerData>* sensor, const Timestamp ts, const BarometerData& data) override;
|
||||
void onSensorData(Sensor<StepData>* sensor, const Timestamp ts, const StepData& data) override;
|
||||
void onSensorData(Sensor<TurnData>* sensor, const Timestamp ts, const TurnData& data) override;
|
||||
void onSensorData(Sensor<WiFiMeasurements>* sensor, const Timestamp ts, const WiFiMeasurements& data) override;
|
||||
|
||||
private:
|
||||
|
||||
PlotWidget* plotGyro;
|
||||
PlotWidget* plotAcc;
|
||||
PlotWidget* plotBaro;
|
||||
QWidget* plotTurn;
|
||||
QWidget* plotWiFi;
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif // SENSORDATAWIDGET_H
|
||||
66
ui/debug/plot/Axes.h
Normal file
@@ -0,0 +1,66 @@
|
||||
#ifndef AXES_H
|
||||
#define AXES_H
|
||||
|
||||
#include "Range.h"
|
||||
|
||||
class Axes {
|
||||
|
||||
/** min/max value to display */
|
||||
Range range;
|
||||
|
||||
/** number of available pixels for above range */
|
||||
int pixels;
|
||||
|
||||
/** whether to invert the axes */
|
||||
bool invert = false;
|
||||
|
||||
public:
|
||||
|
||||
void setMin(const float min) {this->range.min = min;}
|
||||
float getMin() const {return this->range.min;}
|
||||
|
||||
void setMax(const float max) {this->range.max = max;}
|
||||
float getMax() const {return this->range.max;}
|
||||
|
||||
void setRange(const Range& range) {this->range = range;}
|
||||
const Range& getRange() const {return this->range;}
|
||||
|
||||
void setPixels(const int px) {this->pixels = px;}
|
||||
int getPixels() const {return this->pixels;}
|
||||
|
||||
void setInverted(const bool inverted) {this->invert = inverted;}
|
||||
bool isInverted() const {return this->invert;}
|
||||
|
||||
float convert(const float val) const {
|
||||
float percent = (val - range.min) / (range.getSize());
|
||||
if (invert) {percent = 1-percent;}
|
||||
return percent * pixels;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
class AxesX : public Axes {
|
||||
|
||||
public:
|
||||
|
||||
AxesX() {
|
||||
setInverted(false);
|
||||
}
|
||||
|
||||
void setWidth(const int px) {setPixels(px);}
|
||||
|
||||
};
|
||||
|
||||
class AxesY : public Axes {
|
||||
|
||||
public:
|
||||
|
||||
AxesY() {
|
||||
setInverted(true);
|
||||
}
|
||||
|
||||
void setHeight(const int px) {setPixels(px);}
|
||||
|
||||
};
|
||||
|
||||
#endif // AXES_H
|
||||
80
ui/debug/plot/Data.h
Normal file
@@ -0,0 +1,80 @@
|
||||
#ifndef PLOT_DATA_H
|
||||
#define PLOT_DATA_H
|
||||
|
||||
#include <vector>
|
||||
#include "Range.h"
|
||||
#include <cmath>
|
||||
|
||||
class Data {
|
||||
|
||||
using Key = float;
|
||||
using Value = float;
|
||||
|
||||
public:
|
||||
|
||||
struct KeyVal {
|
||||
Key key;
|
||||
Value val;
|
||||
KeyVal(const Key& key, const Value& val) : key(key), val(val) {;}
|
||||
};
|
||||
|
||||
private:
|
||||
|
||||
/** contained data */
|
||||
std::vector<KeyVal> data;
|
||||
|
||||
|
||||
|
||||
public:
|
||||
|
||||
/** add a new value */
|
||||
void add(const Key key, const Value val) {
|
||||
data.push_back(KeyVal(key,val));
|
||||
}
|
||||
|
||||
/** remove the given index */
|
||||
void remove(const int idx) {
|
||||
data.erase(data.begin()+idx);
|
||||
}
|
||||
|
||||
Key getKey(const int idx) const {
|
||||
return data[idx].key;
|
||||
}
|
||||
|
||||
Value getValue(const int idx) const {
|
||||
return data[idx].val;
|
||||
}
|
||||
|
||||
const KeyVal& getKeyValue(const int idx) const {
|
||||
return data[idx];
|
||||
}
|
||||
|
||||
const KeyVal& operator [] (const int idx) const {
|
||||
return data[idx];
|
||||
}
|
||||
|
||||
const KeyVal& front() const {return data.front();}
|
||||
const KeyVal& back() const {return data.back();}
|
||||
|
||||
/** get the range (min/max) for the key-data (x-axes) */
|
||||
Range getKeyRange() const {
|
||||
Range range(+INFINITY,-INFINITY);
|
||||
for (const KeyVal& kv : data) {range.adjust(kv.key);}
|
||||
return range;
|
||||
}
|
||||
|
||||
/** get the range (min/max) for the value-data (y-axes) */
|
||||
Range getValueRange() const {
|
||||
Range range(+INFINITY,-INFINITY);
|
||||
for (const KeyVal& kv : data) {range.adjust(kv.val);}
|
||||
return range;
|
||||
}
|
||||
|
||||
/** get the number of entries */
|
||||
size_t size() const {
|
||||
return data.size();
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // PLOT_DATA_H
|
||||
215
ui/debug/plot/Plot.h
Normal file
@@ -0,0 +1,215 @@
|
||||
#ifndef PLOT_H
|
||||
#define PLOT_H
|
||||
|
||||
#include <QPainter>
|
||||
|
||||
#include "Axes.h"
|
||||
#include "Data.h"
|
||||
|
||||
#include <Indoor/geo/Point2.h>
|
||||
|
||||
/** describes a plot-setup */
|
||||
struct PlotParameters {
|
||||
|
||||
AxesX xAxes;
|
||||
AxesY yAxes;
|
||||
|
||||
int w;
|
||||
int h;
|
||||
|
||||
/** helper method */
|
||||
Point2 getPoint(const typename Data::KeyVal& kv) const {
|
||||
const float x1 = xAxes.convert(kv.key);
|
||||
const float y1 = yAxes.convert(kv.val);
|
||||
return Point2(x1, y1);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
/** interface for all plots */
|
||||
class Plot {
|
||||
|
||||
protected:
|
||||
|
||||
Data data;
|
||||
|
||||
QColor bg = QColor(255,255,255,128);
|
||||
|
||||
public:
|
||||
|
||||
virtual ~Plot() {;}
|
||||
|
||||
void render(QPainter& p, const PlotParameters& params) {
|
||||
// maybe do something here?
|
||||
renderSub(p, params);
|
||||
}
|
||||
|
||||
Data& getData() {return data;}
|
||||
|
||||
Range getKeyRange() const {return data.getKeyRange();}
|
||||
|
||||
Range getValueRange() const {return data.getValueRange();}
|
||||
|
||||
protected:
|
||||
|
||||
/** subclasses must render themselves here */
|
||||
virtual void renderSub(QPainter& p, const PlotParameters& params) = 0;
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
/** combine several plots (several lines, points, ...) together into one plot */
|
||||
class PlotContainer {
|
||||
|
||||
private:
|
||||
|
||||
PlotParameters params;
|
||||
|
||||
std::vector<Plot*> plots;
|
||||
|
||||
public:
|
||||
|
||||
/** ctor */
|
||||
PlotContainer() {
|
||||
;
|
||||
}
|
||||
|
||||
AxesX& getAxesX() {return params.xAxes;}
|
||||
AxesY& getAxesY() {return params.yAxes;}
|
||||
|
||||
Range overwriteRangeKey = Range(0,0);
|
||||
Range overwriteRangeVal = Range(0,0);
|
||||
|
||||
void setValRange(const Range& range) {overwriteRangeVal = range;}
|
||||
void setKeyRange(const Range& range) {overwriteRangeKey = range;}
|
||||
|
||||
|
||||
void resize(const int w, const int h) {
|
||||
params.w = w;
|
||||
params.h = h;
|
||||
}
|
||||
|
||||
void addPlot(Plot* plt) {
|
||||
plots.push_back(plt);
|
||||
}
|
||||
|
||||
void render(QPainter& p) {
|
||||
|
||||
setupAxes();
|
||||
|
||||
QColor bg(255,255,255,192);
|
||||
p.fillRect(0,0,params.w,params.h,bg);
|
||||
p.setPen(Qt::black);
|
||||
p.drawRect(0,0,params.w-1,params.h-1);
|
||||
|
||||
for (Plot* plt : plots) {
|
||||
plt->render(p, params);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
void setupAxes() {
|
||||
|
||||
params.xAxes.setPixels(params.w);
|
||||
params.yAxes.setPixels(params.h);
|
||||
|
||||
Range keyRange(+INFINITY,-INFINITY);
|
||||
Range valRange(+INFINITY,-INFINITY);
|
||||
|
||||
if (overwriteRangeKey.isValid()) {keyRange.adjust(overwriteRangeKey);}
|
||||
if (overwriteRangeVal.isValid()) {valRange.adjust(overwriteRangeVal);}
|
||||
|
||||
/** calculate min/max for both x and y axis */
|
||||
for (Plot* plt : plots) {
|
||||
if (!overwriteRangeKey.isValid()) {keyRange.adjust(plt->getKeyRange());}
|
||||
if (!overwriteRangeVal.isValid()) {valRange.adjust(plt->getValueRange());}
|
||||
}
|
||||
|
||||
valRange.scale(1.1);
|
||||
|
||||
params.xAxes.setRange(keyRange);
|
||||
params.yAxes.setRange(valRange);
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
class LinePlot : public Plot {
|
||||
|
||||
private:
|
||||
|
||||
QColor lineColor = QColor(0,0,255);
|
||||
|
||||
public:
|
||||
|
||||
void setColor(const QColor c) {
|
||||
this->lineColor = c;
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
void renderSub(QPainter& p , const PlotParameters& params) override {
|
||||
|
||||
p.setPen(lineColor);
|
||||
|
||||
for (int i = 0; i < (int) data.size()-1; ++i) {
|
||||
|
||||
const typename Data::KeyVal kv1 = data[i+0];
|
||||
const typename Data::KeyVal kv2 = data[i+1];
|
||||
|
||||
const Point2 p1 = params.getPoint(kv1);
|
||||
const Point2 p2 = params.getPoint(kv2);
|
||||
|
||||
p.drawLine(p1.x, p1.y, p2.x, p2.y);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
class PointPlot : public Plot {
|
||||
|
||||
private:
|
||||
|
||||
QColor pointColor = QColor(0,0,255);
|
||||
float pointSize = 4;
|
||||
|
||||
public:
|
||||
|
||||
void setColor(const QColor c) {
|
||||
this->pointColor = c;
|
||||
}
|
||||
|
||||
void setPointSize(const float size) {
|
||||
this->pointSize = size;
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
void renderSub(QPainter& p , const PlotParameters& params) override {
|
||||
|
||||
p.setPen(Qt::NoPen);
|
||||
p.setBrush(pointColor);
|
||||
|
||||
for (int i = 0; i < (int) data.size(); ++i) {
|
||||
|
||||
const typename Data::KeyVal kv1 = data[i+0];
|
||||
|
||||
const Point2 p1 = params.getPoint(kv1);
|
||||
|
||||
p.drawEllipse(p1.x, p1.y, pointSize, pointSize);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // PLOT_H
|
||||
37
ui/debug/plot/PlottWidget.cpp
Normal file
@@ -0,0 +1,37 @@
|
||||
#include "PlottWidget.h"
|
||||
|
||||
#include <QResizeEvent>
|
||||
#include <QPaintEvent>
|
||||
#include <QPainter>
|
||||
|
||||
PlotWidget::PlotWidget(QWidget *parent) : QWidget(parent) {
|
||||
|
||||
setMinimumSize(100, 100);
|
||||
|
||||
// LinePlot* lp = new LinePlot();
|
||||
// pc.addPlot(lp);
|
||||
|
||||
// lp->getData().add(1, 1);
|
||||
// lp->getData().add(2, 2);
|
||||
// lp->getData().add(3, 3);
|
||||
// lp->getData().add(4, 1);
|
||||
// lp->getData().add(5, 2);
|
||||
// lp->getData().add(6, 3);
|
||||
// lp->getData().add(7, 1);
|
||||
// lp->getData().add(8, 2);
|
||||
// lp->getData().add(9, 3);
|
||||
|
||||
|
||||
}
|
||||
|
||||
void PlotWidget::resizeEvent(QResizeEvent* evt) {
|
||||
(void) evt;
|
||||
pc.resize(width(), height());
|
||||
}
|
||||
|
||||
void PlotWidget::paintEvent(QPaintEvent* evt) {
|
||||
(void) evt;
|
||||
QPainter p(this);
|
||||
pc.render(p);
|
||||
p.end();
|
||||
}
|
||||
30
ui/debug/plot/PlottWidget.h
Normal file
@@ -0,0 +1,30 @@
|
||||
#ifndef PLOTTI_H
|
||||
#define PLOTTI_H
|
||||
|
||||
#include <QWidget>
|
||||
#include "Plot.h"
|
||||
|
||||
/** widget to render one plot */
|
||||
class PlotWidget : public QWidget {
|
||||
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
|
||||
/** ctor */
|
||||
explicit PlotWidget(QWidget *parent = 0);
|
||||
|
||||
protected:
|
||||
|
||||
PlotContainer pc;
|
||||
|
||||
signals:
|
||||
|
||||
public slots:
|
||||
|
||||
void paintEvent(QPaintEvent*);
|
||||
void resizeEvent(QResizeEvent*);
|
||||
|
||||
};
|
||||
|
||||
#endif // PLOTTI_H
|
||||
48
ui/debug/plot/Range.h
Normal file
@@ -0,0 +1,48 @@
|
||||
#ifndef PLOT_RANGE_H
|
||||
#define PLOT_RANGE_H
|
||||
|
||||
struct Range {
|
||||
|
||||
float min;
|
||||
float max;
|
||||
|
||||
Range() : min(0), max(0) {;}
|
||||
|
||||
Range(const float min, const float max) : min(min), max(max) {
|
||||
;
|
||||
}
|
||||
|
||||
float getSize() const {
|
||||
return max-min;
|
||||
}
|
||||
|
||||
float getCenter() const {
|
||||
return (max+min)/2;
|
||||
}
|
||||
|
||||
bool isValid() const {
|
||||
return getSize() > 0;
|
||||
}
|
||||
|
||||
/** resize the region. 1.0 = keep-as-is */
|
||||
void scale(const float val) {
|
||||
const float center = getCenter();
|
||||
const float size = getSize();
|
||||
min = center - size / 2 * val;
|
||||
max = center + size / 2 * val;
|
||||
}
|
||||
|
||||
/** adjust (grow) the range */
|
||||
void adjust(const float val) {
|
||||
if (val < min) {min = val;}
|
||||
if (val > max) {max = val;}
|
||||
}
|
||||
|
||||
void adjust(const Range& o) {
|
||||
if (o.min < min) {min = o.min;}
|
||||
if (o.max > max) {max = o.max;}
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // PLOT_RANGE_H
|
||||
73
ui/dialog/LoadSetupDialog.cpp
Normal file
@@ -0,0 +1,73 @@
|
||||
#include "LoadSetupDialog.h"
|
||||
|
||||
#include <QLabel>
|
||||
#include <QPushButton>
|
||||
#include <QListView>
|
||||
#include <QFile>
|
||||
#include <QDir>
|
||||
#include <QStringListModel>
|
||||
|
||||
#include <iostream>
|
||||
|
||||
#include <Indoor/Assertions.h>
|
||||
|
||||
#include "../Config.h"
|
||||
|
||||
LoadSetupDialog::LoadSetupDialog() {
|
||||
|
||||
// the folder all map-setups reside within
|
||||
const std::string base = Config::getMapDir();
|
||||
QDir mapFolder(QString(base.c_str()));
|
||||
|
||||
// sanity check. folder must exist
|
||||
Assert::isTrue(mapFolder.exists(), "folder not found: " + base);
|
||||
|
||||
// get all subfolders (each subfolder descibres one setup), skip the first two folders: "." and ".."
|
||||
QStringList subfolders = mapFolder.entryList(QDir::Dirs);
|
||||
subfolders.removeFirst();
|
||||
subfolders.removeFirst();
|
||||
// for (int i = 2; i < subfolders.size(); ++i) {
|
||||
// const QString subfolder = subfolders[i];
|
||||
// std::cout << subfolder.toStdString() << std::endl;
|
||||
// }
|
||||
|
||||
int w = 350;
|
||||
int h = 350;
|
||||
|
||||
const QFont font("Arial", 20);
|
||||
|
||||
QListView* lst = new QListView(this);
|
||||
lst->setGeometry(5,5,w-5-5,h-5-5);
|
||||
lst->setFont(font);
|
||||
|
||||
QStringListModel* mdl = new QStringListModel(subfolders);
|
||||
lst->setModel(mdl);
|
||||
|
||||
// list item selected
|
||||
connect(lst, &QListView::clicked, [this, base, subfolders] (const QModelIndex& idx) {
|
||||
const int i = idx.row();
|
||||
selDir = base + subfolders[i].toStdString();
|
||||
this->close();
|
||||
});
|
||||
|
||||
// QPushButton* btnOK = new QPushButton(this);
|
||||
// btnOK->setText("OK");
|
||||
// btnOK->setGeometry(5,h-32-5,w-5-5,32);
|
||||
|
||||
// // OK button clicked
|
||||
// btnOK->connect(btnOK, &QPushButton::clicked, [&] () {
|
||||
// this->close();
|
||||
// });
|
||||
|
||||
this->resize(w,h);
|
||||
|
||||
}
|
||||
|
||||
QDir LoadSetupDialog::pickSetupFolder() {
|
||||
|
||||
|
||||
LoadSetupDialog dlg;
|
||||
dlg.exec();
|
||||
return QDir(QString(dlg.selDir.c_str()));
|
||||
|
||||
}
|
||||
25
ui/dialog/LoadSetupDialog.h
Normal file
@@ -0,0 +1,25 @@
|
||||
#ifndef LOADSETUPDIALOG_H
|
||||
#define LOADSETUPDIALOG_H
|
||||
|
||||
#include <QDialog>
|
||||
#include <QDir>
|
||||
|
||||
class LoadSetupDialog : public QDialog {
|
||||
|
||||
Q_OBJECT
|
||||
|
||||
private:
|
||||
|
||||
/** hidden ctor */
|
||||
explicit LoadSetupDialog();
|
||||
|
||||
std::string selDir = "";
|
||||
|
||||
public:
|
||||
|
||||
/** show a dialog to open a data-folder */
|
||||
static QDir pickSetupFolder();
|
||||
|
||||
};
|
||||
|
||||
#endif // LOADSETUPDIALOG_H
|
||||
266
ui/map/MapView.cpp
Normal file
@@ -0,0 +1,266 @@
|
||||
#include "MapView.h"
|
||||
|
||||
#include <QMouseEvent>
|
||||
#include <QGLShaderProgram>
|
||||
|
||||
#include "elements/Walls.h"
|
||||
#include "elements/Ground.h"
|
||||
#include "elements/Handrails.h"
|
||||
#include "elements/Stairs.h"
|
||||
#include "elements/Doors.h"
|
||||
#include "elements/Path.h"
|
||||
#include "elements/ColorPoints.h"
|
||||
#include "elements/Object.h"
|
||||
|
||||
#include <Indoor/data/Timestamp.h>
|
||||
#include <QDebug>
|
||||
|
||||
/**
|
||||
* before adding elements to the MapView via setMap(),
|
||||
* the MapViews openGL context must be initialized
|
||||
* that means: the MapView must have been added to a window,
|
||||
* which is already visible!
|
||||
*/
|
||||
|
||||
MapView::MapView(QWidget* parent) : QOpenGLWidget(parent) {
|
||||
|
||||
|
||||
|
||||
};
|
||||
|
||||
void MapView::clear() {
|
||||
|
||||
for (Renderable* r : elements) {delete r;}
|
||||
elements.clear();
|
||||
|
||||
}
|
||||
|
||||
void MapView::setMap(Floorplan::IndoorMap* map) {
|
||||
|
||||
clear();
|
||||
|
||||
if (!isGLInitialized) {throw Exception("openGL is not yet initialized. add mapView to a visible window!");}
|
||||
|
||||
// first to be rendered
|
||||
this->colorPoints = new ColorPoints();
|
||||
elements.push_back(this->colorPoints);
|
||||
|
||||
//leDude = new Object("/mnt/firma/tmp/3D/minion/minion.obj", "/mnt/firma/tmp/3D/minion/minion.png", "", 0.35);
|
||||
leDude = new Object("/mnt/firma/tmp/3D/gnome/gnome.obj", "/mnt/firma/tmp/3D/gnome/gnome_diffuse.jpg", "/mnt/firma/tmp/3D/gnome/gnome_normal.jpg", 0.033);
|
||||
//leDude = new Object("/mnt/firma/tmp/3D/squirrel/squirrel.obj", "/mnt/firma/tmp/3D/squirrel/squirrel.jpg", "/mnt/firma/tmp/3D/squirrel/squirrel_normal.jpg", 0.033);
|
||||
elements.push_back(leDude);
|
||||
|
||||
for (Floorplan::Floor* floor : map->floors) {
|
||||
elements.push_back(new Ground(floor));
|
||||
elements.push_back(new Walls(floor));
|
||||
elements.push_back(new Handrails(floor));
|
||||
elements.push_back(new Stairs(floor));
|
||||
elements.push_back(new Doors(floor));
|
||||
}
|
||||
|
||||
this->path = new Path();
|
||||
elements.push_back(this->path);
|
||||
|
||||
|
||||
|
||||
// initialize the OpenGL context of all contained elements
|
||||
for (Renderable* r : elements) {
|
||||
r->initGL();
|
||||
}
|
||||
|
||||
// i want the focus! needed for key-events
|
||||
setFocusPolicy(Qt::StrongFocus);
|
||||
|
||||
}
|
||||
|
||||
void MapView::setPath(const std::vector<Point3>& path) {
|
||||
this->path->set(path);
|
||||
}
|
||||
|
||||
|
||||
void MapView::timerEvent(QTimerEvent *) {
|
||||
update();
|
||||
}
|
||||
|
||||
void MapView::initializeGL() {
|
||||
|
||||
initializeOpenGLFunctions();
|
||||
|
||||
// basic config
|
||||
glEnable(GL_DEPTH_TEST);
|
||||
glEnable(GL_CULL_FACE);
|
||||
|
||||
// start background update timer
|
||||
const int fps = 25;
|
||||
const int interval = 1000 / fps;
|
||||
timer.start(interval, this);
|
||||
|
||||
// OpenGL is now initialized
|
||||
isGLInitialized = true;
|
||||
|
||||
}
|
||||
|
||||
void MapView::paintGL() {
|
||||
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
|
||||
draw();
|
||||
}
|
||||
|
||||
void MapView::resizeGL(int w, int h) {
|
||||
|
||||
// Calculate aspect ratio
|
||||
qreal aspect = qreal(w) / qreal(h ? h : 1);
|
||||
|
||||
// viewing frustrum [0:50] meter
|
||||
const qreal zNear = 0.02, zFar = 50, fov = 50.0;
|
||||
|
||||
// Reset projection
|
||||
matProject.setToIdentity();
|
||||
matProject.scale(-1, 1, 1);
|
||||
glCullFace(GL_FRONT);
|
||||
//matProject.scale(0.05, 0.05, 0.05);
|
||||
matProject.perspective(fov, aspect, zNear, zFar);
|
||||
//matProject.scale(-0.01, 0.01, 0.01);
|
||||
|
||||
}
|
||||
|
||||
void MapView::rebuildLookat() {
|
||||
// QVector3D qDir(lookAt.dir.x, lookAt.dir.z, lookAt.dir.y);
|
||||
// QVector3D at = QVector3D(lookAt.pos.x, lookAt.pos.z, lookAt.pos.y);
|
||||
// QVector3D eye = at + qDir * 0.1;
|
||||
// QVector3D up = QVector3D(0,1,0);
|
||||
// matView.setToIdentity();
|
||||
// //matView.scale(0.01, 0.01, 0.01);
|
||||
// matView.lookAt(eye, at, up);
|
||||
// //matView.scale(0.99, 1, 1);
|
||||
// //matView.translate(0.7, 0, 0);
|
||||
// lightPos = eye + QVector3D(0.0, 4.0, 0.0);
|
||||
// eyePos = eye;
|
||||
|
||||
const Point3 dir = lookAt.getDir();
|
||||
|
||||
QVector3D qDir(dir.x, dir.z, dir.y);
|
||||
QVector3D eye(lookAt.eye_m.x, lookAt.eye_m.z, lookAt.eye_m.y);
|
||||
QVector3D at = eye + qDir * 0.5;
|
||||
QVector3D up = QVector3D(0,1,0);
|
||||
matView.setToIdentity();
|
||||
matView.lookAt(eye, at, up);
|
||||
lightPos = eye + QVector3D(0.0, 0.5, 0.0) + qDir * 1.2;
|
||||
eyePos = eye;
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
void MapView::setCurrentEstimation(const Point3 pos, const Point3 dir) {
|
||||
const float angle = std::atan2(dir.y, dir.x) * 180 / M_PI;
|
||||
if (leDude) {
|
||||
leDude->setPosition(pos.x, pos.y, pos.z);
|
||||
leDude->setRotation(0, 0, -angle + 90);
|
||||
}
|
||||
}
|
||||
|
||||
void MapView::setLookAt(const Point3 pos_m, const Point3 dir) {
|
||||
lookAt.eye_m = pos_m + dir * 0.1;
|
||||
lookAt.dir = dir;
|
||||
rebuildLookat();
|
||||
}
|
||||
|
||||
void MapView::setLookDir(const Point3 dir) {
|
||||
lookAt.dir = dir;
|
||||
rebuildLookat();
|
||||
}
|
||||
|
||||
void MapView::setLookEye(const Point3 eye_m) {
|
||||
lookAt.eye_m = eye_m;
|
||||
rebuildLookat();
|
||||
}
|
||||
|
||||
|
||||
|
||||
void MapView::mousePressEvent(QMouseEvent* evt) {
|
||||
mouseState.down = true;
|
||||
mouseState.x = evt->x();
|
||||
mouseState.y = evt->y();
|
||||
}
|
||||
|
||||
void MapView::mouseMoveEvent(QMouseEvent* evt) {
|
||||
|
||||
const float dx = evt->x() - mouseState.x;
|
||||
const float dy = evt->y() - mouseState.y;
|
||||
|
||||
// PI*0.3 head movement left/right and up/down
|
||||
const float yFac = (this->height() / 2) / (M_PI * 0.3);
|
||||
const float xFac = (this->width() / 2) / (M_PI * 0.3);
|
||||
|
||||
lookAt.dirOffset = Point3(0, std::sin(dx/xFac), std::sin(-dy/yFac));
|
||||
rebuildLookat();
|
||||
|
||||
}
|
||||
|
||||
void MapView::mouseReleaseEvent(QMouseEvent* evt) {
|
||||
mouseState.down = false;
|
||||
}
|
||||
|
||||
|
||||
void MapView::keyPressEvent(QKeyEvent* evt) {
|
||||
|
||||
if (evt->key() == Qt::Key_W) {lookAt.eye_m += lookAt.getDir(); rebuildLookat();}
|
||||
if (evt->key() == Qt::Key_S) {lookAt.eye_m -= lookAt.getDir(); rebuildLookat();}
|
||||
|
||||
|
||||
}
|
||||
|
||||
void MapView::toggleRenderMode() {
|
||||
|
||||
renderMode = (RenderMode) (((int)renderMode + 1) % 3);
|
||||
|
||||
for (Renderable* r : elements) {
|
||||
if (renderMode == RenderMode::OUTLINE) {
|
||||
r->setOutlineOnly(true);
|
||||
} else {
|
||||
r->setOutlineOnly(false);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void MapView::draw() {
|
||||
|
||||
//const Timestamp ts1 = Timestamp::fromUnixTime();
|
||||
|
||||
// clear everything
|
||||
glClearColor(0,0,0,1);
|
||||
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
|
||||
|
||||
if (renderMode == RenderMode::TRANSPARENT) {
|
||||
glEnable(GL_BLEND);
|
||||
} else {
|
||||
glDisable(GL_BLEND);
|
||||
}
|
||||
|
||||
glBlendEquationSeparate(GL_FUNC_ADD, GL_FUNC_ADD);
|
||||
glBlendFuncSeparate(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA, GL_ONE, GL_ZERO);
|
||||
|
||||
|
||||
|
||||
for (Renderable* r : elements) {
|
||||
|
||||
QOpenGLShaderProgram& program = r->getProgram();
|
||||
program.bind();
|
||||
|
||||
// set the matrices
|
||||
program.setUniformValue("m_matrix", r->modelMatrix.mat);
|
||||
program.setUniformValue("mv_matrix", matView * r->modelMatrix.mat);
|
||||
program.setUniformValue("mvp_matrix", matProject * matView * r->modelMatrix.mat);
|
||||
program.setUniformValue("lightWorldPos", lightPos);
|
||||
program.setUniformValue("eyeWorldPos", eyePos);
|
||||
|
||||
r->render();
|
||||
|
||||
}
|
||||
|
||||
//const Timestamp ts2 = Timestamp::fromUnixTime();
|
||||
//qDebug("%d ms", (ts2-ts1).ms());
|
||||
|
||||
|
||||
}
|
||||
152
ui/map/MapView.h
Normal file
@@ -0,0 +1,152 @@
|
||||
#ifndef MAPVIEW_H
|
||||
#define MAPVIEW_H
|
||||
|
||||
#include <../misc/fixc11.h>
|
||||
|
||||
|
||||
#include <QOpenGLWidget>
|
||||
#include <QOpenGLFunctions>
|
||||
#include <QOpenGLShaderProgram>
|
||||
#include <QBasicTimer>
|
||||
|
||||
#include <Indoor/geo/Point3.h>
|
||||
#include <Indoor/nav/dijkstra/DijkstraPath.h>
|
||||
|
||||
#include "elements/Path.h"
|
||||
#include "elements/ColorPoints.h"
|
||||
#include "elements/Object.h"
|
||||
|
||||
#include "../nav/State.h"
|
||||
|
||||
namespace Floorplan {
|
||||
class IndoorMap;
|
||||
}
|
||||
|
||||
class Renderable;
|
||||
class Path;
|
||||
|
||||
|
||||
class MapView : public QOpenGLWidget, protected QOpenGLFunctions {
|
||||
|
||||
Q_OBJECT
|
||||
|
||||
private:
|
||||
|
||||
QMatrix4x4 matProject;
|
||||
QMatrix4x4 matView;
|
||||
|
||||
QVector3D lightPos;
|
||||
QVector3D eyePos;
|
||||
|
||||
|
||||
QBasicTimer timer;
|
||||
|
||||
std::vector<Renderable*> elements;
|
||||
Path* path = nullptr;
|
||||
ColorPoints* colorPoints = nullptr;
|
||||
Object* leDude = nullptr;
|
||||
|
||||
struct LookAt {
|
||||
Point3 eye_m = Point3(0,0,1);
|
||||
Point3 dir = Point3(1,0,-0.1);
|
||||
Point3 dirOffset = Point3(0,0,0);
|
||||
Point3 getDir() const {return dir + dirOffset;}
|
||||
} lookAt;
|
||||
|
||||
struct MouseState {
|
||||
float x = 0;
|
||||
float y = 0;
|
||||
bool down = false;
|
||||
} mouseState;
|
||||
|
||||
void rebuildLookat();
|
||||
|
||||
void clear();
|
||||
|
||||
public:
|
||||
|
||||
MapView(QWidget* parent = 0);
|
||||
|
||||
/** set the map to display */
|
||||
void setMap(Floorplan::IndoorMap* map);
|
||||
|
||||
/** the position to look at + looking direction */
|
||||
void setLookAt(const Point3 pos, const Point3 dir = Point3(1, 0, -0.1));
|
||||
|
||||
/** set the eye's looking direction (looking from eye into this direction) */
|
||||
void setLookDir(const Point3 dir);
|
||||
|
||||
/** set the eye's position (looking from here) */
|
||||
void setLookEye(const Point3 eye_m);
|
||||
|
||||
|
||||
/** set the currently estimated position */
|
||||
void setCurrentEstimation(const Point3 pos, const Point3 dir);
|
||||
|
||||
/** set the path to disply */
|
||||
void setPath(const std::vector<Point3>& path);
|
||||
|
||||
/** NOTE: must be called from Qt's main thread! */
|
||||
/** set the path to disply */
|
||||
Q_INVOKABLE void setPath(const void* path) {
|
||||
setPath( (const DijkstraPath<MyGridNode>*) path);
|
||||
}
|
||||
|
||||
/** NOTE: must be called from Qt's main thread! */
|
||||
/** set the path to disply */
|
||||
template <typename Node> void setPath(const DijkstraPath<Node>* path) {
|
||||
this->path->set(*path);
|
||||
}
|
||||
|
||||
/** NOTE: must be called from Qt's main thread! */
|
||||
void showGridImportance(Grid<MyGridNode>* grid) {
|
||||
this->colorPoints->setFromGridImportance(grid);
|
||||
}
|
||||
|
||||
/** NOTE: must be called from Qt's main thread! */
|
||||
Q_INVOKABLE void showParticles(const void* particles) {
|
||||
showParticles((const std::vector<K::Particle<MyState>>*) particles);
|
||||
}
|
||||
|
||||
/** NOTE: must be called from Qt's main thread! */
|
||||
void showParticles(const std::vector<K::Particle<MyState>>* particles) {
|
||||
this->colorPoints->setFromParticles(*particles);
|
||||
}
|
||||
|
||||
enum RenderMode {
|
||||
NORMAL,
|
||||
TRANSPARENT,
|
||||
OUTLINE,
|
||||
};
|
||||
|
||||
RenderMode renderMode = RenderMode::NORMAL;
|
||||
|
||||
void toggleRenderMode();
|
||||
|
||||
public slots:
|
||||
|
||||
void mousePressEvent(QMouseEvent*);
|
||||
void mouseMoveEvent(QMouseEvent*);
|
||||
void mouseReleaseEvent(QMouseEvent*);
|
||||
|
||||
void keyPressEvent(QKeyEvent*);
|
||||
|
||||
protected:
|
||||
|
||||
void timerEvent(QTimerEvent *e) Q_DECL_OVERRIDE;
|
||||
|
||||
void initializeGL();
|
||||
|
||||
void paintGL();
|
||||
|
||||
void resizeGL(int width, int height);
|
||||
|
||||
private:
|
||||
|
||||
bool isGLInitialized = false;
|
||||
|
||||
void draw();
|
||||
|
||||
};
|
||||
|
||||
#endif // MAPVIEW_H
|
||||
76
ui/map/Renderable.h
Normal file
@@ -0,0 +1,76 @@
|
||||
#ifndef RENDERABLE_H
|
||||
#define RENDERABLE_H
|
||||
|
||||
#include <QOpenGLShaderProgram>
|
||||
|
||||
class Renderable {
|
||||
|
||||
protected:
|
||||
|
||||
QOpenGLShaderProgram program;
|
||||
|
||||
public:
|
||||
|
||||
/** dtor */
|
||||
virtual ~Renderable() {;}
|
||||
|
||||
/** get the renderable's shader */
|
||||
QOpenGLShaderProgram& getProgram() {return program;}
|
||||
|
||||
/** render the renderable */
|
||||
void render() {
|
||||
program.bind();
|
||||
_render();
|
||||
}
|
||||
|
||||
struct ModelMatrix {
|
||||
QVector3D pos = QVector3D(0,0,0);
|
||||
QVector3D rot = QVector3D(0,0,0);
|
||||
QVector3D scale = QVector3D(1,1,1);
|
||||
QMatrix4x4 mat;
|
||||
ModelMatrix() {mat.setToIdentity();}
|
||||
void update() {
|
||||
const QVector3D _rot = rot.normalized();
|
||||
const float rotDeg = rot.length();
|
||||
mat.setToIdentity();
|
||||
mat.scale(scale.x(), scale.y(), scale.z());
|
||||
mat.translate(pos.x(), pos.y(), pos.z());
|
||||
mat.rotate(rotDeg, _rot.x(), _rot.y(), _rot.z());
|
||||
}
|
||||
} modelMatrix;
|
||||
|
||||
void setPosition(QVector3D vec) {
|
||||
modelMatrix.pos = vec * 0.99;
|
||||
modelMatrix.update();
|
||||
}
|
||||
|
||||
void setPosition(const float x, const float y, const float z) {
|
||||
setPosition(QVector3D(x,z,y));
|
||||
}
|
||||
|
||||
/** in degrees! */
|
||||
void setRotation(const float x, const float y, const float z) {
|
||||
modelMatrix.rot = QVector3D(x,z,y);
|
||||
modelMatrix.update();
|
||||
}
|
||||
|
||||
virtual void setOutlineOnly(const bool outline) {;}
|
||||
|
||||
virtual void initGL() = 0;
|
||||
|
||||
virtual void _render() = 0;
|
||||
|
||||
protected:
|
||||
|
||||
/** helper method to build the shader */
|
||||
void loadShader(const QString& vertex, const QString& fragment) {
|
||||
program.removeAllShaders();
|
||||
if (!program.addShaderFromSourceFile(QOpenGLShader::Vertex, vertex)) {throw "1";}
|
||||
if (!program.addShaderFromSourceFile(QOpenGLShader::Fragment, fragment)) {throw "2";}
|
||||
if (!program.link()) {throw "3";}
|
||||
if (!program.bind()) {throw "4";}
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // RENDERABLE_H
|
||||
114
ui/map/elements/ColorPoints.h
Normal file
@@ -0,0 +1,114 @@
|
||||
#ifndef GL_PARTICLES_H
|
||||
#define GL_PARTICLES_H
|
||||
|
||||
|
||||
#include <Indoor/floorplan/v2/Floorplan.h>
|
||||
#include <KLib/math/filter/particles/ParticleFilter.h>
|
||||
|
||||
#include "../gl/GLHelper.h"
|
||||
#include "../gl/GLPoints.h"
|
||||
#include "../Renderable.h"
|
||||
|
||||
#include "../../../nav/Node.h"
|
||||
|
||||
class ColorPoints : public Renderable {
|
||||
|
||||
private:
|
||||
|
||||
GLPoints points;
|
||||
float size = 3.0f;
|
||||
|
||||
public:
|
||||
|
||||
/** ctor */
|
||||
ColorPoints() {
|
||||
|
||||
}
|
||||
|
||||
/** NOTE: must be called from Qt's main thread! */
|
||||
void setFromGridImportance(Grid<MyGridNode>* grid) {
|
||||
|
||||
points.clear();
|
||||
|
||||
for (const MyGridNode& n : *grid) {
|
||||
const QVector3D pt(n.x_cm/100.0f, n.z_cm/100.0f + 0.1f, n.y_cm/100.0f); // swap z and y
|
||||
const float f = n.getNavImportance();
|
||||
float h = 0.66 - (f*0.20); // 0.66 is blue on the HSV-scale
|
||||
if (h < 0) {h = 0;}
|
||||
if (h > 1) {h = 1;}
|
||||
const QColor color = QColor::fromHsvF(h, 1, 1);
|
||||
points.addPoint(pt, color);
|
||||
}
|
||||
|
||||
size = 3.0f;
|
||||
points.rebuild();
|
||||
|
||||
}
|
||||
|
||||
/** NOTE: must be called from Qt's main thread! */
|
||||
template <typename T> void setFromParticles(const std::vector<K::Particle<T>>& particles) {
|
||||
|
||||
points.clear();
|
||||
|
||||
// group particles by grid-point
|
||||
std::unordered_map<GridPoint, float> weights;
|
||||
for (const K::Particle<T>& p : particles) {
|
||||
const GridPoint gp = p.state.position;
|
||||
weights[gp] += p.weight;
|
||||
}
|
||||
|
||||
// find min/max
|
||||
float min = +INFINITY;
|
||||
float max = -INFINITY;
|
||||
for (auto it : weights) {
|
||||
if (it.second > max) {max = it.second;}
|
||||
if (it.second < min) {min = it.second;}
|
||||
}
|
||||
|
||||
// draw colored
|
||||
for (auto it : weights) {
|
||||
const GridPoint gp = it.first;
|
||||
const float w = it.second;
|
||||
const float p = (w-min) / (max-min); // [0:1]
|
||||
const QVector3D pt(gp.x_cm/100.0f, gp.z_cm/100.0f + 0.1f, gp.y_cm/100.0f); // swap z and y
|
||||
float h = 0.66 - (p*0.66); // 0.66 is blue on the HSV-scale
|
||||
const QColor color = QColor::fromHsvF(h, 1, 1);
|
||||
points.addPoint(pt, color);
|
||||
}
|
||||
|
||||
|
||||
// for (const K::Particle<T>& p : particles) {
|
||||
// const GridPoint gp = p.state.position;
|
||||
// const QVector3D pt(gp.x_cm/100.0f, gp.z_cm/100.0f + 0.1f, gp.y_cm/100.0f); // swap z and y
|
||||
// const QColor color = Qt::blue;
|
||||
// points.addPoint(pt, color);
|
||||
// }
|
||||
|
||||
size = 6.0f;
|
||||
points.rebuild();
|
||||
|
||||
}
|
||||
|
||||
|
||||
void initGL() override {
|
||||
loadShader(":/res/gl/vertex1.glsl", ":/res/gl/fragmentColorPoint.glsl");
|
||||
//program.setUniformValue("color", QVector4D(0.5, 0.5, 0.5, 1.0));
|
||||
points.initGL();
|
||||
}
|
||||
|
||||
/** render the floor */
|
||||
void _render() override {
|
||||
//glDisable(GL_DEPTH_TEST);
|
||||
//glPointSize()
|
||||
#ifndef ANDROID
|
||||
glPointSize(size);
|
||||
#endif
|
||||
points.render(&program);
|
||||
//glEnable(GL_DEPTH_TEST);
|
||||
}
|
||||
|
||||
|
||||
};
|
||||
|
||||
|
||||
#endif // GL_PARTICLES_H
|
||||
@@ -4,9 +4,10 @@
|
||||
#include <Indoor/floorplan/v2/Floorplan.h>
|
||||
#include "../gl/GLHelper.h"
|
||||
#include "../gl/GLTriangles.h"
|
||||
#include "../gl/GLLines.h"
|
||||
#include "../Renderable.h"
|
||||
|
||||
#include "../../lib/gpc/Polygon.h"
|
||||
#include "../../../lib/gpc/Polygon.h"
|
||||
|
||||
class Ground : public Renderable {
|
||||
|
||||
@@ -17,11 +18,14 @@ private:
|
||||
GLTriangles<VertNormTexTan> flooring;
|
||||
GLTriangles<VertNormTexTan> ceiling;
|
||||
|
||||
GLLines outline;
|
||||
bool outlineOnly = false;
|
||||
|
||||
public:
|
||||
|
||||
/** ctor */
|
||||
Ground(Floorplan::Floor* floor) : floor(floor) {
|
||||
;
|
||||
setOutlineOnly(false);
|
||||
}
|
||||
|
||||
|
||||
@@ -37,17 +41,36 @@ public:
|
||||
|
||||
flooring.build();
|
||||
ceiling.build();
|
||||
outline.build();
|
||||
|
||||
loadShader(":/res/gl/vertex1.glsl", ":/res/gl/fragmentTex.glsl");
|
||||
program.setUniformValue("texDiffuse", 0);
|
||||
program.setUniformValue("texNormalMap", 1);
|
||||
//loadShader(":/res/gl/vertex1.glsl", ":/res/gl/fragmentTex.glsl");
|
||||
//program.setUniformValue("texDiffuse", 0);
|
||||
//program.setUniformValue("texNormalMap", 1);
|
||||
|
||||
}
|
||||
|
||||
/** render the floor */
|
||||
void _render() override {
|
||||
flooring.render(&program);
|
||||
ceiling.render(&program);
|
||||
if (outlineOnly) {
|
||||
glLineWidth(5);
|
||||
outline.render(&program);
|
||||
} else {
|
||||
flooring.render(&program);
|
||||
ceiling.render(&program);
|
||||
}
|
||||
}
|
||||
|
||||
/** render only the outline? */
|
||||
void setOutlineOnly(const bool outline) override {
|
||||
// this->outlineOnly = outline;
|
||||
// if (outlineOnly) {
|
||||
// loadShader(":/res/gl/vertex1.glsl", ":/res/gl/fragmentLine.glsl");
|
||||
// program.setUniformValue("color", QVector4D(0.0, 0.0, 0.4, 1.0));
|
||||
// } else {
|
||||
loadShader(":/res/gl/vertex1.glsl", ":/res/gl/fragmentTex.glsl");
|
||||
program.setUniformValue("texDiffuse", 0);
|
||||
program.setUniformValue("texNormalMap", 1);
|
||||
// }
|
||||
}
|
||||
|
||||
|
||||
@@ -80,7 +103,7 @@ private:
|
||||
|
||||
|
||||
const QVector3D normFloor(0, +1, 0);
|
||||
const QVector3D normCeil(0, +1, 0); // why +1???
|
||||
const QVector3D normCeil(0, -1, 0);
|
||||
const QVector3D t(1,0,0);
|
||||
|
||||
const float s = 0.6;
|
||||
@@ -108,6 +131,10 @@ private:
|
||||
ceiling.addFaceCW(vnt1, vnt2, vnt3);
|
||||
}
|
||||
|
||||
outline.addLine(vert1, vert2);
|
||||
outline.addLine(vert2, vert3);
|
||||
outline.addLine(vert3, vert1);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
84
ui/map/elements/Object.h
Normal file
@@ -0,0 +1,84 @@
|
||||
#ifndef OBJECT_H
|
||||
#define OBJECT_H
|
||||
|
||||
|
||||
#include <Indoor/floorplan/v2/Floorplan.h>
|
||||
#include "../gl/GLHelper.h"
|
||||
#include "../gl/GLTriangles.h"
|
||||
#include "../Renderable.h"
|
||||
|
||||
#include <KLib/data/obj/ObjectFile.h>
|
||||
|
||||
|
||||
class Object : public Renderable {
|
||||
|
||||
private:
|
||||
|
||||
GLTriangles<VertNormTex> triangles;
|
||||
|
||||
public:
|
||||
|
||||
/** ctor */
|
||||
Object(const std::string& file, const std::string& colorTexture, std::string normalsTexture, const float scale = 1.0) {
|
||||
|
||||
K::ObjFileReader reader(file, false);
|
||||
|
||||
|
||||
if (normalsTexture.empty()) {normalsTexture = ":/res/gl/tex/empty_normals.jpg";}
|
||||
|
||||
triangles.setDiffuse(colorTexture.c_str());
|
||||
triangles.setNormalMap(normalsTexture.c_str());
|
||||
|
||||
for (const K::ObjFileReader::Face& face : reader.getData().faces) {
|
||||
|
||||
const QVector3D vertex1(face.vnt[0].vertex.x, face.vnt[0].vertex.y, face.vnt[0].vertex.z);
|
||||
const QVector3D vertex2(face.vnt[1].vertex.x, face.vnt[1].vertex.y, face.vnt[1].vertex.z);
|
||||
const QVector3D vertex3(face.vnt[2].vertex.x, face.vnt[2].vertex.y, face.vnt[2].vertex.z);
|
||||
|
||||
const QVector3D normal1(face.vnt[0].normal.x, face.vnt[0].normal.y, face.vnt[0].normal.z);
|
||||
const QVector3D normal2(face.vnt[1].normal.x, face.vnt[1].normal.y, face.vnt[1].normal.z);
|
||||
const QVector3D normal3(face.vnt[2].normal.x, face.vnt[2].normal.y, face.vnt[2].normal.z);
|
||||
|
||||
const QVector2D texture1(face.vnt[0].texture.x, face.vnt[0].texture.y);
|
||||
const QVector2D texture2(face.vnt[1].texture.x, face.vnt[1].texture.y);
|
||||
const QVector2D texture3(face.vnt[2].texture.x, face.vnt[2].texture.y);
|
||||
|
||||
const QVector3D o(0, 0.0, 0);
|
||||
|
||||
const VertNormTex vnt1(vertex1*scale+o, normal1, texture1);
|
||||
const VertNormTex vnt2(vertex2*scale+o, normal2, texture2);
|
||||
const VertNormTex vnt3(vertex3*scale+o, normal3, texture3);
|
||||
|
||||
triangles.addFace(vnt1, vnt2, vnt3);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
void initGL() override {
|
||||
build();
|
||||
triangles.build();
|
||||
loadShader(":/res/gl/vertex1.glsl", ":/res/gl/fragmentTex.glsl");
|
||||
program.setUniformValue("texDiffuse", 0);
|
||||
program.setUniformValue("texNormalMap", 1);
|
||||
}
|
||||
|
||||
/** render the floor */
|
||||
void _render() override {
|
||||
triangles.render(&program);
|
||||
}
|
||||
|
||||
|
||||
|
||||
private:
|
||||
|
||||
void build() {
|
||||
triangles.build();
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
#endif // OBJECT_H
|
||||
@@ -9,7 +9,6 @@
|
||||
#include "../gl/GLTriangles.h"
|
||||
#include "../Renderable.h"
|
||||
|
||||
#include "../../lib/gpc/Polygon.h"
|
||||
|
||||
class Path : public Renderable {
|
||||
|
||||
@@ -27,8 +27,10 @@ public:
|
||||
void initGL() override {
|
||||
|
||||
build();
|
||||
parts.setDiffuse(":/res/gl/tex/granite1.jpg");
|
||||
parts.setNormalMap(":/res/gl/tex/granite1_normal.jpg");
|
||||
// parts.setDiffuse(":/res/gl/tex/granite1.jpg");
|
||||
// parts.setNormalMap(":/res/gl/tex/granite1_normal.jpg");
|
||||
parts.setDiffuse(":/res/gl/tex/floor4.jpg");
|
||||
parts.setNormalMap(":/res/gl/tex/floor4_normal.jpg");
|
||||
parts.build();
|
||||
|
||||
loadShader(":/res/gl/vertex1.glsl", ":/res/gl/fragmentTex.glsl");
|
||||
@@ -4,9 +4,10 @@
|
||||
#include <Indoor/floorplan/v2/Floorplan.h>
|
||||
#include "../gl/GLHelper.h"
|
||||
#include "../gl/GLTriangles.h"
|
||||
#include "../gl/GLLines.h"
|
||||
#include "../Renderable.h"
|
||||
#include "../gl/Shader.h"
|
||||
|
||||
#include "../../lib/gpc/Polygon.h"
|
||||
|
||||
class Walls : public Renderable {
|
||||
|
||||
@@ -14,36 +15,54 @@ private:
|
||||
|
||||
Floorplan::Floor* floor;
|
||||
|
||||
GLTriangles<VertNormTexTan> walls;
|
||||
GLTriangles<VertNormTexTan> triangles;
|
||||
GLLines outlines;
|
||||
bool outlineOnly = false;
|
||||
|
||||
public:
|
||||
|
||||
/** ctor */
|
||||
Walls(Floorplan::Floor* floor) : floor(floor) {
|
||||
;
|
||||
|
||||
setOutlineOnly(false);
|
||||
|
||||
}
|
||||
|
||||
|
||||
void initGL() override {
|
||||
|
||||
build();
|
||||
walls.setDiffuse(":/res/gl/tex/floor3.jpg");
|
||||
walls.setNormalMap(":/res/gl/tex/floor3_normal.jpg");
|
||||
|
||||
walls.build();
|
||||
triangles.build();
|
||||
triangles.setDiffuse(":/res/gl/tex/wall3.jpg");
|
||||
triangles.setNormalMap(":/res/gl/tex/wall3_normal.jpg");
|
||||
|
||||
loadShader(":/res/gl/vertex1.glsl", ":/res/gl/fragmentTex.glsl");
|
||||
program.setUniformValue("texDiffuse", 0);
|
||||
program.setUniformValue("texNormalMap", 1);
|
||||
//glEnable(GL_TEXTURE0 + 1);
|
||||
outlines.build();
|
||||
|
||||
}
|
||||
|
||||
/** render the floor */
|
||||
void _render() override {
|
||||
walls.render(&program);
|
||||
if (outlineOnly) {
|
||||
glLineWidth(1);
|
||||
outlines.render(&program);
|
||||
} else {
|
||||
triangles.render(&program);
|
||||
}
|
||||
}
|
||||
|
||||
/** render only the outline? */
|
||||
void setOutlineOnly(const bool outline) override {
|
||||
this->outlineOnly = outline;
|
||||
if (outlineOnly) {
|
||||
loadShader(":/res/gl/vertex1.glsl", ":/res/gl/fragmentLine.glsl");
|
||||
program.setUniformValue("color", QVector4D(0.9, 0.9, 0.9, 1.0));
|
||||
} else {
|
||||
loadShader(":/res/gl/vertex1.glsl", ":/res/gl/fragmentTex.glsl");
|
||||
program.setUniformValue("texDiffuse", 0);
|
||||
program.setUniformValue("texNormalMap", 1);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
private:
|
||||
@@ -98,15 +117,20 @@ private:
|
||||
const VertNormTexTan vnt2(vert2, n1, tex2*s, tan);
|
||||
const VertNormTexTan vnt3(vert3, n1, tex3*s, tan);
|
||||
const VertNormTexTan vnt4(vert4, n1, tex4*s, tan);
|
||||
walls.addQuadCCW(vnt1, vnt2, vnt3, vnt4);
|
||||
triangles.addQuadCCW(vnt1, vnt2, vnt3, vnt4);
|
||||
} {
|
||||
const VertNormTexTan vnt1(vert1, n2, tex1*s, -tan);
|
||||
const VertNormTexTan vnt2(vert2, n2, tex2*s, -tan);
|
||||
const VertNormTexTan vnt3(vert3, n2, tex3*s, -tan);
|
||||
const VertNormTexTan vnt4(vert4, n2, tex4*s, -tan);
|
||||
walls.addQuadCW(vnt1, vnt2, vnt3, vnt4);
|
||||
triangles.addQuadCW(vnt1, vnt2, vnt3, vnt4);
|
||||
}
|
||||
|
||||
outlines.addLine(vert1, vert2);
|
||||
outlines.addLine(vert2, vert3);
|
||||
outlines.addLine(vert3, vert4);
|
||||
outlines.addLine(vert4, vert1);
|
||||
|
||||
}
|
||||
|
||||
//private:
|
||||
@@ -13,6 +13,18 @@ struct Vert {
|
||||
bool operator == (const Vert& o) const {return (vert == o.vert);}
|
||||
};
|
||||
|
||||
struct VertColor {
|
||||
QVector3D vert;
|
||||
QVector3D color;
|
||||
VertColor(QVector3D vert, QVector3D color) : vert(vert), color(color) {;}
|
||||
int getVertOffset() const {return 0;}
|
||||
int getColorOffset() const {return sizeof(QVector3D);}
|
||||
int getTanOffset() const {throw "error";}
|
||||
bool operator == (const VertColor& o) const {return (vert == o.vert) && (color == o.color);}
|
||||
static bool hasTangent() {return false;}
|
||||
static bool hasColor() {return true;}
|
||||
};
|
||||
|
||||
struct VertNorm {
|
||||
QVector3D vert;
|
||||
QVector3D norm;
|
||||
111
ui/map/gl/GLPoints.h
Normal file
@@ -0,0 +1,111 @@
|
||||
#ifndef GLPOINTS_H
|
||||
#define GLPOINTS_H
|
||||
|
||||
|
||||
#include <QOpenGLFunctions>
|
||||
#include "GL.h"
|
||||
#include "GLHelper.h"
|
||||
|
||||
#include <Indoor/geo/Point3.h>
|
||||
|
||||
class GLPoints : protected QOpenGLFunctions {
|
||||
|
||||
private:
|
||||
|
||||
QOpenGLBuffer arrayBuf;
|
||||
QOpenGLBuffer indexBuf;
|
||||
|
||||
std::vector<VertColor> vertices;
|
||||
std::vector<GLuint> indices;
|
||||
|
||||
int mode = GL_POINTS;
|
||||
bool initOnce = true;
|
||||
|
||||
public:
|
||||
|
||||
/** ctor */
|
||||
GLPoints() : arrayBuf(QOpenGLBuffer::VertexBuffer), indexBuf(QOpenGLBuffer::IndexBuffer) {
|
||||
alloc();
|
||||
}
|
||||
|
||||
/** dtor */
|
||||
~GLPoints() {
|
||||
destroy();
|
||||
}
|
||||
|
||||
/** add a new face to this element */
|
||||
void addPoint(const QVector3D& pt, const QColor& color) {
|
||||
indices.push_back(vertices.size());
|
||||
QVector3D c(color.redF(), color.greenF(), color.blueF());
|
||||
vertices.push_back(VertColor(pt, c));
|
||||
}
|
||||
|
||||
|
||||
void alloc() {
|
||||
if (!indexBuf.isCreated()) {indexBuf.create();}
|
||||
if (!arrayBuf.isCreated()) {arrayBuf.create();}
|
||||
}
|
||||
|
||||
void destroy() {
|
||||
if (indexBuf.isCreated()) {indexBuf.destroy();}
|
||||
if (arrayBuf.isCreated()) {arrayBuf.destroy();}
|
||||
}
|
||||
|
||||
/** build the underlying buffers */
|
||||
void build() {
|
||||
|
||||
// Transfer vertex data to VBO 0
|
||||
arrayBuf.bind();
|
||||
arrayBuf.allocate(vertices.data(), vertices.size() * sizeof(vertices[0]));
|
||||
|
||||
// Transfer index data to VBO 1
|
||||
indexBuf.bind();
|
||||
indexBuf.allocate(indices.data(), indices.size() * sizeof(indices[0]));
|
||||
|
||||
}
|
||||
|
||||
void initGL() {
|
||||
initializeOpenGLFunctions();
|
||||
}
|
||||
|
||||
void rebuild() {
|
||||
build();
|
||||
}
|
||||
|
||||
void clear() {
|
||||
indices.clear();
|
||||
vertices.clear();
|
||||
}
|
||||
|
||||
void setMode(const int mode) {
|
||||
this->mode = mode;
|
||||
}
|
||||
|
||||
/** render the element */
|
||||
void render(QOpenGLShaderProgram *program) {
|
||||
|
||||
if (indices.empty()) {return;}
|
||||
|
||||
// Tell OpenGL which VBOs to use
|
||||
arrayBuf.bind();
|
||||
indexBuf.bind();
|
||||
|
||||
// vertices
|
||||
int vertLoc = program->attributeLocation("a_position");
|
||||
program->enableAttributeArray(vertLoc);
|
||||
program->setAttributeBuffer(vertLoc, GL_FLOAT, vertices[0].getVertOffset(), 3, sizeof(vertices[0]));
|
||||
|
||||
// colors
|
||||
int colorLoc = program->attributeLocation("a_color");
|
||||
program->enableAttributeArray(colorLoc);
|
||||
program->setAttributeBuffer(colorLoc, GL_FLOAT, vertices[0].getColorOffset(), 3, sizeof(vertices[0]));
|
||||
|
||||
// Draw cube geometry using indices from VBO 1
|
||||
glDrawElements(mode, indices.size(), GL_UNSIGNED_INT, 0);
|
||||
|
||||
}
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif // GLPOINTS_H
|
||||
@@ -59,6 +59,11 @@ public:
|
||||
setTexture(1, textureFile);
|
||||
}
|
||||
|
||||
/** add a new face to this element */
|
||||
void addFace(const T& vnt1, const T& vnt2, const T& vnt3) {
|
||||
addFace(vnt1, vnt2, vnt3, 0);
|
||||
}
|
||||
|
||||
/** add a new face to this element */
|
||||
void addFaceCCW(const T& vnt1, const T& vnt2, const T& vnt3) {
|
||||
addFace(vnt1, vnt2, vnt3, 1);
|
||||
31
ui/map/gl/Shader.h
Normal file
@@ -0,0 +1,31 @@
|
||||
#ifndef SHADER_H
|
||||
#define SHADER_H
|
||||
|
||||
#include <QOpenGLShaderProgram>
|
||||
|
||||
/**
|
||||
* just some helper methods
|
||||
*/
|
||||
class Shader {
|
||||
|
||||
private:
|
||||
|
||||
QOpenGLShaderProgram program;
|
||||
|
||||
public:
|
||||
|
||||
/** get the underlying program */
|
||||
QOpenGLShaderProgram* getProgram() {return &program;}
|
||||
|
||||
/** helper method to build the shader */
|
||||
void loadShaderFromFile(const QString& vertex, const QString& fragment) {
|
||||
if (!program.addShaderFromSourceFile(QOpenGLShader::Vertex, vertex)) {throw "1";}
|
||||
if (!program.addShaderFromSourceFile(QOpenGLShader::Fragment, fragment)) {throw "2";}
|
||||
if (!program.link()) {throw "3";}
|
||||
if (!program.bind()) {throw "4";}
|
||||
}
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif // SHADER_H
|
||||
55
ui/menu/MainMenu.cpp
Normal file
@@ -0,0 +1,55 @@
|
||||
|
||||
#include "MainMenu.h"
|
||||
#include "../Icons.h"
|
||||
|
||||
#include <QPushButton>
|
||||
#include <QGridLayout>
|
||||
|
||||
#include <Indoor/Assertions.h>
|
||||
|
||||
MainMenu::MainMenu(QWidget* parent) : QWidget(parent) {
|
||||
|
||||
setMinimumHeight(64);
|
||||
|
||||
QGridLayout* lay = new QGridLayout(this);
|
||||
int row = 0;
|
||||
int col = 0;
|
||||
|
||||
btnLoadMap = getButton("load");
|
||||
Assert::isTrue(connect(btnLoadMap, &QPushButton::clicked, this, &MainMenu::onLoadButton), "connect() failed");
|
||||
lay->addWidget(btnLoadMap, row, col, 1,1,Qt::AlignTop); ++col;
|
||||
|
||||
btnDebug = getButton("bug");
|
||||
Assert::isTrue(connect(btnDebug, &QPushButton::clicked, this, &MainMenu::onDebugButton), "connect() failed");
|
||||
lay->addWidget(btnDebug, row, col, 1,1,Qt::AlignTop); ++col;
|
||||
|
||||
btnCamera = getButton("camera");
|
||||
Assert::isTrue(connect(btnCamera, &QPushButton::clicked, this, &MainMenu::onCameraButton), "connect() failed");
|
||||
lay->addWidget(btnCamera, row, col, 1,1,Qt::AlignTop); ++col;
|
||||
|
||||
btnTransparent = getButton("cube");
|
||||
Assert::isTrue(connect(btnTransparent, &QPushButton::clicked, this, &MainMenu::onTransparentButton), "connect() failed");
|
||||
lay->addWidget(btnTransparent, row, col, 1,1,Qt::AlignTop); ++col;
|
||||
|
||||
btnStart = getButton("run");
|
||||
Assert::isTrue(connect(btnStart, &QPushButton::clicked, this, &MainMenu::onStartButton), "connect() failed");
|
||||
lay->addWidget(btnStart, row, col, 1,1,Qt::AlignTop); ++col;
|
||||
|
||||
|
||||
}
|
||||
|
||||
QPushButton* MainMenu::getButton(const std::string& icon) {
|
||||
|
||||
const int size = 48;
|
||||
const int border = 4;
|
||||
|
||||
QPushButton* btn = new QPushButton(Icons::getIcon(icon, size), "");
|
||||
btn->setIconSize(QSize(size,size));
|
||||
btn->setMinimumHeight(size+border);
|
||||
btn->setMaximumHeight(size+border);
|
||||
btn->setMinimumWidth(size+border);
|
||||
btn->setMaximumWidth(size+border);
|
||||
|
||||
return btn;
|
||||
|
||||
}
|
||||
36
ui/menu/MainMenu.h
Normal file
@@ -0,0 +1,36 @@
|
||||
#ifndef MAINMENU_H
|
||||
#define MAINMENU_H
|
||||
|
||||
#include <QWidget>
|
||||
|
||||
class QPushButton;
|
||||
|
||||
class MainMenu : public QWidget {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
|
||||
/** ctor */
|
||||
explicit MainMenu(QWidget* parent);
|
||||
|
||||
signals:
|
||||
|
||||
void onLoadButton();
|
||||
void onStartButton();
|
||||
void onDebugButton();
|
||||
void onCameraButton();
|
||||
void onTransparentButton();
|
||||
|
||||
private:
|
||||
|
||||
QPushButton* getButton(const std::string& icon);
|
||||
|
||||
QPushButton* btnLoadMap;
|
||||
QPushButton* btnStart;
|
||||
QPushButton* btnDebug;
|
||||
QPushButton* btnCamera;
|
||||
QPushButton* btnTransparent;
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
101
yasmin.pro
@@ -1,10 +1,19 @@
|
||||
TEMPLATE = app
|
||||
|
||||
QT += qml opengl
|
||||
QT += qml opengl svg
|
||||
|
||||
# android?
|
||||
#QT += androidextras sensors
|
||||
#DEFINES += ANDROID
|
||||
|
||||
|
||||
# CONFIG+=ANDROID DEFINES+=ANDROID
|
||||
ANDROID {
|
||||
QT += androidextras
|
||||
QT += sensors
|
||||
}
|
||||
|
||||
# debug
|
||||
DEFINES += WITH_DEBUG_LOG
|
||||
DEFINES += WITH_ASSERTIONS
|
||||
|
||||
CONFIG += c++11
|
||||
|
||||
@@ -12,7 +21,13 @@ CONFIG += c++11
|
||||
ANDROID_PACKAGE_SOURCE_DIR = $$PWD/_android
|
||||
|
||||
INCLUDEPATH += \
|
||||
../
|
||||
../ \
|
||||
./lib/
|
||||
|
||||
|
||||
# linux desktop wifi
|
||||
#INCLUDEPATH +=/usr/include/libnl3/
|
||||
#LIBS += -lnl-genl-3 -lnl-3
|
||||
|
||||
OTHER_FILES += \
|
||||
_android/src/WiFi.java \
|
||||
@@ -21,15 +36,24 @@ OTHER_FILES += \
|
||||
|
||||
SOURCES += \
|
||||
main.cpp \
|
||||
map/MapView.cpp \
|
||||
map/Geometry.cpp \
|
||||
lib/gpc/gpc.cpp \
|
||||
../Indoor/lib/tinyxml/tinyxml2.cpp
|
||||
lib/gpc/gpc.cpp \
|
||||
../Indoor/lib/tinyxml/tinyxml2.cpp \
|
||||
ui/map/MapView.cpp \
|
||||
ui/menu/MainMenu.cpp \
|
||||
ui/MainWindow.cpp \
|
||||
Controller.cpp \
|
||||
ui/dialog/LoadSetupDialog.cpp \
|
||||
ui/debug/SensorDataWidget.cpp \
|
||||
ui/debug/plot/PlottWidget.cpp \
|
||||
ui/debug/PlotTurns.cpp \
|
||||
ui/debug/PlotWiFiScan.cpp \
|
||||
sensors/android/WiFiSensorAndroid.cpp \
|
||||
sensors/linux/WiFiSensorLinuxC.c
|
||||
|
||||
RESOURCES += qml.qrc
|
||||
|
||||
# Additional import path used to resolve QML modules in Qt Creator's code model
|
||||
QML_IMPORT_PATH =
|
||||
#QML_IMPORT_PATH =
|
||||
|
||||
# Default rules for deployment.
|
||||
include(deployment.pri)
|
||||
@@ -46,24 +70,69 @@ HEADERS += \
|
||||
sensors/linux/WiFiSensorLinux.h \
|
||||
sensors/android/WiFiSensorAndroid.h \
|
||||
sensors/StepSensor.h \
|
||||
sensors/TurnSensor.h \
|
||||
sensors/AccelerometerSensor.h \
|
||||
sensors/GyroscopeSensor.h \
|
||||
sensors/BarometerSensor.h \
|
||||
sensors/android/AccelerometerSensorAndroid.h \
|
||||
sensors/android/GyroscopeSensorAndroid.h \
|
||||
sensors/android/BarometerSensorAndroid.h \
|
||||
sensors/dummy/AccelerometerSensorDummy.h \
|
||||
sensors/dummy/GyroscopeSensorDummy.h \
|
||||
sensors/dummy/BarometerSensorDummy.h \
|
||||
sensors/Sensor.h \
|
||||
sensors/SensorFactory.h \
|
||||
sensors/WiFiSensor.h \
|
||||
misc/Debug.h \
|
||||
misc/fixc11.h \
|
||||
sensors/dummy/WiFiSensorDummy.h \
|
||||
map/MapView.h \
|
||||
map/Geometry.h \
|
||||
map/FloorRenderer.h \
|
||||
map/Ground.h \
|
||||
lib/gpc/Polygon.h \
|
||||
map/GL.h \
|
||||
Stairs.h
|
||||
Stairs.h \
|
||||
ui/map/MapView.h \
|
||||
ui/map/FloorRenderer.h \
|
||||
ui/map/gl/GL.h \
|
||||
ui/map/gl/GLHelper.h \
|
||||
ui/map/gl/GLLines.h \
|
||||
ui/map/gl/GLTriangles.h \
|
||||
ui/map/elements/Doors.h \
|
||||
ui/map/elements/Ground.h \
|
||||
ui/map/elements/Handrails.h \
|
||||
ui/map/elements/Path.h \
|
||||
ui/map/elements/Stairs.h \
|
||||
ui/map/elements/Walls.h \
|
||||
ui/Icons.h \
|
||||
ui/MainWindow.h \
|
||||
Controller.h \
|
||||
ui/menu/MainMenu.h \
|
||||
Config.h \
|
||||
ui/dialog/LoadSetupDialog.h \
|
||||
ui/debug/plot/Axes.h \
|
||||
ui/debug/plot/Plot.h \
|
||||
ui/debug/plot/Data.h \
|
||||
ui/debug/plot/Range.h \
|
||||
nav/NavController.h \
|
||||
sensors/dummy/RandomSensor.h \
|
||||
ui/debug/SensorDataWidget.h \
|
||||
ui/debug/plot/PlottWidget.h \
|
||||
ui/debug/PlotTurns.h \
|
||||
ui/debug/PlotWiFiScan.h \
|
||||
nav/State.h \
|
||||
nav/Filter.h \
|
||||
nav/Node.h \
|
||||
sensors/linux/WiFiSensorLinuxC.h \
|
||||
ui/map/gl/GLPoints.h \
|
||||
ui/map/elements/ColorPoints.h \
|
||||
sensors/offline/SensorFactoryOffline.h \
|
||||
sensors/dummy/SensorFactoryDummy.h \
|
||||
sensors/android/SensorFactoryAndroid.h \
|
||||
ui/map/gl/Shader.h \
|
||||
ui/map/elements/Object.h \
|
||||
Settings.h \
|
||||
nav/RegionalResampling.h \
|
||||
sensors/offline/AllInOneSensor.h
|
||||
|
||||
DISTFILES += \
|
||||
android-sources/src/MyActivity.java \
|
||||
res/gl/vertex1.glsl \
|
||||
res/gl/fragment1.glsl
|
||||
res/gl/fragment1.glsl \
|
||||
res/gl/tex/empty_normals.jpg
|
||||
|
||||