started working on the tex-part
started working on eval-graphics ned helper methods tested some new aspects some fixes and changes added some graphics new test-floorplan many cleanups
This commit is contained in:
@@ -64,7 +64,7 @@ ADD_DEFINITIONS(
|
|||||||
-fstack-protector-all
|
-fstack-protector-all
|
||||||
|
|
||||||
-g
|
-g
|
||||||
-O0
|
-O1
|
||||||
-DWITH_TESTS
|
-DWITH_TESTS
|
||||||
-DWITH_ASSERTIONS
|
-DWITH_ASSERTIONS
|
||||||
|
|
||||||
|
|||||||
@@ -4,7 +4,7 @@
|
|||||||
#include "MyGridNode.h"
|
#include "MyGridNode.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* allows dijkstra calculation on top of our data-structure
|
* allows BETTER dijkstra calculation on top of our data-structure
|
||||||
*/
|
*/
|
||||||
class DijkstraMapper {
|
class DijkstraMapper {
|
||||||
|
|
||||||
@@ -19,9 +19,31 @@ public:
|
|||||||
const MyGridNode* getNeighbor(const MyGridNode& node, const int idx) const {return &grid.getNeighbor(node, idx);}
|
const MyGridNode* getNeighbor(const MyGridNode& node, const int idx) const {return &grid.getNeighbor(node, idx);}
|
||||||
|
|
||||||
float getWeightBetween(const MyGridNode& n1, const MyGridNode& n2) const {
|
float getWeightBetween(const MyGridNode& n1, const MyGridNode& n2) const {
|
||||||
float d = ((Point3)n1 - (Point3)n2).length(2.0);
|
float d = ((Point3)n1 - (Point3)n2).length(2) ;
|
||||||
//if (d > 20) {d*= 1.30;}
|
//if (d > 20) {d*= 1.30;}
|
||||||
return d / std::pow(n2.imp, 3);
|
d /= std::pow(n2.imp, 3);
|
||||||
|
return d;
|
||||||
|
}
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* allows NORMAL dijkstra calculation on top of our data-structure
|
||||||
|
*/
|
||||||
|
class DijkstraMapperNormal {
|
||||||
|
|
||||||
|
Grid<MyGridNode>& grid;
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
DijkstraMapperNormal(Grid<MyGridNode>& grid) : grid(grid) {;}
|
||||||
|
|
||||||
|
int getNumNeighbors(const MyGridNode& node) const {return node.getNumNeighbors();}
|
||||||
|
|
||||||
|
const MyGridNode* getNeighbor(const MyGridNode& node, const int idx) const {return &grid.getNeighbor(node, idx);}
|
||||||
|
|
||||||
|
float getWeightBetween(const MyGridNode& n1, const MyGridNode& n2) const {
|
||||||
|
return ((Point3)n1 - (Point3)n2).length();
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -25,23 +25,23 @@ public:
|
|||||||
// if (z_cm < 360+340) {return 1;}
|
// if (z_cm < 360+340) {return 1;}
|
||||||
// if (z_cm < 360+340+340) {return 2;}
|
// if (z_cm < 360+340+340) {return 2;}
|
||||||
// return 3;
|
// return 3;
|
||||||
if (z_cm < 180) {return 0;}
|
if (z_cm < 380) {return 0;}
|
||||||
if (z_cm < 360+180) {return 1;}
|
if (z_cm < 380+340) {return 1;}
|
||||||
if (z_cm < 360+340+180) {return 2;}
|
if (z_cm < 380+340+340) {return 2;}
|
||||||
return 3;
|
return 3;
|
||||||
}
|
}
|
||||||
|
|
||||||
/** convert height (in cm) to floor-numbers */
|
/** convert height (in cm) to floor-numbers */
|
||||||
static int getFloorNrFloat(float z_cm) {
|
static int getFloorNrFloat(const float z_cm) {
|
||||||
return z_cm / 340.0f;
|
return z_cm / 350.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
static int getHeight(const int floorNr) {
|
static int getHeight(const int floorNr) {
|
||||||
switch(floorNr) {
|
switch(floorNr) {
|
||||||
case 0: return 0;
|
case 0: return 0;
|
||||||
case 1: return 360;
|
case 1: return 380;
|
||||||
case 2: return 360+340;
|
case 2: return 380+340;
|
||||||
case 3: return 360+340+340;
|
case 3: return 380+340+340;
|
||||||
default: throw "error";
|
default: throw "error";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -86,14 +86,21 @@ public:
|
|||||||
f.s23 = fpFac.getStairs("staircase_2_3");
|
f.s23 = fpFac.getStairs("staircase_2_3");
|
||||||
|
|
||||||
OldGroundTruth gtwp0(MiscSettings::floorplan, "ground_truth_0", 2.822222);
|
OldGroundTruth gtwp0(MiscSettings::floorplan, "ground_truth_0", 2.822222);
|
||||||
|
OldGroundTruth gtwp05(MiscSettings::floorplan, "ground_truth_0_5", 2.822222);
|
||||||
OldGroundTruth gtwp1(MiscSettings::floorplan, "ground_truth_1", 2.822222);
|
OldGroundTruth gtwp1(MiscSettings::floorplan, "ground_truth_1", 2.822222);
|
||||||
|
OldGroundTruth gtwp15(MiscSettings::floorplan, "ground_truth_1_5", 2.822222);
|
||||||
OldGroundTruth gtwp2(MiscSettings::floorplan, "ground_truth_2", 2.822222);
|
OldGroundTruth gtwp2(MiscSettings::floorplan, "ground_truth_2", 2.822222);
|
||||||
|
OldGroundTruth gtwp25(MiscSettings::floorplan, "ground_truth_2_5", 2.822222);
|
||||||
OldGroundTruth gtwp3(MiscSettings::floorplan, "ground_truth_3", 2.822222);
|
OldGroundTruth gtwp3(MiscSettings::floorplan, "ground_truth_3", 2.822222);
|
||||||
|
|
||||||
for (auto it : gtwp0.getWaypoints()) {f.gtwp[it.first] = Point3(it.second.x, it.second.y, getHeight(0));}
|
for (auto it : gtwp0.getWaypoints()) { if (f.gtwp.find(it.first) != f.gtwp.end()) {throw 1;} f.gtwp[it.first] = Point3(it.second.x, it.second.y, getHeight(0));}
|
||||||
for (auto it : gtwp1.getWaypoints()) {f.gtwp[it.first] = Point3(it.second.x, it.second.y, getHeight(1));}
|
for (auto it : gtwp1.getWaypoints()) { if (f.gtwp.find(it.first) != f.gtwp.end()) {throw 1;} f.gtwp[it.first] = Point3(it.second.x, it.second.y, getHeight(1));}
|
||||||
for (auto it : gtwp2.getWaypoints()) {f.gtwp[it.first] = Point3(it.second.x, it.second.y, getHeight(2));}
|
for (auto it : gtwp2.getWaypoints()) { if (f.gtwp.find(it.first) != f.gtwp.end()) {throw 1;} f.gtwp[it.first] = Point3(it.second.x, it.second.y, getHeight(2));}
|
||||||
for (auto it : gtwp3.getWaypoints()) {f.gtwp[it.first] = Point3(it.second.x, it.second.y, getHeight(3));}
|
for (auto it : gtwp3.getWaypoints()) { if (f.gtwp.find(it.first) != f.gtwp.end()) {throw 1;} f.gtwp[it.first] = Point3(it.second.x, it.second.y, getHeight(3));}
|
||||||
|
|
||||||
|
for (auto it : gtwp05.getWaypoints()) { if (f.gtwp.find(it.first) != f.gtwp.end()) {throw 1;} f.gtwp[it.first] = Point3(it.second.x, it.second.y, (getHeight(0)+getHeight(1))/2);}
|
||||||
|
for (auto it : gtwp15.getWaypoints()) { if (f.gtwp.find(it.first) != f.gtwp.end()) {throw 1;} f.gtwp[it.first] = Point3(it.second.x, it.second.y, (getHeight(1)+getHeight(2))/2);}
|
||||||
|
for (auto it : gtwp25.getWaypoints()) { if (f.gtwp.find(it.first) != f.gtwp.end()) {throw 1;} f.gtwp[it.first] = Point3(it.second.x, it.second.y, (getHeight(2)+getHeight(3))/2);}
|
||||||
|
|
||||||
return f;
|
return f;
|
||||||
|
|
||||||
@@ -112,16 +119,15 @@ public:
|
|||||||
gridFac.addStairs(floors.s12, floors.h1.cm(), floors.h2.cm());
|
gridFac.addStairs(floors.s12, floors.h1.cm(), floors.h2.cm());
|
||||||
gridFac.addStairs(floors.s23, floors.h2.cm(), floors.h3.cm());
|
gridFac.addStairs(floors.s23, floors.h2.cm(), floors.h3.cm());
|
||||||
|
|
||||||
// maybe the two sides are wrong?
|
|
||||||
PlatformStair psUpperLeft;
|
PlatformStair psUpperLeft;
|
||||||
psUpperLeft.platform = BBox2(Point2(1560, 4778), Point2(1730, 5128));
|
psUpperLeft.platform = BBox2(Point2(1560, 4778), Point2(1730, 5128));
|
||||||
psUpperLeft.s1 = Stair(Line2( 1278,4790+000, 1278,4790+140 ), Point2(+280,0));
|
psUpperLeft.s1 = Stair(Line2( 1278,4790+160, 1278,4790+160+140 ), Point2(+280,0));
|
||||||
psUpperLeft.s2 = Stair(Line2( 1278,4790+160, 1278,4790+160+140 ), Point2(+280,0));
|
psUpperLeft.s2 = Stair(Line2( 1278,4790+000, 1278,4790+140 ), Point2(+280,0));
|
||||||
gridFac.buildPlatformStair(psUpperLeft, floors.h0.cm(), floors.h1.cm());
|
gridFac.buildPlatformStair(psUpperLeft, floors.h0.cm(), floors.h1.cm());
|
||||||
gridFac.buildPlatformStair(psUpperLeft, floors.h1.cm(), floors.h2.cm());
|
gridFac.buildPlatformStair(psUpperLeft, floors.h1.cm(), floors.h2.cm());
|
||||||
gridFac.buildPlatformStair(psUpperLeft, floors.h2.cm(), floors.h3.cm());
|
gridFac.buildPlatformStair(psUpperLeft, floors.h2.cm(), floors.h3.cm());
|
||||||
// vis.gp << "set xrange [1100:1800]\n";
|
// vis.gp << "set xrange [1100:1800]\n";
|
||||||
// vis.gp << "set yrange [4500:5200]\n";
|
// vis.gp << "set yrange [4500:5200]\n";
|
||||||
|
|
||||||
PlatformStair psUpperRight;
|
PlatformStair psUpperRight;
|
||||||
psUpperRight.platform = BBox2(Point2(6290, 4778), Point2(6500, 5098));
|
psUpperRight.platform = BBox2(Point2(6290, 4778), Point2(6500, 5098));
|
||||||
|
|||||||
@@ -15,6 +15,9 @@ struct MyGridNode : public GridNode, public GridPoint {
|
|||||||
/** node importance based on surroundings */
|
/** node importance based on surroundings */
|
||||||
float imp = 1.0;
|
float imp = 1.0;
|
||||||
|
|
||||||
|
/** used for eval */
|
||||||
|
int cnt = 0;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
/** needed ctor */
|
/** needed ctor */
|
||||||
|
|||||||
@@ -10,13 +10,14 @@
|
|||||||
|
|
||||||
namespace MiscSettings {
|
namespace MiscSettings {
|
||||||
|
|
||||||
const std::string floorplan = "/mnt/data/workspaces/Fusion2016/code/plan.svg";
|
const std::string floorplan = "/mnt/data/workspaces/Fusion2016/code/plan_new.svg";
|
||||||
|
const std::string floorplanPlot = "/mnt/data/workspaces/Fusion2016/code/plan_plots.svg";
|
||||||
|
|
||||||
const int gridSize_cm = 40;
|
const int gridSize_cm = 20;
|
||||||
|
|
||||||
const int timeSteps = 500;
|
const int timeSteps = 500;
|
||||||
|
|
||||||
const int numParticles = 2500;
|
const int numParticles = 7500;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
31
code/Vis.h
31
code/Vis.h
@@ -9,9 +9,12 @@
|
|||||||
|
|
||||||
#include <Indoor/geo/Length.h>
|
#include <Indoor/geo/Length.h>
|
||||||
#include <Indoor/floorplan/Floor.h>
|
#include <Indoor/floorplan/Floor.h>
|
||||||
|
#include <Indoor/geo/Angle.h>
|
||||||
|
#include <Indoor/grid/walk/GridWalkState.h>
|
||||||
|
|
||||||
#include "eval/GroundTruthWay.h"
|
#include "eval/GroundTruthWay.h"
|
||||||
|
|
||||||
|
|
||||||
class Vis {
|
class Vis {
|
||||||
|
|
||||||
public:
|
public:
|
||||||
@@ -22,6 +25,7 @@ public:
|
|||||||
K::GnuplotSplotElementColorPoints gridNodes;
|
K::GnuplotSplotElementColorPoints gridNodes;
|
||||||
K::GnuplotSplotElementLines gridEdges;
|
K::GnuplotSplotElementLines gridEdges;
|
||||||
K::GnuplotSplotElementPoints particles;
|
K::GnuplotSplotElementPoints particles;
|
||||||
|
K::GnuplotSplotElementLines particleDir;
|
||||||
K::GnuplotSplotElementLines groundTruth;
|
K::GnuplotSplotElementLines groundTruth;
|
||||||
K::GnuplotSplotElementLines estPath;
|
K::GnuplotSplotElementLines estPath;
|
||||||
|
|
||||||
@@ -42,12 +46,17 @@ public:
|
|||||||
groundTruth.setLineWidth(2);
|
groundTruth.setLineWidth(2);
|
||||||
groundTruth.setColorHex("#666666");
|
groundTruth.setColorHex("#666666");
|
||||||
|
|
||||||
|
particles.setColorHex("#0000ff");
|
||||||
|
particles.setPointSize(0.3);
|
||||||
|
particleDir.setColorHex("#444444");
|
||||||
|
|
||||||
estPath.setLineWidth(2);
|
estPath.setLineWidth(2);
|
||||||
|
|
||||||
// attach all layers
|
// attach all layers
|
||||||
splot.add(&floors);
|
splot.add(&floors);
|
||||||
splot.add(&gridNodes);
|
splot.add(&gridNodes);
|
||||||
splot.add(&gridEdges);
|
splot.add(&gridEdges);
|
||||||
|
splot.add(&particleDir);
|
||||||
splot.add(&particles);
|
splot.add(&particles);
|
||||||
splot.add(&groundTruth);
|
splot.add(&groundTruth);
|
||||||
splot.add(&estPath);
|
splot.add(&estPath);
|
||||||
@@ -71,6 +80,8 @@ public:
|
|||||||
/** add the grid to the plot */
|
/** add the grid to the plot */
|
||||||
template <typename T> Vis& addGrid(Grid<T>& grid) {
|
template <typename T> Vis& addGrid(Grid<T>& grid) {
|
||||||
|
|
||||||
|
std::set<uint64_t> used;
|
||||||
|
|
||||||
float max = 0;
|
float max = 0;
|
||||||
for (const T& n1 : grid) {
|
for (const T& n1 : grid) {
|
||||||
if (n1.distToTarget > max) {max = n1.distToTarget;}
|
if (n1.distToTarget > max) {max = n1.distToTarget;}
|
||||||
@@ -84,10 +95,14 @@ public:
|
|||||||
//const float color = n1.distToTarget/max;
|
//const float color = n1.distToTarget/max;
|
||||||
const float color = 0;
|
const float color = 0;
|
||||||
gridNodes.add(p1, color);
|
gridNodes.add(p1, color);
|
||||||
// for (const T& n2 : grid.neighbors(n1)) {
|
for (const T& n2 : grid.neighbors(n1)) {
|
||||||
// const K::GnuplotPoint3 p2(n2.x_cm, n2.y_cm, n2.z_cm);
|
const uint64_t idx = n1.getIdx() * n2.getIdx();
|
||||||
// gridEdges.addSegment(p1, p2);
|
if (used.find(idx) == used.end()) {
|
||||||
// }
|
const K::GnuplotPoint3 p2(n2.x_cm, n2.y_cm, n2.z_cm);
|
||||||
|
gridEdges.addSegment(p1, p2);
|
||||||
|
used.insert(idx);
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
@@ -119,6 +134,7 @@ public:
|
|||||||
|
|
||||||
void clearStates() {
|
void clearStates() {
|
||||||
particles.clear();
|
particles.clear();
|
||||||
|
particleDir.clear();
|
||||||
}
|
}
|
||||||
|
|
||||||
void addObject(const int idx, const Point3& p) {
|
void addObject(const int idx, const Point3& p) {
|
||||||
@@ -136,9 +152,14 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> void addState(const GridWalkState<T>& n) {
|
template <typename T> void addState(const GridWalkState<T>& n) {
|
||||||
particles.add(K::GnuplotPoint3(n.node->x_cm, n.node->y_cm, n.node->z_cm));
|
Point2 dir = Angle::getPointer(n.heading.getRAD());
|
||||||
|
K::GnuplotPoint3 p1(n.node->x_cm, n.node->y_cm, n.node->z_cm);
|
||||||
|
K::GnuplotPoint3 p2 = p1 + K::GnuplotPoint3(dir.x, dir.y, 0) * 85;
|
||||||
|
particles.add(p1);
|
||||||
|
particleDir.addSegment(p1, p2);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
template <typename T> Vis& showStates(std::vector<GridWalkState<T>>& states) {
|
template <typename T> Vis& showStates(std::vector<GridWalkState<T>>& states) {
|
||||||
particles.clear();;
|
particles.clear();;
|
||||||
for (const GridWalkState<T>& n : states) {
|
for (const GridWalkState<T>& n : states) {
|
||||||
|
|||||||
@@ -18,50 +18,53 @@ public:
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
Eval() {
|
// Eval() {
|
||||||
|
|
||||||
|
|
||||||
pf = new K::ParticleFilter<MyState, MyControl, MyObservation>( MiscSettings::numParticles, std::unique_ptr<MyInitializer>(new MyInitializer(grid, 1120, 150, 3*350, 90)) );
|
// pf = new K::ParticleFilter<MyState, MyControl, MyObservation>( MiscSettings::numParticles, std::unique_ptr<MyInitializer>(new MyInitializer(grid, 1120, 150, 3*350, 90)) );
|
||||||
|
|
||||||
MyGridNode& start = (MyGridNode&)grid.getNodeFor(GridPoint(500,300,floors.h0.cm()));
|
// MyGridNode& start = (MyGridNode&)grid.getNodeFor(GridPoint(500,300,floors.h0.cm()));
|
||||||
MyGridNode& end = (MyGridNode&)grid.getNodeFor(GridPoint(7000,5000,floors.h3.cm()));
|
// MyGridNode& end = (MyGridNode&)grid.getNodeFor(GridPoint(7000,5000,floors.h3.cm()));
|
||||||
|
|
||||||
//GridWalkLightAtTheEndOfTheTunnel<MyGridNode>* walk = new GridWalkLightAtTheEndOfTheTunnel<MyGridNode>(grid, DijkstraMapper(grid), end);
|
// //GridWalkRandomHeadingUpdate<MyGridNode>* walk = new GridWalkRandomHeadingUpdate<MyGridNode>();
|
||||||
//GridWalkRandomHeadingUpdate<MyGridNode>* walk = new GridWalkRandomHeadingUpdate<MyGridNode>();
|
// GridWalkRandomHeadingUpdateAdv<MyGridNode>* walk = new GridWalkRandomHeadingUpdateAdv<MyGridNode>();
|
||||||
GridWalkRandomHeadingUpdateAdv<MyGridNode>* walk = new GridWalkRandomHeadingUpdateAdv<MyGridNode>();
|
// //GridWalkPushForward<MyGridNode>* walk = new GridWalkPushForward<MyGridNode>();
|
||||||
//GridWalkPushForward<MyGridNode>* walk = new GridWalkPushForward<MyGridNode>();
|
// //GridWalkLightAtTheEndOfTheTunnel<MyGridNode>* walk = new GridWalkLightAtTheEndOfTheTunnel<MyGridNode>(grid, DijkstraMapper(grid), end);
|
||||||
|
|
||||||
pf->setTransition( std::unique_ptr<MyTransition>( new MyTransition(grid, *walk)) );
|
// pf->setTransition( std::unique_ptr<MyTransition>( new MyTransition(grid, *walk)) );
|
||||||
|
|
||||||
sr = new SensorReader("./measurements/13/Galaxy/Path2/1433588396094.csv");
|
// sr = new SensorReader("./measurements/13/Galaxy/Path2/1433588396094.csv");
|
||||||
srt = new SensorReaderTurn("./measurements/13/Galaxy/Path2/Turns.txt");
|
// srt = new SensorReaderTurn("./measurements/13/Galaxy/Path2/Turns.txt");
|
||||||
srs = new SensorReaderStep("./measurements/13/Galaxy/Path2/Steps2.txt");
|
// srs = new SensorReaderStep("./measurements/13/Galaxy/Path2/Steps2.txt");
|
||||||
|
|
||||||
gtw = getGroundTruthWay(*sr, floors.gtwp, way2);
|
// gtw = getGroundTruthWay(*sr, floors.gtwp, way2);
|
||||||
|
|
||||||
}
|
// }
|
||||||
|
|
||||||
|
// //wifi also uniform dist 0/1 fuer bereiche die OK sind?
|
||||||
|
// //steps hochzaehlen weil mehr als einer in einer transition??
|
||||||
|
// //increase regional average region
|
||||||
|
|
||||||
|
// void setEval1() {
|
||||||
|
|
||||||
|
|
||||||
|
// runName = "TODO";
|
||||||
|
|
||||||
void setEval1() {
|
// // the particle filter's evaluation method
|
||||||
|
// std::unique_ptr<MyEvaluation> eval = std::unique_ptr<MyEvaluation>( new MyEvaluation() );
|
||||||
|
// eval.get()->setUsage(true, false, false, true, true);
|
||||||
|
// pf->setEvaluation( std::move(eval) );
|
||||||
|
|
||||||
|
// // resampling step?
|
||||||
|
// pf->setNEffThreshold(1.0);
|
||||||
|
// pf->setResampling( std::unique_ptr<K::ParticleFilterResamplingSimple<MyState>>(new K::ParticleFilterResamplingSimple<MyState>()) );
|
||||||
|
|
||||||
runName = "TODO";
|
// // state estimation step
|
||||||
|
// //pf->setEstimation( std::unique_ptr<K::ParticleFilterEstimationWeightedAverage<MyState>>(new K::ParticleFilterEstimationWeightedAverage<MyState>()));
|
||||||
|
// //pf->setEstimation( std::unique_ptr<K::ParticleFilterEstimationRegionalWeightedAverage<MyState>>(new K::ParticleFilterEstimationRegionalWeightedAverage<MyState>()));
|
||||||
|
// pf->setEstimation( std::unique_ptr<K::ParticleFilterEstimationOrderedWeightedAverage<MyState>>(new K::ParticleFilterEstimationOrderedWeightedAverage<MyState>(0.33f)));
|
||||||
|
|
||||||
// the particle filter's evaluation method
|
// }
|
||||||
std::unique_ptr<MyEvaluation> eval = std::unique_ptr<MyEvaluation>( new MyEvaluation() );
|
|
||||||
eval.get()->setUsage(true, false, false, true, true);
|
|
||||||
pf->setEvaluation( std::move(eval) );
|
|
||||||
|
|
||||||
// resampling step?
|
|
||||||
pf->setNEffThreshold(1.0);
|
|
||||||
pf->setResampling( std::unique_ptr<K::ParticleFilterResamplingSimple<MyState>>(new K::ParticleFilterResamplingSimple<MyState>()) );
|
|
||||||
|
|
||||||
// state estimation step
|
|
||||||
pf->setEstimation( std::unique_ptr<K::ParticleFilterEstimationWeightedAverage<MyState>>(new K::ParticleFilterEstimationWeightedAverage<MyState>()));
|
|
||||||
//pf->setEstimation( std::unique_ptr<K::ParticleFilterEstimationRegionalWeightedAverage<MyState>>(new K::ParticleFilterEstimationRegionalWeightedAverage<MyState>()));
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
98
code/eval/Eval1.h
Normal file
98
code/eval/Eval1.h
Normal file
@@ -0,0 +1,98 @@
|
|||||||
|
#ifndef EVAL1_H
|
||||||
|
#define EVAL1_H
|
||||||
|
|
||||||
|
#include "EvalBase.h"
|
||||||
|
#include "../DijkstraMapper.h"
|
||||||
|
#include <Indoor/grid/walk/GridWalkRandomHeadingUpdate.h>
|
||||||
|
#include <Indoor/grid/walk/GridWalkRandomHeadingUpdateAdv.h>
|
||||||
|
#include <Indoor/grid/walk/GridWalkPushForward.h>
|
||||||
|
#include <Indoor/grid/walk/GridWalkLightAtTheEndOfTheTunnel.h>
|
||||||
|
#include <Indoor/grid/walk/GridWalkSimpleControl.h>
|
||||||
|
|
||||||
|
#include <KLib/math/filter/particles/resampling/ParticleFilterResamplingSimple.h>
|
||||||
|
#include <KLib/math/filter/particles/resampling/ParticleFilterResamplingPercent.h>
|
||||||
|
|
||||||
|
#include <KLib/math/filter/particles/estimation/ParticleFilterEstimationWeightedAverage.h>
|
||||||
|
#include <KLib/math/filter/particles/estimation/ParticleFilterEstimationRegionalWeightedAverage.h>
|
||||||
|
#include <KLib/math/filter/particles/estimation/ParticleFilterEstimationOrderedWeightedAverage.h>
|
||||||
|
|
||||||
|
class Eval1 : public EvalBase {
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
Eval1() {
|
||||||
|
|
||||||
|
|
||||||
|
pf = new K::ParticleFilter<MyState, MyControl, MyObservation>( MiscSettings::numParticles, std::unique_ptr<MyInitializer>(new MyInitializer(grid, 1120, 150, 3*350, 90)) );
|
||||||
|
|
||||||
|
std::vector<int> wp = path1; std::reverse(wp.begin(), wp.end());
|
||||||
|
|
||||||
|
MyGridNode& start = (MyGridNode&)grid.getNodeFor( conv(floors.gtwp[wp.front()]) );
|
||||||
|
MyGridNode& end = (MyGridNode&)grid.getNodeFor( conv(floors.gtwp[wp.back()]) );
|
||||||
|
|
||||||
|
//GridWalkRandomHeadingUpdate<MyGridNode>* walk = new GridWalkRandomHeadingUpdate<MyGridNode>();
|
||||||
|
//GridWalkRandomHeadingUpdateAdv<MyGridNode>* walk = new GridWalkRandomHeadingUpdateAdv<MyGridNode>();
|
||||||
|
//GridWalkPushForward<MyGridNode>* walk = new GridWalkPushForward<MyGridNode>();
|
||||||
|
//GridWalkLightAtTheEndOfTheTunnel<MyGridNode>* walk = new GridWalkLightAtTheEndOfTheTunnel<MyGridNode>(grid, DijkstraMapper(grid), end);
|
||||||
|
GridWalkSimpleControl<MyGridNode>* walk = new GridWalkSimpleControl<MyGridNode>();
|
||||||
|
|
||||||
|
pf->setTransition( std::unique_ptr<MyTransition>( new MyTransition(grid, *walk)) );
|
||||||
|
|
||||||
|
// path1
|
||||||
|
//sr = new SensorReader("./measurements/path1/1/1454345312844.csv"); // forward
|
||||||
|
//srt = new SensorReaderTurn("./measurements/path1/1/Turns.txt");
|
||||||
|
//srs = new SensorReaderStep("./measurements/path1/1/Steps2.txt");
|
||||||
|
sr = new SensorReader("./measurements/path1/2/1454345421125.csv"); // backward
|
||||||
|
srt = new SensorReaderTurn("./measurements/path1/2/Turns.txt");
|
||||||
|
srs = new SensorReaderStep("./measurements/path1/2/Steps2.txt");
|
||||||
|
|
||||||
|
// path2
|
||||||
|
//sr = new SensorReader("./measurements/path2/1/1454345775306.csv"); // forward
|
||||||
|
//srt = new SensorReaderTurn("./measurements/path2/1/Turns.txt");
|
||||||
|
//srs = new SensorReaderStep("./measurements/path2/1/Steps2.txt");
|
||||||
|
//sr = new SensorReader("./measurements/path2/2/1454346071347.csv"); // backward
|
||||||
|
//srt = new SensorReaderTurn("./measurements/path2/2/Turns.txt");
|
||||||
|
//srs = new SensorReaderStep("./measurements/path2/2/Steps2.txt");
|
||||||
|
|
||||||
|
// path3
|
||||||
|
// sr = new SensorReader("./measurements/path3/1/1454345546308.csv"); // forward
|
||||||
|
// srt = new SensorReaderTurn("./measurements/path3/1/Turns.txt");
|
||||||
|
// srs = new SensorReaderStep("./measurements/path3/1/Steps2.txt");
|
||||||
|
// sr = new SensorReader("./measurements/path3/2/1454345622819.csv"); // backward
|
||||||
|
// srt = new SensorReaderTurn("./measurements/path3/2/Turns.txt");
|
||||||
|
// srs = new SensorReaderStep("./measurements/path3/2/Steps2.txt");
|
||||||
|
|
||||||
|
|
||||||
|
gtw = getGroundTruthWay(*sr, floors.gtwp, wp);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
//wifi also uniform dist 0/1 fuer bereiche die OK sind?
|
||||||
|
//steps hochzaehlen weil mehr als einer in einer transition??
|
||||||
|
//increase regional average region
|
||||||
|
|
||||||
|
void setEval1() {
|
||||||
|
|
||||||
|
|
||||||
|
runName = "TODO";
|
||||||
|
|
||||||
|
// the particle filter's evaluation method
|
||||||
|
std::unique_ptr<MyEvaluation> eval = std::unique_ptr<MyEvaluation>( new MyEvaluation() );
|
||||||
|
eval.get()->setUsage(true, true, true, true, true); // TODO: STEP TURN
|
||||||
|
pf->setEvaluation( std::move(eval) );
|
||||||
|
|
||||||
|
// resampling step?
|
||||||
|
pf->setNEffThreshold(1.0);
|
||||||
|
pf->setResampling( std::unique_ptr<K::ParticleFilterResamplingSimple<MyState>>(new K::ParticleFilterResamplingSimple<MyState>()) );
|
||||||
|
//pf->setResampling( std::unique_ptr<K::ParticleFilterResamplingPercent<MyState>>(new K::ParticleFilterResamplingPercent<MyState>(0.10)) );
|
||||||
|
|
||||||
|
// state estimation step
|
||||||
|
//pf->setEstimation( std::unique_ptr<K::ParticleFilterEstimationWeightedAverage<MyState>>(new K::ParticleFilterEstimationWeightedAverage<MyState>()));
|
||||||
|
//pf->setEstimation( std::unique_ptr<K::ParticleFilterEstimationRegionalWeightedAverage<MyState>>(new K::ParticleFilterEstimationRegionalWeightedAverage<MyState>()));
|
||||||
|
pf->setEstimation( std::unique_ptr<K::ParticleFilterEstimationOrderedWeightedAverage<MyState>>(new K::ParticleFilterEstimationOrderedWeightedAverage<MyState>(0.50f)));
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // EVAL1_H
|
||||||
@@ -47,9 +47,16 @@ protected:
|
|||||||
std::string runName;
|
std::string runName;
|
||||||
|
|
||||||
GroundTruthWay gtw;
|
GroundTruthWay gtw;
|
||||||
std::vector<int> way0 = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 2, 1, 0};
|
|
||||||
std::vector<int> way1 = {29, 28, 27, 26, 25, 24, 23, 22, 21, 20, 13, 14, 15, 16, 17, 18, 19, 2, 1, 0};
|
// OLD
|
||||||
std::vector<int> way2 = {29, 28, 27, 10, 9, 8, 7, 6, 5, 4, 3, 2, 1, 0, 1, 2, 19, 18, 17, 16, 15, 14, 13, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29};
|
//std::vector<int> way0 = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 2, 1, 0};
|
||||||
|
//std::vector<int> way1 = {29, 28, 27, 26, 25, 24, 23, 22, 21, 20, 13, 14, 15, 16, 17, 18, 19, 2, 1, 0};
|
||||||
|
//std::vector<int> way2 = {29, 28, 27, 10, 9, 8, 7, 6, 5, 4, 3, 2, 1, 0, 1, 2, 19, 18, 17, 16, 15, 14, 13, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29};
|
||||||
|
|
||||||
|
// NEW
|
||||||
|
std::vector<int> path1 = {29, 28,27,26,255,25,24,23,22,21,20};
|
||||||
|
std::vector<int> path2 = {19, 18, 17, 16, 15, 14, 13, 12, 11, 10, 9, 8, 23, 7, 6};
|
||||||
|
std::vector<int> path3 = {5, 27, 26, 255, 25, 4, 3, 2, 215, 1, 0, 30, 31};
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
@@ -66,13 +73,17 @@ public:
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static GridPoint conv(const Point3& p) {
|
||||||
|
return GridPoint(p.x, p.y, p.z);
|
||||||
|
}
|
||||||
|
|
||||||
GroundTruthWay getGroundTruthWay(SensorReader& sr, const std::unordered_map<int, Point3>& waypoints, std::vector<int> ids) {
|
GroundTruthWay getGroundTruthWay(SensorReader& sr, const std::unordered_map<int, Point3>& waypoints, std::vector<int> ids) {
|
||||||
|
|
||||||
// construct the ground-truth-path by using all contained waypoint ids
|
// construct the ground-truth-path by using all contained waypoint ids
|
||||||
std::vector<Point3> path;
|
std::vector<Point3> path;
|
||||||
for (int id : ids) {
|
for (int id : ids) {
|
||||||
auto it = waypoints.find(id);
|
auto it = waypoints.find(id);
|
||||||
assert(it != waypoints.end());
|
if(it == waypoints.end()) {throw "not found";}
|
||||||
path.push_back(it->second);
|
path.push_back(it->second);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -138,6 +149,11 @@ public:
|
|||||||
|
|
||||||
// the to-be-evaluated observation
|
// the to-be-evaluated observation
|
||||||
MyObservation obs;
|
MyObservation obs;
|
||||||
|
obs.step = new StepObservation(); obs.step->steps = 0;
|
||||||
|
obs.turn = new TurnObservation(); obs.turn->delta_heading = 0; obs.turn->delta_motion = 0;
|
||||||
|
|
||||||
|
// control data
|
||||||
|
MyControl ctrl;
|
||||||
|
|
||||||
|
|
||||||
std::vector<Point3> pathEst;
|
std::vector<Point3> pathEst;
|
||||||
@@ -148,7 +164,8 @@ public:
|
|||||||
K::Statistics<double> stats;
|
K::Statistics<double> stats;
|
||||||
int cnt = 0;
|
int cnt = 0;
|
||||||
|
|
||||||
// process each sensor reading
|
|
||||||
|
// process each single sensor reading
|
||||||
while(sr->hasNext()) {
|
while(sr->hasNext()) {
|
||||||
|
|
||||||
// get the next sensor reading from the CSV
|
// get the next sensor reading from the CSV
|
||||||
@@ -187,58 +204,39 @@ public:
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// process all occurred turns
|
||||||
|
while (!step_observations.empty() && current_time > step_observations.front().ts) {
|
||||||
|
const StepObservation _so = step_observations.front(); step_observations.pop_front(); (void) _so;
|
||||||
|
obs.step->steps++;
|
||||||
|
ctrl.walked_m = obs.step->steps * 0.71;
|
||||||
|
}
|
||||||
|
|
||||||
// scheduled transition every 500 ms
|
// process all occurred steps
|
||||||
if (lastTransitionTS == 0) {lastTransitionTS = se.ts;}
|
while (!turn_observations.empty() && current_time > turn_observations.front().ts) {
|
||||||
for ( ; se.ts - lastTransitionTS > MiscSettings::timeSteps; lastTransitionTS += MiscSettings::timeSteps) {
|
const TurnObservation _to = turn_observations.front(); turn_observations.pop_front();
|
||||||
|
obs.turn->delta_heading += _to.delta_heading;
|
||||||
|
obs.turn->delta_motion += _to.delta_motion;
|
||||||
|
ctrl.headingChange_rad = Angle::degToRad(obs.turn->delta_heading);
|
||||||
|
|
||||||
//Steps are sorted in the list by timestamp.
|
}
|
||||||
//If the current observation timestamp is bigger/equal
|
|
||||||
//to the current step timestamp, use this step as observation
|
|
||||||
//and remove it from the list.
|
|
||||||
//The new first timestamp in the list will be then be the next one (timestamp-wise)
|
|
||||||
StepObservation so;
|
|
||||||
if(current_time >= step_observations.front().ts && !step_observations.empty()) {
|
|
||||||
so.step = true;
|
|
||||||
so.ts = current_time;
|
|
||||||
|
|
||||||
obs.step = &so;
|
|
||||||
step_observations.pop_front();
|
|
||||||
|
|
||||||
}
|
// time for a transition?
|
||||||
else {
|
if (se.ts - lastTransitionTS > MiscSettings::timeSteps) {
|
||||||
so.step = false;
|
|
||||||
so.ts = current_time;
|
|
||||||
|
|
||||||
obs.step = &so;
|
|
||||||
}
|
|
||||||
|
|
||||||
TurnObservation to;
|
|
||||||
//same principal as for steps is applied for turns
|
|
||||||
if(current_time >= turn_observations.front().ts && !turn_observations.empty()) {
|
|
||||||
to = turn_observations.front();
|
|
||||||
obs.turn = &to;
|
|
||||||
|
|
||||||
turn_observations.pop_front();
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
to.delta_heading = 0.0;
|
|
||||||
to.delta_motion = 0.0;
|
|
||||||
|
|
||||||
obs.turn = &to;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
lastTransitionTS = se.ts;
|
||||||
|
|
||||||
// timed updates
|
// timed updates
|
||||||
((MyTransition*)pf->getTransition())->setCurrentTime(lastTransitionTS);
|
((MyTransition*)pf->getTransition())->setCurrentTime(lastTransitionTS);
|
||||||
|
|
||||||
|
|
||||||
// update the particle filter (transition + eval), estimate a new current position and add it to the estimated path
|
// update the particle filter (transition + eval), estimate a new current position and add it to the estimated path
|
||||||
const MyState est = pf->update(nullptr, obs);
|
const MyState est = pf->update(&ctrl, obs);
|
||||||
const Point3 curEst = est.pCur;
|
const Point3 curEst = est.pCur;
|
||||||
|
|
||||||
// error calculation. compare ground-truth to estimation
|
// error calculation. compare ground-truth to estimation
|
||||||
const Point3 curGT = gtw.getPosAtTime(se.ts - 750);
|
const int offset = 0; // 750
|
||||||
|
const Point3 curGT = gtw.getPosAtTime(se.ts - offset);
|
||||||
const Point3 diff = curEst - curGT;
|
const Point3 diff = curEst - curGT;
|
||||||
|
|
||||||
// skip the first 8 scans due to uniform distribution start
|
// skip the first 8 scans due to uniform distribution start
|
||||||
@@ -251,28 +249,31 @@ public:
|
|||||||
|
|
||||||
// plot
|
// plot
|
||||||
vis.clearStates();
|
vis.clearStates();
|
||||||
for (const K::Particle<MyState> p : pf->getParticles()) {vis.addState(p.state.walkState);}
|
for (int i = 0; i < (int) pf->getParticles().size(); i+=15) {
|
||||||
|
const K::Particle<MyState>& p = pf->getParticles()[i];
|
||||||
|
vis.addState(p.state.walkState);
|
||||||
|
}
|
||||||
vis.setTimestamp(se.ts);
|
vis.setTimestamp(se.ts);
|
||||||
vis.addGroundTruth(gtw);
|
vis.addGroundTruth(gtw);
|
||||||
vis.addEstPath(pathEst);
|
vis.addEstPath(pathEst);
|
||||||
vis.setEstAndShould(curEst, curGT);
|
vis.setEstAndShould(curEst, curGT);
|
||||||
vis.show();;
|
|
||||||
|
vis.gp << "set label 111 '" <<ctrl.walked_m << ":" << ctrl.headingChange_rad << "' at screen 0.1,0.1\n";
|
||||||
|
|
||||||
|
Point2 p1(0.1, 0.1);
|
||||||
|
Point2 p2 = p1 + Angle::getPointer(ctrl.headingChange_rad) * 0.1;
|
||||||
|
vis.gp << "set arrow 111 from screen " << p1.x<<","<<p1.y << " to screen " << p2.x<<","<<p2.y<<"\n";
|
||||||
|
|
||||||
|
vis.show();
|
||||||
|
|
||||||
|
// prevent gnuplot errors
|
||||||
|
usleep(1000*33);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
{
|
|
||||||
// vis.setShowParticles(false);
|
|
||||||
// vis.setShowTime(false);
|
|
||||||
// vis.setShowCurPos(false);
|
|
||||||
// vis.debugProcess(0, pathEst, gtw, pf, layers);
|
|
||||||
// std::ofstream out("/tmp/" + runName + ".data");
|
|
||||||
// out << vis.getDataset();
|
|
||||||
// out.close();
|
|
||||||
}
|
|
||||||
|
|
||||||
sleep(1000);
|
sleep(1000);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
95
code/eval/PaperPlot.h
Normal file
95
code/eval/PaperPlot.h
Normal file
@@ -0,0 +1,95 @@
|
|||||||
|
#ifndef PAPERPLOT_H
|
||||||
|
#define PAPERPLOT_H
|
||||||
|
|
||||||
|
#include <KLib/misc/gnuplot/Gnuplot.h>
|
||||||
|
|
||||||
|
#include <KLib/misc/gnuplot/GnuplotSplot.h>
|
||||||
|
#include <KLib/misc/gnuplot/GnuplotSplotElementLines.h>
|
||||||
|
#include <KLib/misc/gnuplot/GnuplotSplotElementPoints.h>
|
||||||
|
#include <KLib/misc/gnuplot/GnuplotSplotElementColorPoints.h>
|
||||||
|
|
||||||
|
|
||||||
|
#include <Indoor/floorplan/Floor.h>
|
||||||
|
#include <Indoor/geo/Length.h>
|
||||||
|
|
||||||
|
class PaperPlot {
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
K::Gnuplot gp;
|
||||||
|
K::GnuplotSplot plot;
|
||||||
|
|
||||||
|
K::GnuplotSplotElementLines floors;
|
||||||
|
K::GnuplotSplotElementColorPoints nodes;
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
PaperPlot() {
|
||||||
|
|
||||||
|
floors.setLineWidth(2);
|
||||||
|
|
||||||
|
plot.add(&nodes);
|
||||||
|
plot.add(&floors);
|
||||||
|
|
||||||
|
gp << "set ticslevel 0\n";
|
||||||
|
|
||||||
|
|
||||||
|
//gp << "set zrange [0:0]\n";
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void show() {
|
||||||
|
gp.draw(plot);
|
||||||
|
gp.flush();;
|
||||||
|
}
|
||||||
|
|
||||||
|
/** add all obstacles of the given floor to the provided height */
|
||||||
|
void addFloor(const Floor& f, const LengthF height) {
|
||||||
|
|
||||||
|
// add each wall
|
||||||
|
for (const Line2& l : f.getObstacles()) {
|
||||||
|
const K::GnuplotPoint3 p1(l.p1.x, l.p1.y, height.cm());
|
||||||
|
const K::GnuplotPoint3 p2(l.p2.x, l.p2.y, height.cm());
|
||||||
|
floors.addSegment(p1, p2);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
/** add the grid to the plot */
|
||||||
|
template <typename T> void addGrid(Grid<T>& grid) {
|
||||||
|
|
||||||
|
// std::set<uint64_t> used;
|
||||||
|
|
||||||
|
// get the min/max value
|
||||||
|
float max = -999999;
|
||||||
|
float min = +999999;
|
||||||
|
for (const T& n1 : grid) {
|
||||||
|
const float val = n1.imp;
|
||||||
|
//const float val = n1.distToTarget;
|
||||||
|
if (val > max) {max = val;}
|
||||||
|
if (val < min) {min = val;}
|
||||||
|
}
|
||||||
|
gp << "set cbrange["<<min<<":"<<max<<"]\n";
|
||||||
|
|
||||||
|
for (const T& n1 : grid) {
|
||||||
|
const K::GnuplotPoint3 p1(n1.x_cm, n1.y_cm, n1.z_cm);
|
||||||
|
const float color = n1.imp;
|
||||||
|
//const float color = n1.distToTarget/max;
|
||||||
|
//const float color = 0;
|
||||||
|
nodes.add(p1, color);
|
||||||
|
// for (const T& n2 : grid.neighbors(n1)) {
|
||||||
|
// const uint64_t idx = n1.getIdx() * n2.getIdx();
|
||||||
|
// if (used.find(idx) == used.end()) {
|
||||||
|
// const K::GnuplotPoint3 p2(n2.x_cm, n2.y_cm, n2.z_cm);
|
||||||
|
// gridEdges.addSegment(p1, p2);
|
||||||
|
// used.insert(idx);
|
||||||
|
// }
|
||||||
|
// }
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // PAPERPLOT_H
|
||||||
141
code/eval/PaperPlot2D.h
Normal file
141
code/eval/PaperPlot2D.h
Normal file
@@ -0,0 +1,141 @@
|
|||||||
|
#ifndef PAPERPLOT2D_H
|
||||||
|
#define PAPERPLOT2D_H
|
||||||
|
|
||||||
|
#include <KLib/misc/gnuplot/Gnuplot.h>
|
||||||
|
|
||||||
|
#include <KLib/misc/gnuplot/GnuplotPlot.h>
|
||||||
|
#include <KLib/misc/gnuplot/GnuplotPlotElementLines.h>
|
||||||
|
#include <KLib/misc/gnuplot/GnuplotPlotElementColorPoints.h>
|
||||||
|
|
||||||
|
#include <Indoor/floorplan/Floor.h>
|
||||||
|
#include <Indoor/geo/Length.h>
|
||||||
|
|
||||||
|
class PaperPlot2D {
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
struct Size {
|
||||||
|
float w;
|
||||||
|
float h;
|
||||||
|
Size(const float w, const float h) : w(w), h(h) {;}
|
||||||
|
};
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
K::Gnuplot gp;
|
||||||
|
K::GnuplotPlot plot;
|
||||||
|
|
||||||
|
K::GnuplotPlotElementLines floors;
|
||||||
|
K::GnuplotPlotElementColorPoints nodes;
|
||||||
|
|
||||||
|
std::string file;
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
PaperPlot2D(const std::string& file, Size s) : file(file) {
|
||||||
|
toFile(file, s);
|
||||||
|
setup();
|
||||||
|
}
|
||||||
|
|
||||||
|
PaperPlot2D() {
|
||||||
|
setup();
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
|
||||||
|
floors.setLineWidth(1.5);
|
||||||
|
|
||||||
|
nodes.setPointType(7);
|
||||||
|
|
||||||
|
plot.add(&nodes);
|
||||||
|
plot.add(&floors);
|
||||||
|
|
||||||
|
gp << "unset border\n";
|
||||||
|
gp << "unset colorbox\n";
|
||||||
|
|
||||||
|
gp << "set tics scale 0,0\n"; // HACK! "unset tics\n" segfaults current gnuplot version...
|
||||||
|
gp << "set format x ' '\n";
|
||||||
|
gp << "set format y ' '\n";
|
||||||
|
|
||||||
|
gp << "set size ratio -1\n";
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void toFile(const std::string& file, const Size s) {
|
||||||
|
gp << "set output '" << file << "'\n";
|
||||||
|
gp << "set terminal eps size " << s.w << "," << s.h << "\n";
|
||||||
|
}
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
void setRanges(const float x1, const float x2, const float y1, const float y2) {
|
||||||
|
gp << "set xrange [" << x1 << ":" << x2 << "]\n";
|
||||||
|
gp << "set yrange [" << y1 << ":" << y2 << "]\n";
|
||||||
|
}
|
||||||
|
|
||||||
|
void show() {
|
||||||
|
gp.draw(plot);
|
||||||
|
if (file.length() != 0) {
|
||||||
|
std::string dataFile = file + ".dat";
|
||||||
|
std::ofstream os(dataFile.c_str());
|
||||||
|
os << gp.getBuffer();
|
||||||
|
os.close();
|
||||||
|
}
|
||||||
|
gp.flush();
|
||||||
|
}
|
||||||
|
|
||||||
|
/** add all obstacles of the given floor to the provided height */
|
||||||
|
void addFloor(const Floor& f) {
|
||||||
|
|
||||||
|
// add each wall
|
||||||
|
for (const Line2& l : f.getObstacles()) {
|
||||||
|
const K::GnuplotPoint2 p1(l.p1.x, l.p1.y);
|
||||||
|
const K::GnuplotPoint2 p2(l.p2.x, l.p2.y);
|
||||||
|
floors.addSegment(p1, p2);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// void removeGrid() {
|
||||||
|
// gp << "unset object\n";
|
||||||
|
// }
|
||||||
|
|
||||||
|
/** add the grid to the plot */
|
||||||
|
template <typename T, typename Colorizer> void addGrid(Grid<T>& grid, const Colorizer col) {
|
||||||
|
|
||||||
|
// get the min/max value
|
||||||
|
float max = -999999;
|
||||||
|
float min = +999999;
|
||||||
|
for (const T& n1 : grid) {
|
||||||
|
const float val = col.get(n1);
|
||||||
|
//const float val = n1.distToTarget;
|
||||||
|
if (val > max) {max = val;}
|
||||||
|
if (val < min) {min = val;}
|
||||||
|
}
|
||||||
|
gp << "set cbrange["<<min<<":"<<max<<"]\n";
|
||||||
|
|
||||||
|
// for (const T& n1 : grid) {
|
||||||
|
// const K::GnuplotPoint2 p1(n1.x_cm, n1.y_cm);
|
||||||
|
// const float color = n1.imp;
|
||||||
|
// //const float color = n1.distToTarget/max;
|
||||||
|
// //const float color = 0;
|
||||||
|
// nodes.add(p1, color);
|
||||||
|
// }
|
||||||
|
|
||||||
|
int i = 0;
|
||||||
|
for (const T& n1 : grid) {
|
||||||
|
if (col.skip(n1)) {continue;}
|
||||||
|
gp << "set object " << (++i) << " rectangle center " << n1.x_cm << "," << n1.y_cm << " size 20,20 fs solid noborder fc palette cb " << col.get(n1) << "\n";
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#endif // PAPERPLOT2D_H
|
||||||
4
code/eval/PaperVisDijkstra.h
Normal file
4
code/eval/PaperVisDijkstra.h
Normal file
@@ -0,0 +1,4 @@
|
|||||||
|
#ifndef PAPERVISDIJKSTRA_H
|
||||||
|
#define PAPERVISDIJKSTRA_H
|
||||||
|
|
||||||
|
#endif // PAPERVISDIJKSTRA_H
|
||||||
190
code/eval/PaperVisImportance.h
Normal file
190
code/eval/PaperVisImportance.h
Normal file
@@ -0,0 +1,190 @@
|
|||||||
|
#ifndef PAPERVISIMPORTANCE_H
|
||||||
|
#define PAPERVISIMPORTANCE_H
|
||||||
|
|
||||||
|
#include <Indoor/grid/Grid.h>
|
||||||
|
#include <Indoor/grid/factory/GridFactory.h>
|
||||||
|
#include <Indoor/grid/factory/GridImportance.h>
|
||||||
|
|
||||||
|
#include <Indoor/floorplan/FloorplanFactorySVG.h>
|
||||||
|
|
||||||
|
#include <Indoor/grid/walk/GridWalkLightAtTheEndOfTheTunnel.h>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#include <Indoor/nav/dijkstra/Dijkstra.h>
|
||||||
|
#include <Indoor/nav/dijkstra/DijkstraPath.h>
|
||||||
|
|
||||||
|
#include "PaperPlot.h"
|
||||||
|
#include "PaperPlot2D.h"
|
||||||
|
|
||||||
|
#include "../MyGridNode.h"
|
||||||
|
#include "../Settings.h"
|
||||||
|
#include "../DijkstraMapper.h"
|
||||||
|
|
||||||
|
PaperPlot2D::Size s1 = PaperPlot2D::Size(2,4);
|
||||||
|
|
||||||
|
class PaperVisImportance {
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
static float clamp(const float in, const float min, const float max) {
|
||||||
|
if (in < min) {return min;}
|
||||||
|
if (in > max) {return max;}
|
||||||
|
return in;
|
||||||
|
}
|
||||||
|
|
||||||
|
// use node-importance as grid-color
|
||||||
|
struct ColorizerImp {
|
||||||
|
float get(const MyGridNode& n) const {return n.imp;}
|
||||||
|
bool skip(const MyGridNode& n) const {return false;}
|
||||||
|
};
|
||||||
|
|
||||||
|
// use node-distance as grid-color
|
||||||
|
struct ColorizerDist {
|
||||||
|
float get(const MyGridNode& n) const {return n.distToTarget;}
|
||||||
|
bool skip(const MyGridNode& n) const {return false;}
|
||||||
|
};
|
||||||
|
|
||||||
|
// use num-visited as grid-color
|
||||||
|
struct ColorizeHeat {
|
||||||
|
int maxCnt; int cutoff;
|
||||||
|
ColorizeHeat(const int maxCnt, const int cutoff) : maxCnt(maxCnt), cutoff(cutoff) {;}
|
||||||
|
float get(const MyGridNode& n) const {return (n.cnt > maxCnt) ? (maxCnt) : (n.cnt);}
|
||||||
|
bool skip(const MyGridNode& n) const {return n.cnt < cutoff;} // skip to reduce plot size
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
static void createImportance() {
|
||||||
|
|
||||||
|
// load the floorplan
|
||||||
|
FloorplanFactorySVG fpFac(MiscSettings::floorplanPlot, 2.822222);
|
||||||
|
Floor f0 = fpFac.getFloor("test1");
|
||||||
|
const LengthF h0 = LengthF::cm(0);
|
||||||
|
|
||||||
|
// add the floorplan to the grid
|
||||||
|
Grid<MyGridNode> grid(20);
|
||||||
|
GridFactory<MyGridNode> gridFac(grid);
|
||||||
|
|
||||||
|
gridFac.addFloor(f0, h0.cm());
|
||||||
|
|
||||||
|
// remove all isolated nodes not attached to 300,300,floor0
|
||||||
|
gridFac.removeIsolated( (MyGridNode&)grid.getNodeFor( GridPoint(400,400,h0.cm()) ) );
|
||||||
|
|
||||||
|
// stamp importance information onto the grid-nodes
|
||||||
|
GridImportance gridImp;
|
||||||
|
gridImp.addImportance(grid, h0.cm());
|
||||||
|
|
||||||
|
|
||||||
|
{
|
||||||
|
PaperPlot2D plot("floorplan_importance.eps", s1);
|
||||||
|
plot.setRanges(0,2100, 0,5100);
|
||||||
|
plot.addFloor(f0);
|
||||||
|
plot.addGrid(grid, ColorizerImp());
|
||||||
|
plot.show();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
static void createPath() {
|
||||||
|
|
||||||
|
// load the floorplan
|
||||||
|
FloorplanFactorySVG fpFac(MiscSettings::floorplanPlot, 2.822222);
|
||||||
|
Floor f0 = fpFac.getFloor("test1");
|
||||||
|
const LengthF h0 = LengthF::cm(0);
|
||||||
|
|
||||||
|
// add the floorplan to the grid
|
||||||
|
Grid<MyGridNode> grid(20);
|
||||||
|
GridFactory<MyGridNode> gridFac(grid);
|
||||||
|
|
||||||
|
gridFac.addFloor(f0, h0.cm());
|
||||||
|
|
||||||
|
// remove all isolated nodes not attached to 300,300,floor0
|
||||||
|
gridFac.removeIsolated( (MyGridNode&)grid.getNodeFor( GridPoint(300,300,h0.cm()) ) );
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
// start and end
|
||||||
|
const MyGridNode& gnStart = grid.getNodeFor(GridPoint(1500, 300, 0));
|
||||||
|
const MyGridNode& gnEnd = grid.getNodeFor(GridPoint(900, 4600, 0));
|
||||||
|
|
||||||
|
// build all shortest path to reach th target
|
||||||
|
Dijkstra<MyGridNode> dijkstra;
|
||||||
|
DijkstraMapper accImp(grid);
|
||||||
|
DijkstraMapperNormal accNormal(grid);
|
||||||
|
|
||||||
|
// path without importance
|
||||||
|
dijkstra.build(gnStart, gnStart, accNormal);
|
||||||
|
DijkstraPath<MyGridNode> pathNormal(dijkstra.getNode(gnEnd), dijkstra.getNode(gnStart));
|
||||||
|
|
||||||
|
// stamp importance information onto the grid-nodes
|
||||||
|
GridImportance gridImp;
|
||||||
|
gridImp.addImportance(grid, h0.cm());
|
||||||
|
|
||||||
|
// path WITH importance
|
||||||
|
dijkstra.build(gnStart, gnStart, accImp);
|
||||||
|
DijkstraPath<MyGridNode> pathImp(dijkstra.getNode(gnEnd), dijkstra.getNode(gnStart));
|
||||||
|
|
||||||
|
// build plot
|
||||||
|
K::GnuplotPlotElementLines gpPath1; gpPath1.setLineWidth(2); gpPath1.setColorHex("#444444");
|
||||||
|
K::GnuplotPlotElementLines gpPath2; gpPath2.setLineWidth(2); gpPath2.setColorHex("#000000");
|
||||||
|
|
||||||
|
for (DijkstraNode<MyGridNode>* dn : pathNormal) {
|
||||||
|
gpPath1.add(K::GnuplotPoint2(dn->element->x_cm, dn->element->y_cm));
|
||||||
|
}
|
||||||
|
for (DijkstraNode<MyGridNode>* dn : pathImp) {
|
||||||
|
gpPath2.add(K::GnuplotPoint2(dn->element->x_cm, dn->element->y_cm));
|
||||||
|
}
|
||||||
|
|
||||||
|
// plot the 2 paths
|
||||||
|
{
|
||||||
|
PaperPlot2D plot("floorplan_paths.eps", s1);
|
||||||
|
plot.setRanges(0,2100, 0,5100);
|
||||||
|
plot.addFloor(f0);
|
||||||
|
plot.plot.add(&gpPath1); gpPath1.setCustomAttr("dashtype 3");
|
||||||
|
plot.plot.add(&gpPath2);
|
||||||
|
plot.show();
|
||||||
|
}
|
||||||
|
|
||||||
|
// stamp distance information onto the grid
|
||||||
|
// attach a corresponding weight-information to each user-grid-node
|
||||||
|
for (MyGridNode& node : grid) {
|
||||||
|
const DijkstraNode<MyGridNode>* dn = dijkstra.getNode(node);
|
||||||
|
node.distToTarget = dn->cumWeight;
|
||||||
|
}
|
||||||
|
|
||||||
|
// walk
|
||||||
|
GridWalkLightAtTheEndOfTheTunnel<MyGridNode> walk (grid, accImp, gnStart);
|
||||||
|
|
||||||
|
for (int i = 0; i < 30000; ++i) {
|
||||||
|
|
||||||
|
if (i % 250 == 0) {std::cout << i << std::endl;}
|
||||||
|
const MyGridNode& nStart = gnEnd;
|
||||||
|
GridWalkState<MyGridNode> sStart(&nStart, Heading::rnd());
|
||||||
|
GridWalkState<MyGridNode> sEnd = walk.getDestination(grid, sStart, 135, 0);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// plot the heat-map
|
||||||
|
{
|
||||||
|
PaperPlot2D plot("floorplan_dijkstra_heatmap.eps", s1);
|
||||||
|
plot.setRanges(0,2100, 0,5100);
|
||||||
|
plot.gp << "set palette gray negative\n";
|
||||||
|
plot.addFloor(f0);
|
||||||
|
plot.addGrid(grid, ColorizeHeat(7000, 50));
|
||||||
|
plot.show();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // PAPERVISIMPORTANCE_H
|
||||||
@@ -44,7 +44,7 @@ public:
|
|||||||
|
|
||||||
// floor difference?
|
// floor difference?
|
||||||
//const double floorDist = std::abs(beacon->zNr - state.getFloorNr());
|
//const double floorDist = std::abs(beacon->zNr - state.getFloorNr());
|
||||||
const float floorDist = std::round(std::abs(Helper::getFloorNrFloat(beacon->z) - Helper::getFloorNrFloat(state.pCur.z)));
|
const float floorDist = std::ceil(std::abs(Helper::getFloorNrFloat(beacon->z) - Helper::getFloorNrFloat(state.pCur.z)));
|
||||||
|
|
||||||
// estimate the rssi depending on above distance
|
// estimate the rssi depending on above distance
|
||||||
const double mdlRSSI = distanceToRssi(beacon->tx, distToBeacon_m, beacon->pl) - (floorDist * waf);
|
const double mdlRSSI = distanceToRssi(beacon->tx, distToBeacon_m, beacon->pl) - (floorDist * waf);
|
||||||
@@ -57,7 +57,7 @@ public:
|
|||||||
// const double mdlRelRSSI = mdlStrongestRSSI - mdlRSSI;
|
// const double mdlRelRSSI = mdlStrongestRSSI - mdlRSSI;
|
||||||
|
|
||||||
// probability? (sigma grows with measurement's age)
|
// probability? (sigma grows with measurement's age)
|
||||||
const double sigma = 8 + ((observation.latestSensorDataTS - entry.ts) / 1000.0) * 2.0;
|
const double sigma = 8 + ((observation.latestSensorDataTS - entry.ts) / 1000.0) * 3.0;
|
||||||
const double p = K::NormalDistribution::getProbability(mdlRSSI, sigma, realRSSI);
|
const double p = K::NormalDistribution::getProbability(mdlRSSI, sigma, realRSSI);
|
||||||
//const double p = K::NormalDistribution::getProbability(mdlRelRSSI, sigma, realRelRSSI);
|
//const double p = K::NormalDistribution::getProbability(mdlRelRSSI, sigma, realRelRSSI);
|
||||||
|
|
||||||
|
|||||||
@@ -25,7 +25,7 @@ public:
|
|||||||
|
|
||||||
addAP(("00:04:96:6b:64:99"), "i.3.20", 290, 1300, Helper::getHeight(3), tx, pl);
|
addAP(("00:04:96:6b:64:99"), "i.3.20", 290, 1300, Helper::getHeight(3), tx, pl);
|
||||||
addAP(("00:04:96:6b:70:c9"), "i.3.25", 290, 3930, Helper::getHeight(3), tx, pl);
|
addAP(("00:04:96:6b:70:c9"), "i.3.25", 290, 3930, Helper::getHeight(3), tx, pl);
|
||||||
addAP(("00:04:96:6b:82:79"), "i.3.16", 1860, 3400, Helper::getHeight(3), tx, pl-1);
|
addAP(("00:04:96:6b:82:79"), "i.3.16", 1860, 3400, Helper::getHeight(3), tx, pl);
|
||||||
addAP(("00:04:96:77:ed:f9"), "i.3.39", 4700, 4850, Helper::getHeight(3), tx, pl);
|
addAP(("00:04:96:77:ed:f9"), "i.3.39", 4700, 4850, Helper::getHeight(3), tx, pl);
|
||||||
addAP(("00:04:96:77:ed:69"), "i.3.3", 6460, 3400, Helper::getHeight(3), tx, pl);
|
addAP(("00:04:96:77:ed:69"), "i.3.3", 6460, 3400, Helper::getHeight(3), tx, pl);
|
||||||
|
|
||||||
@@ -52,25 +52,62 @@ public:
|
|||||||
addAP(("00:04:96:6B:46:09"), "I.0.xx", 6860, 3690, Helper::getHeight(0), tx, pl);
|
addAP(("00:04:96:6B:46:09"), "I.0.xx", 6860, 3690, Helper::getHeight(0), tx, pl);
|
||||||
addAP(("00:04:96:6C:5E:39"), "I.0.36", 4480, 4800, Helper::getHeight(0), tx, pl); // vague!!
|
addAP(("00:04:96:6C:5E:39"), "I.0.36", 4480, 4800, Helper::getHeight(0), tx, pl); // vague!!
|
||||||
|
|
||||||
const int ibOff = +2;
|
|
||||||
const float ibPLE = 1.9;
|
|
||||||
addBeacon("78:A5:04:1F:87:64", -71+ibOff, ibPLE, 1088, 4858, Helper::getHeight(3)); // id:16
|
|
||||||
addBeacon("78:A5:04:1F:8A:59", -65+4, 2.0, 1088, 4858, Helper::getHeight(2)); // id:18
|
|
||||||
addBeacon("1C:BA:8C:21:71:70", -71+ibOff, ibPLE, 1088, 4858, Helper::getHeight(1)); // id:11
|
|
||||||
addBeacon("78:A5:04:1F:88:9F", -71+ibOff, ibPLE, 1088, 4858, Helper::getHeight(0)); // id:20
|
|
||||||
|
|
||||||
addBeacon("F9:CC:C0:A2:02:17", -77+ibOff, ibPLE, 7068, 4518, Helper::getHeight(2)); // idis switchboard
|
|
||||||
addBeacon("E5:6F:57:34:94:40", -77+ibOff, ibPLE, 7468, 5108, Helper::getHeight(2)); // idis outside
|
|
||||||
addBeacon("C6:FC:6E:25:F5:29", -77+ibOff, ibPLE, 6115, 4527, Helper::getHeight(2)); // idis toni
|
|
||||||
|
|
||||||
//addBeacon("78:A5:04:1E:B1:50", -88+ibOff-4, ibPLE, 6108, 4528, Helper::getHeight(1)); // i.1.47
|
// OLD
|
||||||
//addBeacon("78:A5:04:1F:91:41", -88+ibOff-4, ibPLE, 6508, 4038, Helper::getHeight(1)); // fachschaft
|
|
||||||
//addBeacon("78:A5:04:1F:8E:35", -88+ibOff-4, ibPLE, 6313, 4038, Helper::getHeight(1)); // neben fachschaft
|
|
||||||
|
|
||||||
// addBeacon("00:07:80:78:F7:B3", -82, ibPLE, 1038, 4018, 3);
|
// const double pl = 2.7; // 2.7
|
||||||
// addBeacon("78:A5:04:1F:93:02", -88, ibPLE, 1538, 4038, 3);
|
// const double tx = -46;
|
||||||
addBeacon("78:A5:04:1F:91:08", -88, ibPLE, 1448, 4538, 3);
|
|
||||||
addBeacon("78:A5:04:1F:93:02", -88, ibPLE, 2028, 4528, 3);
|
// addAP(("00:04:96:6b:64:99"), "i.3.20", 290, 1300, Helper::getHeight(3), tx, pl-1);
|
||||||
|
// addAP(("00:04:96:6b:70:c9"), "i.3.25", 290, 3930, Helper::getHeight(3), tx, pl);
|
||||||
|
// addAP(("00:04:96:6b:82:79"), "i.3.16", 1860, 3400, Helper::getHeight(3), tx, pl-1);
|
||||||
|
// addAP(("00:04:96:77:ed:f9"), "i.3.39", 4700, 4850, Helper::getHeight(3), tx, pl);
|
||||||
|
// addAP(("00:04:96:77:ed:69"), "i.3.3", 6460, 3400, Helper::getHeight(3), tx, pl);
|
||||||
|
|
||||||
|
// // 2nd floor (vague AP position)
|
||||||
|
// addAP(("00:04:96:6c:3a:a9"), "I.2.1", 6750, 3350, Helper::getHeight(2), tx, pl);
|
||||||
|
// addAP(("00:04:96:6b:bf:f9"), "I.2.9", 3000, 3350, Helper::getHeight(2), tx, pl);
|
||||||
|
// addAP(("00:04:96:77:ec:a9"), "I.2.15", 290, 750, Helper::getHeight(2), tx, pl);
|
||||||
|
// addAP(("00:04:96:6b:0c:c9"), "I.2.19", 300, 4000, Helper::getHeight(2), tx, pl);
|
||||||
|
// addAP(("00:04:96:6b:db:69"), "I.2.34", 4320, 4780, Helper::getHeight(2), tx, pl);
|
||||||
|
|
||||||
|
// // 1st floor (vague AP position)
|
||||||
|
// addAP(("00:04:96:6c:cf:19"), "I.1.2", 6150, 3420, Helper::getHeight(1), tx, pl);
|
||||||
|
// addAP(("00:04:96:7d:07:79"), "I.1.9", 1800, 3300, Helper::getHeight(1), tx, pl);
|
||||||
|
// addAP(("00:04:96:69:48:c9"), "I.1.17", 1500, 300, Helper::getHeight(1), tx, pl);
|
||||||
|
// addAP(("00:04:96:77:eb:99"), "I.1.21", 500, 1700, Helper::getHeight(1), tx, pl);
|
||||||
|
// addAP(("00:04:96:6b:45:59"), "I.1.30", 800, 4800, Helper::getHeight(1), tx, pl);
|
||||||
|
// addAP(("00:04:96:77:ed:89"), "I.1.43", 4600, 4800, Helper::getHeight(1), tx, pl);
|
||||||
|
|
||||||
|
// // 0th floor (exact AP position)
|
||||||
|
// addAP(("00:04:96:6C:6E:F9"), "I.0.27", 530, 4970, Helper::getHeight(0), tx, pl);
|
||||||
|
// addAP(("00:04:96:6C:A5:39"), "I.0.17", 1030, 270, Helper::getHeight(0), tx, pl);
|
||||||
|
// addAP(("00:04:96:6C:A4:A9"), "I.0.9", 1660, 2780, Helper::getHeight(0), tx, pl);
|
||||||
|
// addAP(("00:04:96:77:EE:69"), "I.0.7", 3560, 3380, Helper::getHeight(0), tx, pl);
|
||||||
|
// addAP(("00:04:96:6B:46:09"), "I.0.xx", 6860, 3690, Helper::getHeight(0), tx, pl);
|
||||||
|
// addAP(("00:04:96:6C:5E:39"), "I.0.36", 4480, 4800, Helper::getHeight(0), tx, pl); // vague!!
|
||||||
|
|
||||||
|
|
||||||
|
// const int ibOff = +2;
|
||||||
|
// const float ibPLE = 1.9;
|
||||||
|
// addBeacon("78:A5:04:1F:87:64", -71+ibOff, ibPLE, 1088, 4858, Helper::getHeight(3)); // id:16
|
||||||
|
// addBeacon("78:A5:04:1F:8A:59", -65+4, 2.0, 1088, 4858, Helper::getHeight(2)); // id:18
|
||||||
|
// addBeacon("1C:BA:8C:21:71:70", -71+ibOff, ibPLE, 1088, 4858, Helper::getHeight(1)); // id:11
|
||||||
|
// addBeacon("78:A5:04:1F:88:9F", -71+ibOff, ibPLE, 1088, 4858, Helper::getHeight(0)); // id:20
|
||||||
|
|
||||||
|
// addBeacon("F9:CC:C0:A2:02:17", -77+ibOff, ibPLE, 7068, 4518, Helper::getHeight(2)); // idis switchboard
|
||||||
|
// addBeacon("E5:6F:57:34:94:40", -77+ibOff, ibPLE, 7468, 5108, Helper::getHeight(2)); // idis outside
|
||||||
|
// addBeacon("C6:FC:6E:25:F5:29", -77+ibOff, ibPLE, 6115, 4527, Helper::getHeight(2)); // idis toni
|
||||||
|
|
||||||
|
// addBeacon("78:A5:04:1E:B1:50", -88+ibOff-4, ibPLE, 6108, 4528, Helper::getHeight(1)); // i.1.47
|
||||||
|
// addBeacon("78:A5:04:1F:91:41", -88+ibOff-4, ibPLE, 6508, 4038, Helper::getHeight(1)); // fachschaft
|
||||||
|
// addBeacon("78:A5:04:1F:8E:35", -88+ibOff-4, ibPLE, 6313, 4038, Helper::getHeight(1)); // neben fachschaft
|
||||||
|
|
||||||
|
//// addBeacon("00:07:80:78:F7:B3", -82, ibPLE, 1038, 4018, 3);
|
||||||
|
//// addBeacon("78:A5:04:1F:93:02", -88, ibPLE, 1538, 4038, 3);
|
||||||
|
// addBeacon("78:A5:04:1F:91:08", -88, ibPLE, 1448, 4538, 3);
|
||||||
|
// addBeacon("78:A5:04:1F:93:02", -88, ibPLE, 2028, 4528, 3);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -37,7 +37,7 @@ public:
|
|||||||
|
|
||||||
//const double tx = -48; // tablet
|
//const double tx = -48; // tablet
|
||||||
//const double pl = 3.15;
|
//const double pl = 3.15;
|
||||||
const float waf = 7;//10.0; // was 7 before?! has something todo with the floor heights / levels
|
const float waf = 8;//10.0; // was 7 before?! has something todo with the floor heights / levels
|
||||||
|
|
||||||
// get the ap the client had the strongest measurement for
|
// get the ap the client had the strongest measurement for
|
||||||
//const PositionedWifiAP* relAP = settings.getAP(strongest.mac); assert(relAP);
|
//const PositionedWifiAP* relAP = settings.getAP(strongest.mac); assert(relAP);
|
||||||
@@ -55,9 +55,9 @@ public:
|
|||||||
const float distToAP_m = state.pCur.getDistance(*ap) / 100.0;
|
const float distToAP_m = state.pCur.getDistance(*ap) / 100.0;
|
||||||
|
|
||||||
// floor difference?
|
// floor difference?
|
||||||
const float floorDiff = //std::ceil(
|
const float floorDiff = std::abs(Helper::getFloorNrFloat(ap->z) - Helper::getFloorNrFloat(state.pCur.z));
|
||||||
std::abs(Helper::getFloorNrFloat(ap->z) - Helper::getFloorNrFloat(state.pCur.z));
|
//const float floorDiff = std::round(std::abs(Helper::getFloorNr(ap->z) - Helper::getFloorNr(state.pCur.z)));
|
||||||
//);
|
|
||||||
//const float floorDiff = std::abs(ap->z - state.pCur.z) / 340;
|
//const float floorDiff = std::abs(ap->z - state.pCur.z) / 340;
|
||||||
|
|
||||||
// estimate the rssi depending on above distance
|
// estimate the rssi depending on above distance
|
||||||
@@ -71,7 +71,7 @@ public:
|
|||||||
//const double mdlRelRSSI = mdlStrongestRSSI - mdlRSSI;
|
//const double mdlRelRSSI = mdlStrongestRSSI - mdlRSSI;
|
||||||
|
|
||||||
// probability? (sigma grows with measurement's age)
|
// probability? (sigma grows with measurement's age)
|
||||||
const double sigma = 8 + ((observation.latestSensorDataTS - entry.ts) / 1000.0) * 3.0;
|
const double sigma = (8) + ((observation.latestSensorDataTS - entry.ts) / 1000.0) * 3.5;
|
||||||
const double p = K::NormalDistribution::getProbability(mdlRSSI, sigma, realRSSI); // absolute
|
const double p = K::NormalDistribution::getProbability(mdlRSSI, sigma, realRSSI); // absolute
|
||||||
//const double p = K::NormalDistribution::getProbability(mdlRelRSSI, sigma, realRelRSSI); // relative
|
//const double p = K::NormalDistribution::getProbability(mdlRelRSSI, sigma, realRelRSSI); // relative
|
||||||
|
|
||||||
@@ -80,8 +80,14 @@ public:
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
const double lambda = 0.25; //0.12;
|
//const double lambda = 0.05;//0.15; //0.12;
|
||||||
return lambda * exp(- lambda * (-prob));
|
//return lambda * exp(- lambda * (-prob));
|
||||||
|
return std::pow(std::exp(prob), 0.1);
|
||||||
|
// if (prob < -30) {return 0.01;}
|
||||||
|
// if (prob < -15) {return 0.50;}
|
||||||
|
// else {return 1.00;}
|
||||||
|
|
||||||
|
|
||||||
//return prob;
|
//return prob;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -8,8 +8,8 @@
|
|||||||
#include "StepObservation.h"
|
#include "StepObservation.h"
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
static constexpr double mu_walk = 40;
|
static constexpr double mu_walk = 90;
|
||||||
static constexpr double sigma_walk = 15;
|
static constexpr double sigma_walk = 30;
|
||||||
static constexpr double mu_stop = 0;
|
static constexpr double mu_stop = 0;
|
||||||
static constexpr double sigma_stop = 5;
|
static constexpr double sigma_stop = 5;
|
||||||
|
|
||||||
@@ -21,29 +21,49 @@ public:
|
|||||||
|
|
||||||
return 1;
|
return 1;
|
||||||
|
|
||||||
// double distance = state.distanceWalkedCM;
|
const float mdlWalked_m = state.walkState.distanceWalked_m;
|
||||||
|
|
||||||
// double a = 1.0;
|
((MyState&)state).walkState.distanceWalked_m = 0;
|
||||||
// double mu_distance = 0; //cm
|
|
||||||
// double sigma_distance = 10.0; //cm
|
|
||||||
|
|
||||||
// if(obs->step) {
|
const float stepSize_m = 0.71;
|
||||||
// a = 1.0;
|
const float sensSigma_m = 0.05 + (0.05 * obs->steps);
|
||||||
// mu_distance = mu_walk;//80.0; //cm
|
const float sensWalked_m = obs->steps * stepSize_m;
|
||||||
// sigma_distance = sigma_walk;//40.0; //cm
|
|
||||||
// }
|
|
||||||
|
|
||||||
// else {
|
if (obs->steps > 1) {
|
||||||
// a = 0.0;
|
int i = 0;
|
||||||
// mu_distance = mu_stop; //cm
|
int j = i+1; ++j;
|
||||||
// sigma_distance = sigma_stop; //cm
|
}
|
||||||
// }
|
|
||||||
|
|
||||||
// //Mixed Gaussian model: 1st Gaussian = step, 2nd Gaussian = no step
|
const double prob = K::NormalDistribution::getProbability(sensWalked_m, sensSigma_m, mdlWalked_m);
|
||||||
// const double p = a * K::NormalDistribution::getProbability(mu_distance, sigma_distance, distance) +
|
|
||||||
// (1.0-a) * K::NormalDistribution::getProbability(mu_distance, sigma_distance, distance);
|
if (prob != prob) {
|
||||||
|
throw 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
return prob;
|
||||||
|
|
||||||
|
// float a = 1.0;
|
||||||
|
// float mu_distance = 0;
|
||||||
|
// float sigma_distance = 0;
|
||||||
|
|
||||||
|
// if(obs->step) {
|
||||||
|
// a = 1.0;
|
||||||
|
// mu_distance = mu_walk;
|
||||||
|
// sigma_distance = sigma_walk;
|
||||||
|
// }
|
||||||
|
|
||||||
|
// else {
|
||||||
|
// a = 0.0;
|
||||||
|
// mu_distance = mu_stop;
|
||||||
|
// sigma_distance = sigma_stop;
|
||||||
|
// }
|
||||||
|
|
||||||
|
// //Mixed Gaussian model: 1st Gaussian = step, 2nd Gaussian = no step
|
||||||
|
// const double p = a * K::NormalDistribution::getProbability(mu_distance, sigma_distance, distance) +
|
||||||
|
// (1.0-a) * K::NormalDistribution::getProbability(mu_distance, sigma_distance, distance);
|
||||||
|
|
||||||
|
// return p;
|
||||||
|
|
||||||
// return p;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -2,11 +2,14 @@
|
|||||||
#define STEPOBSERVATION_H
|
#define STEPOBSERVATION_H
|
||||||
|
|
||||||
struct StepObservation {
|
struct StepObservation {
|
||||||
float ts;
|
|
||||||
bool step;
|
float ts;
|
||||||
|
|
||||||
|
int steps = 0;
|
||||||
|
|
||||||
StepObservation() {;}
|
StepObservation() {;}
|
||||||
StepObservation(const float ts) : ts(ts), step(false){;}
|
|
||||||
|
StepObservation(const float ts) : ts(ts), steps(0) {;}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -7,7 +7,7 @@
|
|||||||
//#include <boost/math/special_functions/bessel.hpp>
|
//#include <boost/math/special_functions/bessel.hpp>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
static constexpr double sigma_heading = 35;
|
//static constexpr double sigma_heading = 5;
|
||||||
|
|
||||||
class TurnEvaluation {
|
class TurnEvaluation {
|
||||||
|
|
||||||
@@ -19,6 +19,24 @@ public:
|
|||||||
|
|
||||||
return 1;
|
return 1;
|
||||||
|
|
||||||
|
// get the current heading-change
|
||||||
|
const float delta = Angle::radToDeg(state.walkState.headingChange_rad);
|
||||||
|
|
||||||
|
// and reset it as it was evaluated
|
||||||
|
((MyState&) state).walkState.headingChange_rad = 0;
|
||||||
|
|
||||||
|
// proability?
|
||||||
|
const float sigma = 15.0;
|
||||||
|
const double prob = K::NormalDistribution::getProbability(obs->delta_heading, sigma, delta);
|
||||||
|
|
||||||
|
if (prob != prob) {
|
||||||
|
throw 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
return prob;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// //Particle's heading change
|
// //Particle's heading change
|
||||||
// double delta_heading_particle = state.heading - state.heading_old;
|
// double delta_heading_particle = state.heading - state.heading_old;
|
||||||
|
|
||||||
|
|||||||
@@ -11,7 +11,7 @@ struct TurnObservation {
|
|||||||
float delta_motion; //measured change of motion direction (given by PCA)
|
float delta_motion; //measured change of motion direction (given by PCA)
|
||||||
|
|
||||||
TurnObservation() {;}
|
TurnObservation() {;}
|
||||||
TurnObservation(const float delta_heading, const float motion_angle) : delta_heading(delta_heading), delta_motion(delta_motion) {;}
|
TurnObservation(const float delta_heading, const float motion_angle) : delta_heading(delta_heading), delta_motion(motion_angle) {;}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -11,8 +11,12 @@
|
|||||||
#include "DijkstraMapper.h"
|
#include "DijkstraMapper.h"
|
||||||
|
|
||||||
#include "eval/Eval.h"
|
#include "eval/Eval.h"
|
||||||
|
#include "eval/Eval1.h"
|
||||||
#include "eval/EvalBase.h"
|
#include "eval/EvalBase.h"
|
||||||
|
|
||||||
|
#include "eval/PaperVisImportance.h"
|
||||||
|
#include "eval/PaperVisDijkstra.h"
|
||||||
|
|
||||||
Settings settings;
|
Settings settings;
|
||||||
|
|
||||||
void testModelWalk() {
|
void testModelWalk() {
|
||||||
@@ -31,6 +35,10 @@ void testModelWalk() {
|
|||||||
vis.addFloor(floors.f2, floors.h2);
|
vis.addFloor(floors.f2, floors.h2);
|
||||||
vis.addFloor(floors.f3, floors.h3);
|
vis.addFloor(floors.f3, floors.h3);
|
||||||
|
|
||||||
|
|
||||||
|
vis.gp << "set xrange [1100:1800]\n";
|
||||||
|
vis.gp << "set yrange [4500:5200]\n";
|
||||||
|
|
||||||
// vis.gp << "set xrange [1000:4000]\n";
|
// vis.gp << "set xrange [1000:4000]\n";
|
||||||
// vis.gp << "set yrange [1000:4000]\n";
|
// vis.gp << "set yrange [1000:4000]\n";
|
||||||
// vis.gp << "set zrange [0:600]\n";
|
// vis.gp << "set zrange [0:600]\n";
|
||||||
@@ -48,16 +56,17 @@ void testModelWalk() {
|
|||||||
// track the number-of-visits for each node to draw something like a particle-heat-map?
|
// track the number-of-visits for each node to draw something like a particle-heat-map?
|
||||||
|
|
||||||
// show the importance factors
|
// show the importance factors
|
||||||
// vis.addGrid(grid);
|
vis.addGrid(grid);
|
||||||
// vis.show();
|
vis.show();
|
||||||
// sleep(100);
|
sleep(100);
|
||||||
// vis.removeGrid();
|
vis.removeGrid();
|
||||||
|
|
||||||
Distribution::Normal<float> wDist(0.3, 0.3);
|
Distribution::Normal<float> wDist(0.3, 0.3);
|
||||||
|
Distribution::Normal<float> wHead(0.3, 0.3);
|
||||||
|
|
||||||
while(true) {
|
while(true) {
|
||||||
for (GridWalkState<MyGridNode>& state : states) {
|
for (GridWalkState<MyGridNode>& state : states) {
|
||||||
state = walk.getDestination(grid, state, std::abs(wDist.draw()) );
|
state = walk.getDestination(grid, state, std::abs(wDist.draw()), wHead.draw());
|
||||||
}
|
}
|
||||||
usleep(1000*80);
|
usleep(1000*80);
|
||||||
vis.showStates(states);
|
vis.showStates(states);
|
||||||
@@ -74,11 +83,14 @@ void testModelWalk() {
|
|||||||
|
|
||||||
int main(void) {
|
int main(void) {
|
||||||
|
|
||||||
//testModelWalk();
|
// testModelWalk();
|
||||||
|
|
||||||
Eval eval;
|
// Eval1 eval;
|
||||||
eval.setEval1();
|
// eval.setEval1();
|
||||||
eval.run();
|
// eval.run();
|
||||||
|
|
||||||
|
PaperVisImportance::createImportance();
|
||||||
|
PaperVisImportance::createPath();
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
|
|
||||||
|
|||||||
@@ -3,6 +3,10 @@
|
|||||||
|
|
||||||
struct MyControl {
|
struct MyControl {
|
||||||
|
|
||||||
|
float walked_m = 0;
|
||||||
|
|
||||||
|
float headingChange_rad = 0;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // MYCONTROL_H
|
#endif // MYCONTROL_H
|
||||||
|
|||||||
@@ -61,14 +61,13 @@ public:
|
|||||||
weight *= beaconEval.getProbability(p.state, observation);
|
weight *= beaconEval.getProbability(p.state, observation);
|
||||||
}
|
}
|
||||||
|
|
||||||
// if (useStep) {
|
if (useStep) {
|
||||||
// weight *= stepEval.getProbability(p.state, observation.step);
|
weight *= stepEval.getProbability(p.state, observation.step);
|
||||||
// p.state.distanceWalkedCM = 0.0;
|
}
|
||||||
// }
|
|
||||||
|
|
||||||
// if (useTurn) {
|
if (useTurn) {
|
||||||
// weight *= turnEval.getProbability(p.state, observation.turn, true);
|
weight *= turnEval.getProbability(p.state, observation.turn, true);
|
||||||
// }
|
}
|
||||||
|
|
||||||
// set and accumulate
|
// set and accumulate
|
||||||
p.weight = weight;
|
p.weight = weight;
|
||||||
@@ -76,6 +75,11 @@ public:
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// reset
|
||||||
|
observation.step->steps = 0;
|
||||||
|
observation.turn->delta_heading = 0;
|
||||||
|
observation.turn->delta_motion = 0;
|
||||||
|
|
||||||
return sum;
|
return sum;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -47,7 +47,6 @@ public:
|
|||||||
|
|
||||||
p.state.pOld = p.state.pCur;
|
p.state.pOld = p.state.pCur;
|
||||||
p.state.walkState.heading = Heading::rnd();
|
p.state.walkState.heading = Heading::rnd();
|
||||||
p.state.distanceWalkedCM = 0;
|
|
||||||
p.state.hPa = 0;
|
p.state.hPa = 0;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -23,7 +23,7 @@ struct MyState {
|
|||||||
// the grid-walk state
|
// the grid-walk state
|
||||||
GridWalkState<MyGridNode> walkState;
|
GridWalkState<MyGridNode> walkState;
|
||||||
|
|
||||||
int distanceWalkedCM;
|
//int distanceWalkedCM;
|
||||||
|
|
||||||
|
|
||||||
// double heading_old;
|
// double heading_old;
|
||||||
|
|||||||
@@ -31,7 +31,7 @@ private:
|
|||||||
|
|
||||||
/** a simple normal distribution */
|
/** a simple normal distribution */
|
||||||
K::UniformDistribution distWalkStop;
|
K::UniformDistribution distWalkStop;
|
||||||
K::NormalDistribution distWalk;
|
K::NormalDistribution distWalkPerSec;
|
||||||
K::NormalDistribution distStop;
|
K::NormalDistribution distStop;
|
||||||
|
|
||||||
|
|
||||||
@@ -48,10 +48,10 @@ public:
|
|||||||
*/
|
*/
|
||||||
MyTransition(Grid<MyGridNode>& grid, GridWalk<MyGridNode>& walker) :
|
MyTransition(Grid<MyGridNode>& grid, GridWalk<MyGridNode>& walker) :
|
||||||
grid(grid), walker(walker),
|
grid(grid), walker(walker),
|
||||||
distWalkStop(0.0, 1.0), distWalk(1.5, 0.5), distStop(0.0, 0.1), distBaro(0.3, 0.05) {
|
distWalkStop(0.0, 1.0), distWalkPerSec(1.0, 0.3), distStop(0.0, 0.1), distBaro(0.3, 0.05) {
|
||||||
|
|
||||||
distWalkStop.setSeed(1234);
|
distWalkStop.setSeed(1234);
|
||||||
distWalk.setSeed(1234);
|
distWalkPerSec.setSeed(1234);
|
||||||
distStop.setSeed(1234);
|
distStop.setSeed(1234);
|
||||||
|
|
||||||
distBaro.setSeed(5678);
|
distBaro.setSeed(5678);
|
||||||
@@ -90,20 +90,17 @@ public:
|
|||||||
p.state.pOld = p.state.pCur;
|
p.state.pOld = p.state.pCur;
|
||||||
|
|
||||||
|
|
||||||
// 10% stand still, 90% walk
|
// // 10% stand still, 90% walk
|
||||||
double dist_m;
|
// double dist_m;
|
||||||
if (distWalkStop.draw() > 0.9) {
|
// if (distWalkStop.draw() > 0.9) {
|
||||||
dist_m = std::abs(distStop.draw() * deltaMS / 1000.0);
|
// dist_m = std::abs(distStop.draw() * deltaMS / 1000.0);
|
||||||
} else {
|
// } else {
|
||||||
dist_m = std::abs(distWalk.draw() * deltaMS / 1000.0);
|
// dist_m = std::abs(distWalkPerSec.draw() * deltaMS / 1000.0);
|
||||||
}
|
// }
|
||||||
|
|
||||||
// update cumulative distance
|
|
||||||
p.state.distanceWalkedCM += std::abs(dist_m * 100.0);
|
|
||||||
|
|
||||||
// get new destination
|
// get new destination
|
||||||
//const Node3* dst = choice->getTarget(src, p.state, dist_m);
|
//const Node3* dst = choice->getTarget(src, p.state, dist_m);
|
||||||
p.state.walkState = walker.getDestination(grid, p.state.walkState, dist_m );
|
p.state.walkState = walker.getDestination(grid, p.state.walkState, control->walked_m, control->headingChange_rad );
|
||||||
|
|
||||||
// randomly move the particle within its target grid (box)
|
// randomly move the particle within its target grid (box)
|
||||||
// (z remains unchanged!)
|
// (z remains unchanged!)
|
||||||
@@ -114,56 +111,9 @@ public:
|
|||||||
p.state.pCur = (Point3) *p.state.walkState.node + noise;
|
p.state.pCur = (Point3) *p.state.walkState.node + noise;
|
||||||
|
|
||||||
|
|
||||||
// --- ATTENTION HORRIBLE CODE INCOMING. ---
|
// update the baromter
|
||||||
p.state.hPa += (p.state.pOld.z - p.state.pCur.z) / 100.0f * 0.105f;
|
p.state.hPa += (p.state.pOld.z - p.state.pCur.z) / 100.0f * 0.105f;
|
||||||
// //how many floors are changed? and in what direction (given by the sign)
|
|
||||||
// double numFloorChanged = p.state.z_nr_old - p.state.z_nr;
|
|
||||||
|
|
||||||
// //The height of the single floor levels.
|
|
||||||
// const static double floor_height[3] = {4.1, 3.4, 3.4};
|
|
||||||
|
|
||||||
// //update barometer
|
|
||||||
// if(USE_BAROMETRIC_FORMULAR){
|
|
||||||
// //height the particle has climbed.
|
|
||||||
// double h_1 = 0.0;
|
|
||||||
// double mu = 0.0;
|
|
||||||
|
|
||||||
// //we need only the sign of the floors changed, since the pressure change between the floors
|
|
||||||
// //is calculated within s_getAtmosphericPressure
|
|
||||||
// numFloorChanged = sgn(numFloorChanged);
|
|
||||||
|
|
||||||
// for(int i = std::min(p.state.z_nr_old, p.state.z_nr); i < std::max(p.state.z_nr_old, p.state.z_nr); i++){
|
|
||||||
// h_1 += floor_height[i];
|
|
||||||
// }
|
|
||||||
|
|
||||||
// {
|
|
||||||
// // use the barometric formular to calculate the relative pressure
|
|
||||||
// // the calculation is done assuming sea level height at every floor.
|
|
||||||
// double mslp = BarometricFormular::s_getSeaLevelPressure();
|
|
||||||
// double pressure = BarometricFormular::s_getAtmosphericPressure(h_1, 297.0);
|
|
||||||
// mu = std::abs(mslp - pressure);
|
|
||||||
// }
|
|
||||||
|
|
||||||
// if (!USE_STATIC_CIRCULAR_BUFFERING && !USE_DYNAMIC_CIRCULAR_BUFFERING)
|
|
||||||
// p.state.hPa += numFloorChanged * K::NormalDistribution::draw(mu, 0.005);
|
|
||||||
// else
|
|
||||||
// p.state.hPa = numFloorChanged * K::NormalDistribution::draw(mu, 0.15);
|
|
||||||
// }
|
|
||||||
// else{
|
|
||||||
// if (!USE_STATIC_CIRCULAR_BUFFERING && !USE_DYNAMIC_CIRCULAR_BUFFERING)
|
|
||||||
// p.state.hPa += numFloorChanged * distBaro.draw();
|
|
||||||
// else
|
|
||||||
// p.state.hPa = numFloorChanged * distBaro.draw();
|
|
||||||
// }
|
|
||||||
|
|
||||||
// // sanity check
|
|
||||||
// if (p.state.heading != p.state.heading) {throw "detected NaN";}
|
|
||||||
// if (p.state.z_nr != p.state.z_nr) {throw "detected NaN";}
|
|
||||||
// if (p.state.x_cm != p.state.x_cm) {throw "detected NaN";}
|
|
||||||
// if (p.state.y_cm != p.state.y_cm) {throw "detected NaN";}
|
|
||||||
|
|
||||||
// // ensure p.state.z_nr IS discreet
|
|
||||||
// if ( std::abs(p.state.z_nr - std::round(p.state.z_nr)) > 0.01) {throw "detected continuous z_nr!";}
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -46,13 +46,13 @@
|
|||||||
inkscape:window-height="845"
|
inkscape:window-height="845"
|
||||||
id="namedview3234"
|
id="namedview3234"
|
||||||
showgrid="true"
|
showgrid="true"
|
||||||
inkscape:zoom="0.84948895"
|
inkscape:zoom="3.3979558"
|
||||||
inkscape:cx="272.89941"
|
inkscape:cx="1962.4967"
|
||||||
inkscape:cy="1411.2257"
|
inkscape:cy="1511.039"
|
||||||
inkscape:window-x="0"
|
inkscape:window-x="0"
|
||||||
inkscape:window-y="0"
|
inkscape:window-y="0"
|
||||||
inkscape:window-maximized="1"
|
inkscape:window-maximized="1"
|
||||||
inkscape:current-layer="layer8"
|
inkscape:current-layer="layer9"
|
||||||
inkscape:object-nodes="true"
|
inkscape:object-nodes="true"
|
||||||
units="px"
|
units="px"
|
||||||
showborder="true"
|
showborder="true"
|
||||||
@@ -1464,7 +1464,7 @@
|
|||||||
inkscape:groupmode="layer"
|
inkscape:groupmode="layer"
|
||||||
id="layer18"
|
id="layer18"
|
||||||
inkscape:label="ground_truth_2"
|
inkscape:label="ground_truth_2"
|
||||||
style="display:none">
|
style="display:inline">
|
||||||
<text
|
<text
|
||||||
xml:space="preserve"
|
xml:space="preserve"
|
||||||
style="font-style:normal;font-weight:normal;font-size:16px;line-height:125%;font-family:Times;-inkscape-font-specification:Times;text-align:center;letter-spacing:0px;word-spacing:0px;text-anchor:middle;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
style="font-style:normal;font-weight:normal;font-size:16px;line-height:125%;font-family:Times;-inkscape-font-specification:Times;text-align:center;letter-spacing:0px;word-spacing:0px;text-anchor:middle;fill:#000000;fill-opacity:1;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
@@ -2022,7 +2022,7 @@
|
|||||||
sodipodi:nodetypes="cc" />
|
sodipodi:nodetypes="cc" />
|
||||||
<path
|
<path
|
||||||
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
d="m 453.54331,485.43304 0,251.5748"
|
d="m 453.54331,460.62989 0,276.37795"
|
||||||
id="path4616"
|
id="path4616"
|
||||||
inkscape:connector-curvature="0"
|
inkscape:connector-curvature="0"
|
||||||
sodipodi:nodetypes="cc" />
|
sodipodi:nodetypes="cc" />
|
||||||
@@ -2283,6 +2283,12 @@
|
|||||||
d="m 595.27559,1491.7322 60.23622,0"
|
d="m 595.27559,1491.7322 60.23622,0"
|
||||||
id="path5901"
|
id="path5901"
|
||||||
inkscape:connector-curvature="0" />
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 453.54331,485.43304 53.1496,0"
|
||||||
|
id="path4954"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
</g>
|
</g>
|
||||||
<g
|
<g
|
||||||
inkscape:groupmode="layer"
|
inkscape:groupmode="layer"
|
||||||
@@ -2950,12 +2956,28 @@
|
|||||||
d="m 595.27559,1491.7322 60.23622,0"
|
d="m 595.27559,1491.7322 60.23622,0"
|
||||||
id="path5905"
|
id="path5905"
|
||||||
inkscape:connector-curvature="0" />
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 442.91339,485.43304 63.77952,0"
|
||||||
|
id="path4952"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 442.91339,712.20469 63.77952,0"
|
||||||
|
id="path4958"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 2097.6378,340.15744 0,60.23623"
|
||||||
|
id="path4968"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
</g>
|
</g>
|
||||||
<g
|
<g
|
||||||
inkscape:groupmode="layer"
|
inkscape:groupmode="layer"
|
||||||
id="layer9"
|
id="layer9"
|
||||||
inkscape:label="floor_2"
|
inkscape:label="floor_2"
|
||||||
style="display:none"
|
style="display:inline"
|
||||||
transform="translate(0,4.2364502e-5)">
|
transform="translate(0,4.2364502e-5)">
|
||||||
<path
|
<path
|
||||||
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
@@ -3167,7 +3189,7 @@
|
|||||||
sodipodi:nodetypes="cc" />
|
sodipodi:nodetypes="cc" />
|
||||||
<path
|
<path
|
||||||
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
d="m 1984.252,340.1574 155.9055,4e-5 0,60.23623 -155.9055,-5e-5"
|
d="m 1927.5591,340.1574 212.5984,4e-5 0,60.23623 -212.5984,-5e-5"
|
||||||
id="path11661"
|
id="path11661"
|
||||||
inkscape:connector-curvature="0"
|
inkscape:connector-curvature="0"
|
||||||
sodipodi:nodetypes="cccc" />
|
sodipodi:nodetypes="cccc" />
|
||||||
@@ -3628,14 +3650,14 @@
|
|||||||
<text
|
<text
|
||||||
xml:space="preserve"
|
xml:space="preserve"
|
||||||
style="font-style:normal;font-weight:normal;font-size:16px;line-height:125%;font-family:Times;-inkscape-font-specification:Times;text-align:center;letter-spacing:0px;word-spacing:0px;text-anchor:middle;fill:#000000;fill-opacity:1;stroke:none"
|
style="font-style:normal;font-weight:normal;font-size:16px;line-height:125%;font-family:Times;-inkscape-font-specification:Times;text-align:center;letter-spacing:0px;word-spacing:0px;text-anchor:middle;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
x="1980.7086"
|
x="2055.1182"
|
||||||
y="368.50385"
|
y="357.87393"
|
||||||
id="text3478"
|
id="text3478"
|
||||||
sodipodi:linespacing="125%"><tspan
|
sodipodi:linespacing="125%"><tspan
|
||||||
sodipodi:role="line"
|
sodipodi:role="line"
|
||||||
id="tspan3480"
|
id="tspan3480"
|
||||||
x="1980.7086"
|
x="2055.1182"
|
||||||
y="368.50385">a little shorter.. is a hack</tspan></text>
|
y="357.87393">a little shorter.. is a hack</tspan></text>
|
||||||
<path
|
<path
|
||||||
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
d="m 2207.4803,279.92122 17.7166,0"
|
d="m 2207.4803,279.92122 17.7166,0"
|
||||||
@@ -3678,12 +3700,33 @@
|
|||||||
d="m 595.27559,1491.7322 60.23622,0"
|
d="m 595.27559,1491.7322 60.23622,0"
|
||||||
id="path5909"
|
id="path5909"
|
||||||
inkscape:connector-curvature="0" />
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 442.91339,712.20465 63.77952,0"
|
||||||
|
id="path4948"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 442.91339,485.433 63.77952,0"
|
||||||
|
id="path4950"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 1700.7874,336.6141 0,67.32283"
|
||||||
|
id="path4962"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 1927.5591,340.1574 0,60.23622"
|
||||||
|
id="path4966"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
</g>
|
</g>
|
||||||
<g
|
<g
|
||||||
inkscape:groupmode="layer"
|
inkscape:groupmode="layer"
|
||||||
id="layer8"
|
id="layer8"
|
||||||
inkscape:label="floor_3"
|
inkscape:label="floor_3"
|
||||||
style="display:inline"
|
style="display:none"
|
||||||
transform="translate(0,4.2364502e-5)">
|
transform="translate(0,4.2364502e-5)">
|
||||||
<path
|
<path
|
||||||
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
@@ -4458,6 +4501,17 @@
|
|||||||
d="m 595.27559,1491.7322 60.23622,0"
|
d="m 595.27559,1491.7322 60.23622,0"
|
||||||
id="path5913"
|
id="path5913"
|
||||||
inkscape:connector-curvature="0" />
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 446.45669,712.20465 60.23622,0"
|
||||||
|
id="path4956"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 1573.2283,336.6141 0,67.32283"
|
||||||
|
id="path4964"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
</g>
|
</g>
|
||||||
<g
|
<g
|
||||||
inkscape:groupmode="layer"
|
inkscape:groupmode="layer"
|
||||||
@@ -4481,10 +4535,10 @@
|
|||||||
inkscape:groupmode="layer"
|
inkscape:groupmode="layer"
|
||||||
id="layer11"
|
id="layer11"
|
||||||
inkscape:label="staircase_1_2"
|
inkscape:label="staircase_1_2"
|
||||||
style="display:none">
|
style="display:inline">
|
||||||
<path
|
<path
|
||||||
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
d="m 2125.9843,343.70075 0,53.14961 -226.7717,0"
|
d="m 2125.9843,343.70075 0,53.14961 -212.5985,0"
|
||||||
id="path4998"
|
id="path4998"
|
||||||
inkscape:connector-curvature="0"
|
inkscape:connector-curvature="0"
|
||||||
sodipodi:nodetypes="ccc" />
|
sodipodi:nodetypes="ccc" />
|
||||||
|
|||||||
|
Before Width: | Height: | Size: 224 KiB After Width: | Height: | Size: 226 KiB |
@@ -27,7 +27,7 @@
|
|||||||
<dc:format>image/svg+xml</dc:format>
|
<dc:format>image/svg+xml</dc:format>
|
||||||
<dc:type
|
<dc:type
|
||||||
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
<dc:title></dc:title>
|
<dc:title />
|
||||||
</cc:Work>
|
</cc:Work>
|
||||||
</rdf:RDF>
|
</rdf:RDF>
|
||||||
</metadata>
|
</metadata>
|
||||||
@@ -42,17 +42,17 @@
|
|||||||
guidetolerance="10"
|
guidetolerance="10"
|
||||||
inkscape:pageopacity="0"
|
inkscape:pageopacity="0"
|
||||||
inkscape:pageshadow="2"
|
inkscape:pageshadow="2"
|
||||||
inkscape:window-width="3200"
|
inkscape:window-width="1600"
|
||||||
inkscape:window-height="1671"
|
inkscape:window-height="845"
|
||||||
id="namedview3234"
|
id="namedview3234"
|
||||||
showgrid="true"
|
showgrid="true"
|
||||||
inkscape:zoom="0.6006794"
|
inkscape:zoom="3.3979558"
|
||||||
inkscape:cx="1327.5074"
|
inkscape:cx="1802.381"
|
||||||
inkscape:cy="994.75114"
|
inkscape:cy="1512.0287"
|
||||||
inkscape:window-x="0"
|
inkscape:window-x="0"
|
||||||
inkscape:window-y="55"
|
inkscape:window-y="0"
|
||||||
inkscape:window-maximized="1"
|
inkscape:window-maximized="1"
|
||||||
inkscape:current-layer="layer8"
|
inkscape:current-layer="layer9"
|
||||||
inkscape:object-nodes="true"
|
inkscape:object-nodes="true"
|
||||||
units="px"
|
units="px"
|
||||||
showborder="true"
|
showborder="true"
|
||||||
@@ -2081,7 +2081,7 @@
|
|||||||
sodipodi:nodetypes="cc" />
|
sodipodi:nodetypes="cc" />
|
||||||
<path
|
<path
|
||||||
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
d="m 453.54331,485.43304 0,251.5748"
|
d="m 453.54331,460.62989 0,276.37795"
|
||||||
id="path4616"
|
id="path4616"
|
||||||
inkscape:connector-curvature="0"
|
inkscape:connector-curvature="0"
|
||||||
sodipodi:nodetypes="cc" />
|
sodipodi:nodetypes="cc" />
|
||||||
@@ -2342,6 +2342,16 @@
|
|||||||
d="m 595.27559,1491.7322 60.23622,0"
|
d="m 595.27559,1491.7322 60.23622,0"
|
||||||
id="path5901"
|
id="path5901"
|
||||||
inkscape:connector-curvature="0" />
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 2657.4803,627.16532 116.9291,0"
|
||||||
|
id="path5824"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 453.54331,485.43304 53.1496,0"
|
||||||
|
id="path5826"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
</g>
|
</g>
|
||||||
<g
|
<g
|
||||||
inkscape:groupmode="layer"
|
inkscape:groupmode="layer"
|
||||||
@@ -3009,12 +3019,27 @@
|
|||||||
d="m 595.27559,1491.7322 60.23622,0"
|
d="m 595.27559,1491.7322 60.23622,0"
|
||||||
id="path5905"
|
id="path5905"
|
||||||
inkscape:connector-curvature="0" />
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 2097.6378,400.39367 0,-60.23623"
|
||||||
|
id="path5822"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 442.91339,485.43304 63.77952,0"
|
||||||
|
id="path5828"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 442.91339,712.20469 63.77952,0"
|
||||||
|
id="path5836"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
</g>
|
</g>
|
||||||
<g
|
<g
|
||||||
inkscape:groupmode="layer"
|
inkscape:groupmode="layer"
|
||||||
id="layer9"
|
id="layer9"
|
||||||
inkscape:label="floor_2"
|
inkscape:label="floor_2"
|
||||||
style="display:none"
|
style="display:inline"
|
||||||
transform="translate(0,4.2364502e-5)">
|
transform="translate(0,4.2364502e-5)">
|
||||||
<path
|
<path
|
||||||
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
@@ -3226,7 +3251,7 @@
|
|||||||
sodipodi:nodetypes="cc" />
|
sodipodi:nodetypes="cc" />
|
||||||
<path
|
<path
|
||||||
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
style="fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
d="m 1984.252,340.1574 155.9055,4e-5 0,60.23623 -155.9055,-5e-5"
|
d="m 1927.5591,340.1574 212.5984,4e-5 0,60.23623 -212.5984,-5e-5"
|
||||||
id="path11661"
|
id="path11661"
|
||||||
inkscape:connector-curvature="0"
|
inkscape:connector-curvature="0"
|
||||||
sodipodi:nodetypes="cccc" />
|
sodipodi:nodetypes="cccc" />
|
||||||
@@ -3726,12 +3751,34 @@
|
|||||||
d="m 595.27559,1491.7322 60.23622,0"
|
d="m 595.27559,1491.7322 60.23622,0"
|
||||||
id="path5909"
|
id="path5909"
|
||||||
inkscape:connector-curvature="0" />
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 1700.7874,407.48024 0,-74.40945"
|
||||||
|
id="path5818"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 1955.9055,403.93693 0,-67.32283"
|
||||||
|
id="path5820"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 442.91339,485.433 63.77952,0"
|
||||||
|
id="path5830"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 442.91339,712.20465 63.77952,0"
|
||||||
|
id="path5834"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
</g>
|
</g>
|
||||||
<g
|
<g
|
||||||
inkscape:groupmode="layer"
|
inkscape:groupmode="layer"
|
||||||
id="layer8"
|
id="layer8"
|
||||||
inkscape:label="floor_3"
|
inkscape:label="floor_3"
|
||||||
style="display:inline"
|
style="display:none"
|
||||||
transform="translate(0,4.2364502e-5)">
|
transform="translate(0,4.2364502e-5)">
|
||||||
<path
|
<path
|
||||||
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
@@ -4506,6 +4553,16 @@
|
|||||||
d="m 595.27559,1491.7322 60.23622,0"
|
d="m 595.27559,1491.7322 60.23622,0"
|
||||||
id="path5913"
|
id="path5913"
|
||||||
inkscape:connector-curvature="0" />
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 1559.0551,403.93693 0,-67.32283"
|
||||||
|
id="path5816"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 446.45669,712.20465 60.23622,0"
|
||||||
|
id="path5832"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
</g>
|
</g>
|
||||||
<g
|
<g
|
||||||
inkscape:groupmode="layer"
|
inkscape:groupmode="layer"
|
||||||
@@ -4532,7 +4589,7 @@
|
|||||||
style="display:none">
|
style="display:none">
|
||||||
<path
|
<path
|
||||||
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
d="m 2125.9843,343.70075 0,53.14961 -226.7717,0"
|
d="m 2125.9843,343.70075 0,53.14961 -212.5985,0"
|
||||||
id="path4998"
|
id="path4998"
|
||||||
inkscape:connector-curvature="0"
|
inkscape:connector-curvature="0"
|
||||||
sodipodi:nodetypes="ccc" />
|
sodipodi:nodetypes="ccc" />
|
||||||
|
|||||||
|
Before Width: | Height: | Size: 226 KiB After Width: | Height: | Size: 229 KiB |
355
code/plan_plots.svg
Normal file
355
code/plan_plots.svg
Normal file
@@ -0,0 +1,355 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||||
|
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
width="724"
|
||||||
|
height="1800"
|
||||||
|
viewBox="0 0 724.00001 1800"
|
||||||
|
id="svg5100"
|
||||||
|
version="1.1"
|
||||||
|
inkscape:version="0.91 r13725"
|
||||||
|
sodipodi:docname="plan_plots.svg">
|
||||||
|
<defs
|
||||||
|
id="defs5102" />
|
||||||
|
<sodipodi:namedview
|
||||||
|
id="base"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
bordercolor="#666666"
|
||||||
|
borderopacity="1.0"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:zoom="0.98994949"
|
||||||
|
inkscape:cx="451.23575"
|
||||||
|
inkscape:cy="136.10259"
|
||||||
|
inkscape:document-units="px"
|
||||||
|
inkscape:current-layer="layer1"
|
||||||
|
showgrid="true"
|
||||||
|
fit-margin-top="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
inkscape:object-nodes="true"
|
||||||
|
inkscape:window-width="1600"
|
||||||
|
inkscape:window-height="845"
|
||||||
|
inkscape:window-x="0"
|
||||||
|
inkscape:window-y="0"
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
units="px">
|
||||||
|
<inkscape:grid
|
||||||
|
type="xygrid"
|
||||||
|
id="grid5900"
|
||||||
|
originx="0"
|
||||||
|
originy="6.8902557e-05"
|
||||||
|
empspacing="4" />
|
||||||
|
</sodipodi:namedview>
|
||||||
|
<metadata
|
||||||
|
id="metadata5105">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
inkscape:label="test1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
id="layer1"
|
||||||
|
transform="translate(814.21766,568.50997)">
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -810.32002,-557.59658 0.10236,1785.08658 318.89764,0 0,-162.9922"
|
||||||
|
id="path11563"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cccc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -491.32002,1021.9782 0,-28.34651 -318.89764,0"
|
||||||
|
id="path11567"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="ccc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -491.32002,993.63169 0,-38.9764"
|
||||||
|
id="path11569"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -491.32002,919.22219 0,-123.81877"
|
||||||
|
id="path11571"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -491.32002,320.40335 0,-464.17327"
|
||||||
|
id="path11577"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -491.32002,-179.203 0,-109.84247"
|
||||||
|
id="path11581"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -413.32002,320.40342 -246,0"
|
||||||
|
id="path11587"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -711.32002,320.40342 -98.89764,-7e-5"
|
||||||
|
id="path11589"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -491.32002,-288.59658 -319,0"
|
||||||
|
id="path11593"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -475.32002,-345.59665 -235.68504,-0.14174 0,-131.10236"
|
||||||
|
id="path11597"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="ccc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -475.32002,-551.59665 0,206"
|
||||||
|
id="path11605"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -711.00506,-515.81713 0,-42.51968"
|
||||||
|
id="path11607"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -491.32002,1227.49 287.00787,0 -0.008,-1117.08658"
|
||||||
|
id="path11619"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="ccc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -425.32002,795.40342 150,0"
|
||||||
|
id="path11623"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -413.32002,864.40342 209,0"
|
||||||
|
id="path11627"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -413.36727,1032.6081 209.05512,0"
|
||||||
|
id="path11631"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -413.32002,864.40342 -0.0472,302.85038"
|
||||||
|
id="path11633"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -413.32002,795.40342 0,-207"
|
||||||
|
id="path11637"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -420.45388,-345.73843 53.14961,0"
|
||||||
|
id="path11669"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -321.24128,-345.73843 38.97638,0"
|
||||||
|
id="path11671"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -409.82396,-427.23449 0,81.49606"
|
||||||
|
id="path11673"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -409.82396,-427.23449 173.62205,0"
|
||||||
|
id="path11675"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -321.24128,-345.73843 0,-81.49606"
|
||||||
|
id="path11677"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -236.20191,-558.33685 0,212.59842 139.88189,0.14185"
|
||||||
|
id="path11679"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="ccc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -413.32002,-223.59658 0,544"
|
||||||
|
id="path11757"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -123.32002,-223.59658 27,0"
|
||||||
|
id="path11761"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -310.61136,-491.01402 -102.75591,0"
|
||||||
|
id="path11822"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -563.32002,696.40342 150,0"
|
||||||
|
id="path4208"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -392.10742,-427.23449 0,-63.77953"
|
||||||
|
id="path5833"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -392.10742,-491.01402 0,-67.32283"
|
||||||
|
id="path5847"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -810.32002,-557.59658 715,0"
|
||||||
|
id="path5902"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -355.32002,110.40342 260,0"
|
||||||
|
id="path5923"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -96.32002,-557.59658 0,668"
|
||||||
|
id="path5925"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -491.32002,660.40339 0,-139.99997"
|
||||||
|
id="path5929"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -810.32002,384.40342 183,0"
|
||||||
|
id="path5931"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -627.32002,384.40342 60,24 52,52"
|
||||||
|
id="path5933"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="ccc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -515.32002,460.40342 24,60"
|
||||||
|
id="path5935"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -413.32002,-223.59658 246,0"
|
||||||
|
id="path5937"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -413.32002,795.40342 -78,0"
|
||||||
|
id="path5939"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -413.32002,600.40339 134,3e-5"
|
||||||
|
id="path5941"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -563.32002,696.40342 72,98.99997"
|
||||||
|
id="path5945"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -413.32002,528.40342 134,0"
|
||||||
|
id="path5947"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -413.32002,320.40342 22,0"
|
||||||
|
id="path5951"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -359.32002,320.40342 155,0"
|
||||||
|
id="path5953"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -413.32002,540.40342 0,-156"
|
||||||
|
id="path5955"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -239.32002,600.40339 35,3e-5"
|
||||||
|
id="path5959"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -239.32002,528.40339 35,3e-5"
|
||||||
|
id="path5961"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -413.32002,110.40342 22,0"
|
||||||
|
id="path5965"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -235.32002,795.40342 31,-3e-5"
|
||||||
|
id="path5967"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
</g>
|
||||||
|
</svg>
|
||||||
|
After Width: | Height: | Size: 15 KiB |
@@ -16,7 +16,7 @@ public:
|
|||||||
//return 1;
|
//return 1;
|
||||||
|
|
||||||
// //rho_z
|
// //rho_z
|
||||||
double barometerSigma = 0.09;
|
double barometerSigma = 0.12+0.04;//0.09;
|
||||||
|
|
||||||
// //The height of the single floor levels.
|
// //The height of the single floor levels.
|
||||||
// const static double floor_height[3] = {4.1, 3.4, 3.4};
|
// const static double floor_height[3] = {4.1, 3.4, 3.4};
|
||||||
|
|||||||
@@ -45,7 +45,7 @@ public:
|
|||||||
|
|
||||||
obs->hpa = hPa - first_hPa;
|
obs->hpa = hPa - first_hPa;
|
||||||
|
|
||||||
std::cout << obs->hpa << std::endl;
|
//std::cout << obs->hpa << std::endl;
|
||||||
|
|
||||||
// done
|
// done
|
||||||
return obs;
|
return obs;
|
||||||
|
|||||||
@@ -182,6 +182,8 @@
|
|||||||
|
|
||||||
\input{chapters/system}
|
\input{chapters/system}
|
||||||
|
|
||||||
|
\input{chapters/floorplan}
|
||||||
|
|
||||||
\input{chapters/grid}
|
\input{chapters/grid}
|
||||||
|
|
||||||
\input{chapters/experiments}
|
\input{chapters/experiments}
|
||||||
|
|||||||
53
tex/chapters/floorplan.tex
Normal file
53
tex/chapters/floorplan.tex
Normal file
@@ -0,0 +1,53 @@
|
|||||||
|
\section{Floorplan/Path/whatever (RENAME)}
|
||||||
|
|
||||||
|
\subsection{wall avoidance}
|
||||||
|
|
||||||
|
\begin{figure}
|
||||||
|
\includegraphics[angle=-90, width=\columnwidth, trim=15 15 15 15]{floorplan_importance}
|
||||||
|
\end{figure}
|
||||||
|
|
||||||
|
|
||||||
|
\subsection{door detection}
|
||||||
|
|
||||||
|
invert grid,
|
||||||
|
find k-NN within inversion
|
||||||
|
calculate centroid, covariance and eigenvalues
|
||||||
|
when centroid OK and eigenvalues OK: is door/passage
|
||||||
|
|
||||||
|
\commentByFrank {
|
||||||
|
doors serve 3 purposes:
|
||||||
|
- reverting the downvote due to "near walls"
|
||||||
|
- hint for a pathless-movement-model how to leave rooms
|
||||||
|
- also detecting narrow passages (center the path)
|
||||||
|
}
|
||||||
|
|
||||||
|
Doors are usually anchored between two (thin) walls and have a normed width. Examining only a limited region
|
||||||
|
around the door, its surrounding walls describe a flat ellipse with the same center as the door itself. It is thus
|
||||||
|
possible to detect doors within the floorplan using the PCA \todo{cite}. To describe the surroundings of a door,
|
||||||
|
we create and inverted version of our grid whereby the contained nodes denote walls and other obstacles.
|
||||||
|
To decide whether a node within the (non-inverted) grid belongs to a door, we use $k$-NN \todo{cite} to fetch its
|
||||||
|
$k$ nearest neighbors within the inverted grid. If the distance \todo{equation} between the centroid of those neighbors
|
||||||
|
and the node-in-question is above certain threshold, the node does not belong to a door. Assuming the distance was fine,
|
||||||
|
we compare the two eigenvalues $\{e_1, e_2 \mid e_1 > e_2\}$ , determined by the PCA. If their ratio $\frac{e_1}{e_2}$ is above
|
||||||
|
a certain threshold (flat ellipse)
|
||||||
|
the node-in-question belongs to a door. Fig. \ref{fig:doorPCA} depicts all three cases where the node is part of a door (left),
|
||||||
|
the distance between node and k-NN centroid is above the threshold (middle) and the ration between $e_1$ and $e_2$ is below the
|
||||||
|
threshold (right).
|
||||||
|
|
||||||
|
\begin{figure}
|
||||||
|
\includegraphics[width=\columnwidth]{door_pca}
|
||||||
|
\caption{Detect doors within the floorplan using k-NN and PCA. While the white nodes are walkable, the black ones represent walls. The grey node is the one in question.}
|
||||||
|
\label{fig:doorPCA}
|
||||||
|
\end{figure}
|
||||||
|
|
||||||
|
|
||||||
|
\subsection{pathfinding}
|
||||||
|
|
||||||
|
\begin{figure}
|
||||||
|
\includegraphics[angle=-90, width=\columnwidth, trim=15 15 15 15]{floorplan_paths}
|
||||||
|
\end{figure}
|
||||||
|
|
||||||
|
\begin{figure}
|
||||||
|
\includegraphics[angle=-90, width=\columnwidth, trim=15 15 15 15]{floorplan_dijkstra_heatmap}
|
||||||
|
\end{figure}
|
||||||
|
|
||||||
552
tex/gfx/door_pca.eps
Normal file
552
tex/gfx/door_pca.eps
Normal file
@@ -0,0 +1,552 @@
|
|||||||
|
%!PS-Adobe-3.0 EPSF-3.0
|
||||||
|
%%Creator: cairo 1.14.4 (http://cairographics.org)
|
||||||
|
%%CreationDate: Wed Feb 3 18:26:16 2016
|
||||||
|
%%Pages: 1
|
||||||
|
%%DocumentData: Clean7Bit
|
||||||
|
%%LanguageLevel: 2
|
||||||
|
%%BoundingBox: 3 2 356 37
|
||||||
|
%%EndComments
|
||||||
|
%%BeginProlog
|
||||||
|
save
|
||||||
|
50 dict begin
|
||||||
|
/q { gsave } bind def
|
||||||
|
/Q { grestore } bind def
|
||||||
|
/cm { 6 array astore concat } bind def
|
||||||
|
/w { setlinewidth } bind def
|
||||||
|
/J { setlinecap } bind def
|
||||||
|
/j { setlinejoin } bind def
|
||||||
|
/M { setmiterlimit } bind def
|
||||||
|
/d { setdash } bind def
|
||||||
|
/m { moveto } bind def
|
||||||
|
/l { lineto } bind def
|
||||||
|
/c { curveto } bind def
|
||||||
|
/h { closepath } bind def
|
||||||
|
/re { exch dup neg 3 1 roll 5 3 roll moveto 0 rlineto
|
||||||
|
0 exch rlineto 0 rlineto closepath } bind def
|
||||||
|
/S { stroke } bind def
|
||||||
|
/f { fill } bind def
|
||||||
|
/f* { eofill } bind def
|
||||||
|
/n { newpath } bind def
|
||||||
|
/W { clip } bind def
|
||||||
|
/W* { eoclip } bind def
|
||||||
|
/BT { } bind def
|
||||||
|
/ET { } bind def
|
||||||
|
/pdfmark where { pop globaldict /?pdfmark /exec load put }
|
||||||
|
{ globaldict begin /?pdfmark /pop load def /pdfmark
|
||||||
|
/cleartomark load def end } ifelse
|
||||||
|
/BDC { mark 3 1 roll /BDC pdfmark } bind def
|
||||||
|
/EMC { mark /EMC pdfmark } bind def
|
||||||
|
/cairo_store_point { /cairo_point_y exch def /cairo_point_x exch def } def
|
||||||
|
/Tj { show currentpoint cairo_store_point } bind def
|
||||||
|
/TJ {
|
||||||
|
{
|
||||||
|
dup
|
||||||
|
type /stringtype eq
|
||||||
|
{ show } { -0.001 mul 0 cairo_font_matrix dtransform rmoveto } ifelse
|
||||||
|
} forall
|
||||||
|
currentpoint cairo_store_point
|
||||||
|
} bind def
|
||||||
|
/cairo_selectfont { cairo_font_matrix aload pop pop pop 0 0 6 array astore
|
||||||
|
cairo_font exch selectfont cairo_point_x cairo_point_y moveto } bind def
|
||||||
|
/Tf { pop /cairo_font exch def /cairo_font_matrix where
|
||||||
|
{ pop cairo_selectfont } if } bind def
|
||||||
|
/Td { matrix translate cairo_font_matrix matrix concatmatrix dup
|
||||||
|
/cairo_font_matrix exch def dup 4 get exch 5 get cairo_store_point
|
||||||
|
/cairo_font where { pop cairo_selectfont } if } bind def
|
||||||
|
/Tm { 2 copy 8 2 roll 6 array astore /cairo_font_matrix exch def
|
||||||
|
cairo_store_point /cairo_font where { pop cairo_selectfont } if } bind def
|
||||||
|
/g { setgray } bind def
|
||||||
|
/rg { setrgbcolor } bind def
|
||||||
|
/d1 { setcachedevice } bind def
|
||||||
|
%%EndProlog
|
||||||
|
%%BeginSetup
|
||||||
|
%%EndSetup
|
||||||
|
%%Page: 1 1
|
||||||
|
%%BeginPageSetup
|
||||||
|
%%PageBoundingBox: 3 2 356 37
|
||||||
|
%%EndPageSetup
|
||||||
|
q 3 2 353 35 rectclip q
|
||||||
|
1 0.501961 0.501961 rg
|
||||||
|
281.602 19.201 m 281.602 10.365 273.004 3.201 262.398 3.201 c 251.797 3.201
|
||||||
|
243.199 10.365 243.199 19.201 c 243.199 28.037 251.797 35.201 262.398 35.201
|
||||||
|
c 273.004 35.201 281.602 28.037 281.602 19.201 c h
|
||||||
|
281.602 19.201 m f
|
||||||
|
0 g
|
||||||
|
0.8 w
|
||||||
|
0 J
|
||||||
|
0 j
|
||||||
|
[ 0.8 0.8] 0 d
|
||||||
|
4 M q 1 0 0 -1 0 38.400002 cm
|
||||||
|
281.602 19.199 m 281.602 28.035 273.004 35.199 262.398 35.199 c 251.797
|
||||||
|
35.199 243.199 28.035 243.199 19.199 c 243.199 10.363 251.797 3.199 262.398
|
||||||
|
3.199 c 273.004 3.199 281.602 10.363 281.602 19.199 c h
|
||||||
|
281.602 19.199 m S Q
|
||||||
|
0.501961 1 0.501961 rg
|
||||||
|
115.199 19.201 m 115.199 15.666 92.277 12.798 64 12.798 c 35.723 12.798
|
||||||
|
12.801 15.666 12.801 19.201 c 12.801 22.736 35.723 25.599 64 25.599 c 92.277
|
||||||
|
25.599 115.199 22.736 115.199 19.201 c h
|
||||||
|
115.199 19.201 m f
|
||||||
|
0 g
|
||||||
|
[ 0.8 0.8] 0 d
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
115.199 19.199 m 115.199 22.734 92.277 25.602 64 25.602 c 35.723 25.602
|
||||||
|
12.801 22.734 12.801 19.199 c 12.801 15.664 35.723 12.801 64 12.801 c 92.277
|
||||||
|
12.801 115.199 15.664 115.199 19.199 c h
|
||||||
|
115.199 19.199 m S Q
|
||||||
|
1 0.501961 0.501961 rg
|
||||||
|
236.801 19.201 m 236.801 15.666 216.742 12.798 192 12.798 c 167.258 12.798
|
||||||
|
147.199 15.666 147.199 19.201 c 147.199 22.736 167.258 25.599 192 25.599
|
||||||
|
c 216.742 25.599 236.801 22.736 236.801 19.201 c h
|
||||||
|
236.801 19.201 m f
|
||||||
|
0 g
|
||||||
|
[ 0.8 0.8] 0 d
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
236.801 19.199 m 236.801 22.734 216.742 25.602 192 25.602 c 167.258 25.602
|
||||||
|
147.199 22.734 147.199 19.199 c 147.199 15.664 167.258 12.801 192 12.801
|
||||||
|
c 216.742 12.801 236.801 15.664 236.801 19.199 c h
|
||||||
|
236.801 19.199 m S Q
|
||||||
|
0.501961 g
|
||||||
|
[] 0.0 d
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
48 19.199 m 48 20.969 46.566 22.398 44.801 22.398 c 43.031 22.398 41.602
|
||||||
|
20.969 41.602 19.199 c 41.602 17.434 43.031 16 44.801 16 c 46.566 16 48
|
||||||
|
17.434 48 19.199 c h
|
||||||
|
48 19.199 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
60.801 19.199 m 60.801 20.969 59.367 22.398 57.602 22.398 c 55.832 22.398
|
||||||
|
54.398 20.969 54.398 19.199 c 54.398 17.434 55.832 16 57.602 16 c 59.367
|
||||||
|
16 60.801 17.434 60.801 19.199 c h
|
||||||
|
60.801 19.199 m S Q
|
||||||
|
73.602 32.002 m 73.602 30.232 72.168 28.798 70.398 28.798 c 68.633 28.798
|
||||||
|
67.199 30.232 67.199 32.002 c 67.199 33.767 68.633 35.201 70.398 35.201
|
||||||
|
c 72.168 35.201 73.602 33.767 73.602 32.002 c h
|
||||||
|
73.602 32.002 m f
|
||||||
|
0 g
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
73.602 6.398 m 73.602 8.168 72.168 9.602 70.398 9.602 c 68.633 9.602 67.199
|
||||||
|
8.168 67.199 6.398 c 67.199 4.633 68.633 3.199 70.398 3.199 c 72.168 3.199
|
||||||
|
73.602 4.633 73.602 6.398 c h
|
||||||
|
73.602 6.398 m S Q
|
||||||
|
0.501961 g
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
86.398 19.199 m 86.398 20.969 84.969 22.398 83.199 22.398 c 81.434 22.398
|
||||||
|
80 20.969 80 19.199 c 80 17.434 81.434 16 83.199 16 c 84.969 16 86.398
|
||||||
|
17.434 86.398 19.199 c h
|
||||||
|
86.398 19.199 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
22.398 32 m 22.398 33.766 20.969 35.199 19.199 35.199 c 17.434 35.199 16
|
||||||
|
33.766 16 32 c 16 30.234 17.434 28.801 19.199 28.801 c 20.969 28.801 22.398
|
||||||
|
30.234 22.398 32 c h
|
||||||
|
22.398 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
35.199 32 m 35.199 33.766 33.766 35.199 32 35.199 c 30.234 35.199 28.801
|
||||||
|
33.766 28.801 32 c 28.801 30.234 30.234 28.801 32 28.801 c 33.766 28.801
|
||||||
|
35.199 30.234 35.199 32 c h
|
||||||
|
35.199 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
48 32 m 48 33.766 46.566 35.199 44.801 35.199 c 43.031 35.199 41.602 33.766
|
||||||
|
41.602 32 c 41.602 30.234 43.031 28.801 44.801 28.801 c 46.566 28.801 48
|
||||||
|
30.234 48 32 c h
|
||||||
|
48 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
60.801 32 m 60.801 33.766 59.367 35.199 57.602 35.199 c 55.832 35.199 54.398
|
||||||
|
33.766 54.398 32 c 54.398 30.234 55.832 28.801 57.602 28.801 c 59.367 28.801
|
||||||
|
60.801 30.234 60.801 32 c h
|
||||||
|
60.801 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
73.602 32 m 73.602 33.766 72.168 35.199 70.398 35.199 c 68.633 35.199 67.199
|
||||||
|
33.766 67.199 32 c 67.199 30.234 68.633 28.801 70.398 28.801 c 72.168 28.801
|
||||||
|
73.602 30.234 73.602 32 c h
|
||||||
|
73.602 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
86.398 32 m 86.398 33.766 84.969 35.199 83.199 35.199 c 81.434 35.199 80
|
||||||
|
33.766 80 32 c 80 30.234 81.434 28.801 83.199 28.801 c 84.969 28.801 86.398
|
||||||
|
30.234 86.398 32 c h
|
||||||
|
86.398 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
99.199 32 m 99.199 33.766 97.766 35.199 96 35.199 c 94.234 35.199 92.801
|
||||||
|
33.766 92.801 32 c 92.801 30.234 94.234 28.801 96 28.801 c 97.766 28.801
|
||||||
|
99.199 30.234 99.199 32 c h
|
||||||
|
99.199 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
112 32 m 112 33.766 110.566 35.199 108.801 35.199 c 107.031 35.199 105.602
|
||||||
|
33.766 105.602 32 c 105.602 30.234 107.031 28.801 108.801 28.801 c 110.566
|
||||||
|
28.801 112 30.234 112 32 c h
|
||||||
|
112 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
22.398 6.398 m 22.398 8.168 20.969 9.602 19.199 9.602 c 17.434 9.602 16
|
||||||
|
8.168 16 6.398 c 16 4.633 17.434 3.199 19.199 3.199 c 20.969 3.199 22.398
|
||||||
|
4.633 22.398 6.398 c h
|
||||||
|
22.398 6.398 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
35.199 6.398 m 35.199 8.168 33.766 9.602 32 9.602 c 30.234 9.602 28.801
|
||||||
|
8.168 28.801 6.398 c 28.801 4.633 30.234 3.199 32 3.199 c 33.766 3.199
|
||||||
|
35.199 4.633 35.199 6.398 c h
|
||||||
|
35.199 6.398 m S Q
|
||||||
|
0 g
|
||||||
|
9.602 6.4 m 9.602 4.634 8.168 3.201 6.398 3.201 c 4.633 3.201 3.199 4.634
|
||||||
|
3.199 6.4 c 3.199 8.166 4.633 9.599 6.398 9.599 c 8.168 9.599 9.602 8.166
|
||||||
|
9.602 6.4 c h
|
||||||
|
9.602 6.4 m f
|
||||||
|
0.501961 g
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
220.801 6.398 m 220.801 8.168 219.367 9.602 217.602 9.602 c 215.832 9.602
|
||||||
|
214.398 8.168 214.398 6.398 c 214.398 4.633 215.832 3.199 217.602 3.199
|
||||||
|
c 219.367 3.199 220.801 4.633 220.801 6.398 c h
|
||||||
|
220.801 6.398 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
86.398 6.398 m 86.398 8.168 84.969 9.602 83.199 9.602 c 81.434 9.602 80
|
||||||
|
8.168 80 6.398 c 80 4.633 81.434 3.199 83.199 3.199 c 84.969 3.199 86.398
|
||||||
|
4.633 86.398 6.398 c h
|
||||||
|
86.398 6.398 m S Q
|
||||||
|
0 g
|
||||||
|
9.602 19.201 m 9.602 17.431 8.168 16.002 6.398 16.002 c 4.633 16.002 3.199
|
||||||
|
17.431 3.199 19.201 c 3.199 20.966 4.633 22.4 6.398 22.4 c 8.168 22.4 9.602
|
||||||
|
20.966 9.602 19.201 c h
|
||||||
|
9.602 19.201 m f
|
||||||
|
22.398 19.201 m 22.398 17.431 20.969 16.002 19.199 16.002 c 17.434 16.002
|
||||||
|
16 17.431 16 19.201 c 16 20.966 17.434 22.4 19.199 22.4 c 20.969 22.4 22.398
|
||||||
|
20.966 22.398 19.201 c h
|
||||||
|
22.398 19.201 m f
|
||||||
|
35.199 19.201 m 35.199 17.431 33.766 16.002 32 16.002 c 30.234 16.002 28.801
|
||||||
|
17.431 28.801 19.201 c 28.801 20.966 30.234 22.4 32 22.4 c 33.766 22.4
|
||||||
|
35.199 20.966 35.199 19.201 c h
|
||||||
|
35.199 19.201 m f
|
||||||
|
99.199 19.201 m 99.199 17.431 97.766 16.002 96 16.002 c 94.234 16.002 92.801
|
||||||
|
17.431 92.801 19.201 c 92.801 20.966 94.234 22.4 96 22.4 c 97.766 22.4
|
||||||
|
99.199 20.966 99.199 19.201 c h
|
||||||
|
99.199 19.201 m f
|
||||||
|
112 19.201 m 112 17.431 110.566 16.002 108.801 16.002 c 107.031 16.002
|
||||||
|
105.602 17.431 105.602 19.201 c 105.602 20.966 107.031 22.4 108.801 22.4
|
||||||
|
c 110.566 22.4 112 20.966 112 19.201 c h
|
||||||
|
112 19.201 m f
|
||||||
|
0.501961 g
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
48 6.398 m 48 8.168 46.566 9.602 44.801 9.602 c 43.031 9.602 41.602 8.168
|
||||||
|
41.602 6.398 c 41.602 4.633 43.031 3.199 44.801 3.199 c 46.566 3.199 48
|
||||||
|
4.633 48 6.398 c h
|
||||||
|
48 6.398 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
60.801 6.398 m 60.801 8.168 59.367 9.602 57.602 9.602 c 55.832 9.602 54.398
|
||||||
|
8.168 54.398 6.398 c 54.398 4.633 55.832 3.199 57.602 3.199 c 59.367 3.199
|
||||||
|
60.801 4.633 60.801 6.398 c h
|
||||||
|
60.801 6.398 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
73.602 19.199 m 73.602 20.969 72.168 22.398 70.398 22.398 c 68.633 22.398
|
||||||
|
67.199 20.969 67.199 19.199 c 67.199 17.434 68.633 16 70.398 16 c 72.168
|
||||||
|
16 73.602 17.434 73.602 19.199 c h
|
||||||
|
73.602 19.199 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
99.199 6.398 m 99.199 8.168 97.766 9.602 96 9.602 c 94.234 9.602 92.801
|
||||||
|
8.168 92.801 6.398 c 92.801 4.633 94.234 3.199 96 3.199 c 97.766 3.199
|
||||||
|
99.199 4.633 99.199 6.398 c h
|
||||||
|
99.199 6.398 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
112 6.398 m 112 8.168 110.566 9.602 108.801 9.602 c 107.031 9.602 105.602
|
||||||
|
8.168 105.602 6.398 c 105.602 4.633 107.031 3.199 108.801 3.199 c 110.566
|
||||||
|
3.199 112 4.633 112 6.398 c h
|
||||||
|
112 6.398 m S Q
|
||||||
|
0 g
|
||||||
|
9.602 32.002 m 9.602 30.232 8.168 28.798 6.398 28.798 c 4.633 28.798 3.199
|
||||||
|
30.232 3.199 32.002 c 3.199 33.767 4.633 35.201 6.398 35.201 c 8.168 35.201
|
||||||
|
9.602 33.767 9.602 32.002 c h
|
||||||
|
9.602 32.002 m f
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
64 19.199 m 64 12.801 l S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
64 19.199 m 12.801 19.199 l S Q
|
||||||
|
0 0 0.752941 rg
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
64 19.199 m 70.398 6.398 l S Q
|
||||||
|
0.501961 g
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
169.602 19.199 m 169.602 20.969 168.168 22.398 166.398 22.398 c 164.633
|
||||||
|
22.398 163.199 20.969 163.199 19.199 c 163.199 17.434 164.633 16 166.398
|
||||||
|
16 c 168.168 16 169.602 17.434 169.602 19.199 c h
|
||||||
|
169.602 19.199 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
182.398 19.199 m 182.398 20.969 180.969 22.398 179.199 22.398 c 177.434
|
||||||
|
22.398 176 20.969 176 19.199 c 176 17.434 177.434 16 179.199 16 c 180.969
|
||||||
|
16 182.398 17.434 182.398 19.199 c h
|
||||||
|
182.398 19.199 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
208 19.199 m 208 20.969 206.566 22.398 204.801 22.398 c 203.031 22.398
|
||||||
|
201.602 20.969 201.602 19.199 c 201.602 17.434 203.031 16 204.801 16 c 206.566
|
||||||
|
16 208 17.434 208 19.199 c h
|
||||||
|
208 19.199 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
144 32 m 144 33.766 142.566 35.199 140.801 35.199 c 139.031 35.199 137.602
|
||||||
|
33.766 137.602 32 c 137.602 30.234 139.031 28.801 140.801 28.801 c 142.566
|
||||||
|
28.801 144 30.234 144 32 c h
|
||||||
|
144 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
156.801 32 m 156.801 33.766 155.367 35.199 153.602 35.199 c 151.832 35.199
|
||||||
|
150.398 33.766 150.398 32 c 150.398 30.234 151.832 28.801 153.602 28.801
|
||||||
|
c 155.367 28.801 156.801 30.234 156.801 32 c h
|
||||||
|
156.801 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
169.602 32 m 169.602 33.766 168.168 35.199 166.398 35.199 c 164.633 35.199
|
||||||
|
163.199 33.766 163.199 32 c 163.199 30.234 164.633 28.801 166.398 28.801
|
||||||
|
c 168.168 28.801 169.602 30.234 169.602 32 c h
|
||||||
|
169.602 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
182.398 32 m 182.398 33.766 180.969 35.199 179.199 35.199 c 177.434 35.199
|
||||||
|
176 33.766 176 32 c 176 30.234 177.434 28.801 179.199 28.801 c 180.969
|
||||||
|
28.801 182.398 30.234 182.398 32 c h
|
||||||
|
182.398 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
195.199 32 m 195.199 33.766 193.766 35.199 192 35.199 c 190.234 35.199
|
||||||
|
188.801 33.766 188.801 32 c 188.801 30.234 190.234 28.801 192 28.801 c 193.766
|
||||||
|
28.801 195.199 30.234 195.199 32 c h
|
||||||
|
195.199 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
208 32 m 208 33.766 206.566 35.199 204.801 35.199 c 203.031 35.199 201.602
|
||||||
|
33.766 201.602 32 c 201.602 30.234 203.031 28.801 204.801 28.801 c 206.566
|
||||||
|
28.801 208 30.234 208 32 c h
|
||||||
|
208 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
220.801 32 m 220.801 33.766 219.367 35.199 217.602 35.199 c 215.832 35.199
|
||||||
|
214.398 33.766 214.398 32 c 214.398 30.234 215.832 28.801 217.602 28.801
|
||||||
|
c 219.367 28.801 220.801 30.234 220.801 32 c h
|
||||||
|
220.801 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
233.602 32 m 233.602 33.766 232.168 35.199 230.398 35.199 c 228.633 35.199
|
||||||
|
227.199 33.766 227.199 32 c 227.199 30.234 228.633 28.801 230.398 28.801
|
||||||
|
c 232.168 28.801 233.602 30.234 233.602 32 c h
|
||||||
|
233.602 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
144 6.398 m 144 8.168 142.566 9.602 140.801 9.602 c 139.031 9.602 137.602
|
||||||
|
8.168 137.602 6.398 c 137.602 4.633 139.031 3.199 140.801 3.199 c 142.566
|
||||||
|
3.199 144 4.633 144 6.398 c h
|
||||||
|
144 6.398 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
156.801 6.398 m 156.801 8.168 155.367 9.602 153.602 9.602 c 151.832 9.602
|
||||||
|
150.398 8.168 150.398 6.398 c 150.398 4.633 151.832 3.199 153.602 3.199
|
||||||
|
c 155.367 3.199 156.801 4.633 156.801 6.398 c h
|
||||||
|
156.801 6.398 m S Q
|
||||||
|
0 g
|
||||||
|
131.199 6.4 m 131.199 4.634 129.766 3.201 128 3.201 c 126.234 3.201 124.801
|
||||||
|
4.634 124.801 6.4 c 124.801 8.166 126.234 9.599 128 9.599 c 129.766 9.599
|
||||||
|
131.199 8.166 131.199 6.4 c h
|
||||||
|
131.199 6.4 m f
|
||||||
|
131.199 19.201 m 131.199 17.431 129.766 16.002 128 16.002 c 126.234 16.002
|
||||||
|
124.801 17.431 124.801 19.201 c 124.801 20.966 126.234 22.4 128 22.4 c
|
||||||
|
129.766 22.4 131.199 20.966 131.199 19.201 c h
|
||||||
|
131.199 19.201 m f
|
||||||
|
144 19.201 m 144 17.431 142.566 16.002 140.801 16.002 c 139.031 16.002
|
||||||
|
137.602 17.431 137.602 19.201 c 137.602 20.966 139.031 22.4 140.801 22.4
|
||||||
|
c 142.566 22.4 144 20.966 144 19.201 c h
|
||||||
|
144 19.201 m f
|
||||||
|
156.801 19.201 m 156.801 17.431 155.367 16.002 153.602 16.002 c 151.832
|
||||||
|
16.002 150.398 17.431 150.398 19.201 c 150.398 20.966 151.832 22.4 153.602
|
||||||
|
22.4 c 155.367 22.4 156.801 20.966 156.801 19.201 c h
|
||||||
|
156.801 19.201 m f
|
||||||
|
220.801 19.201 m 220.801 17.431 219.367 16.002 217.602 16.002 c 215.832
|
||||||
|
16.002 214.398 17.431 214.398 19.201 c 214.398 20.966 215.832 22.4 217.602
|
||||||
|
22.4 c 219.367 22.4 220.801 20.966 220.801 19.201 c h
|
||||||
|
220.801 19.201 m f
|
||||||
|
233.602 19.201 m 233.602 17.431 232.168 16.002 230.398 16.002 c 228.633
|
||||||
|
16.002 227.199 17.431 227.199 19.201 c 227.199 20.966 228.633 22.4 230.398
|
||||||
|
22.4 c 232.168 22.4 233.602 20.966 233.602 19.201 c h
|
||||||
|
233.602 19.201 m f
|
||||||
|
0.501961 g
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
169.602 6.398 m 169.602 8.168 168.168 9.602 166.398 9.602 c 164.633 9.602
|
||||||
|
163.199 8.168 163.199 6.398 c 163.199 4.633 164.633 3.199 166.398 3.199
|
||||||
|
c 168.168 3.199 169.602 4.633 169.602 6.398 c h
|
||||||
|
169.602 6.398 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
182.398 6.398 m 182.398 8.168 180.969 9.602 179.199 9.602 c 177.434 9.602
|
||||||
|
176 8.168 176 6.398 c 176 4.633 177.434 3.199 179.199 3.199 c 180.969 3.199
|
||||||
|
182.398 4.633 182.398 6.398 c h
|
||||||
|
182.398 6.398 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
195.199 6.398 m 195.199 8.168 193.766 9.602 192 9.602 c 190.234 9.602 188.801
|
||||||
|
8.168 188.801 6.398 c 188.801 4.633 190.234 3.199 192 3.199 c 193.766 3.199
|
||||||
|
195.199 4.633 195.199 6.398 c h
|
||||||
|
195.199 6.398 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
208 6.398 m 208 8.168 206.566 9.602 204.801 9.602 c 203.031 9.602 201.602
|
||||||
|
8.168 201.602 6.398 c 201.602 4.633 203.031 3.199 204.801 3.199 c 206.566
|
||||||
|
3.199 208 4.633 208 6.398 c h
|
||||||
|
208 6.398 m S Q
|
||||||
|
0 g
|
||||||
|
131.199 32.002 m 131.199 30.232 129.766 28.798 128 28.798 c 126.234 28.798
|
||||||
|
124.801 30.232 124.801 32.002 c 124.801 33.767 126.234 35.201 128 35.201
|
||||||
|
c 129.766 35.201 131.199 33.767 131.199 32.002 c h
|
||||||
|
131.199 32.002 m f
|
||||||
|
0.501961 g
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
195.199 19.199 m 195.199 20.969 193.766 22.398 192 22.398 c 190.234 22.398
|
||||||
|
188.801 20.969 188.801 19.199 c 188.801 17.434 190.234 16 192 16 c 193.766
|
||||||
|
16 195.199 17.434 195.199 19.199 c h
|
||||||
|
195.199 19.199 m S Q
|
||||||
|
233.602 32.002 m 233.602 30.232 232.168 28.798 230.398 28.798 c 228.633
|
||||||
|
28.798 227.199 30.232 227.199 32.002 c 227.199 33.767 228.633 35.201 230.398
|
||||||
|
35.201 c 232.168 35.201 233.602 33.767 233.602 32.002 c h
|
||||||
|
233.602 32.002 m f
|
||||||
|
0 g
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
233.602 6.398 m 233.602 8.168 232.168 9.602 230.398 9.602 c 228.633 9.602
|
||||||
|
227.199 8.168 227.199 6.398 c 227.199 4.633 228.633 3.199 230.398 3.199
|
||||||
|
c 232.168 3.199 233.602 4.633 233.602 6.398 c h
|
||||||
|
233.602 6.398 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
192 19.199 m 192 12.801 l S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
192 19.199 m 147.199 19.199 l S Q
|
||||||
|
0 0 0.752941 rg
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
192 19.199 m 230.398 6.398 l S Q
|
||||||
|
0.501961 g
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
291.199 19.199 m 291.199 20.969 289.766 22.398 288 22.398 c 286.234 22.398
|
||||||
|
284.801 20.969 284.801 19.199 c 284.801 17.434 286.234 16 288 16 c 289.766
|
||||||
|
16 291.199 17.434 291.199 19.199 c h
|
||||||
|
291.199 19.199 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
304 19.199 m 304 20.969 302.566 22.398 300.801 22.398 c 299.031 22.398
|
||||||
|
297.602 20.969 297.602 19.199 c 297.602 17.434 299.031 16 300.801 16 c 302.566
|
||||||
|
16 304 17.434 304 19.199 c h
|
||||||
|
304 19.199 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
329.602 19.199 m 329.602 20.969 328.168 22.398 326.398 22.398 c 324.633
|
||||||
|
22.398 323.199 20.969 323.199 19.199 c 323.199 17.434 324.633 16 326.398
|
||||||
|
16 c 328.168 16 329.602 17.434 329.602 19.199 c h
|
||||||
|
329.602 19.199 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
265.602 32 m 265.602 33.766 264.168 35.199 262.398 35.199 c 260.633 35.199
|
||||||
|
259.199 33.766 259.199 32 c 259.199 30.234 260.633 28.801 262.398 28.801
|
||||||
|
c 264.168 28.801 265.602 30.234 265.602 32 c h
|
||||||
|
265.602 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
278.398 32 m 278.398 33.766 276.969 35.199 275.199 35.199 c 273.434 35.199
|
||||||
|
272 33.766 272 32 c 272 30.234 273.434 28.801 275.199 28.801 c 276.969
|
||||||
|
28.801 278.398 30.234 278.398 32 c h
|
||||||
|
278.398 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
291.199 32 m 291.199 33.766 289.766 35.199 288 35.199 c 286.234 35.199
|
||||||
|
284.801 33.766 284.801 32 c 284.801 30.234 286.234 28.801 288 28.801 c 289.766
|
||||||
|
28.801 291.199 30.234 291.199 32 c h
|
||||||
|
291.199 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
304 32 m 304 33.766 302.566 35.199 300.801 35.199 c 299.031 35.199 297.602
|
||||||
|
33.766 297.602 32 c 297.602 30.234 299.031 28.801 300.801 28.801 c 302.566
|
||||||
|
28.801 304 30.234 304 32 c h
|
||||||
|
304 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
316.801 32 m 316.801 33.766 315.367 35.199 313.602 35.199 c 311.832 35.199
|
||||||
|
310.398 33.766 310.398 32 c 310.398 30.234 311.832 28.801 313.602 28.801
|
||||||
|
c 315.367 28.801 316.801 30.234 316.801 32 c h
|
||||||
|
316.801 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
329.602 32 m 329.602 33.766 328.168 35.199 326.398 35.199 c 324.633 35.199
|
||||||
|
323.199 33.766 323.199 32 c 323.199 30.234 324.633 28.801 326.398 28.801
|
||||||
|
c 328.168 28.801 329.602 30.234 329.602 32 c h
|
||||||
|
329.602 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
342.398 32 m 342.398 33.766 340.969 35.199 339.199 35.199 c 337.434 35.199
|
||||||
|
336 33.766 336 32 c 336 30.234 337.434 28.801 339.199 28.801 c 340.969
|
||||||
|
28.801 342.398 30.234 342.398 32 c h
|
||||||
|
342.398 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
355.199 32 m 355.199 33.766 353.766 35.199 352 35.199 c 350.234 35.199
|
||||||
|
348.801 33.766 348.801 32 c 348.801 30.234 350.234 28.801 352 28.801 c 353.766
|
||||||
|
28.801 355.199 30.234 355.199 32 c h
|
||||||
|
355.199 32 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
265.602 6.398 m 265.602 8.168 264.168 9.602 262.398 9.602 c 260.633 9.602
|
||||||
|
259.199 8.168 259.199 6.398 c 259.199 4.633 260.633 3.199 262.398 3.199
|
||||||
|
c 264.168 3.199 265.602 4.633 265.602 6.398 c h
|
||||||
|
265.602 6.398 m S Q
|
||||||
|
0 g
|
||||||
|
252.801 6.4 m 252.801 4.634 251.367 3.201 249.602 3.201 c 247.832 3.201
|
||||||
|
246.398 4.634 246.398 6.4 c 246.398 8.166 247.832 9.599 249.602 9.599 c
|
||||||
|
251.367 9.599 252.801 8.166 252.801 6.4 c h
|
||||||
|
252.801 6.4 m f
|
||||||
|
252.801 19.201 m 252.801 17.431 251.367 16.002 249.602 16.002 c 247.832
|
||||||
|
16.002 246.398 17.431 246.398 19.201 c 246.398 20.966 247.832 22.4 249.602
|
||||||
|
22.4 c 251.367 22.4 252.801 20.966 252.801 19.201 c h
|
||||||
|
252.801 19.201 m f
|
||||||
|
265.602 19.201 m 265.602 17.431 264.168 16.002 262.398 16.002 c 260.633
|
||||||
|
16.002 259.199 17.431 259.199 19.201 c 259.199 20.966 260.633 22.4 262.398
|
||||||
|
22.4 c 264.168 22.4 265.602 20.966 265.602 19.201 c h
|
||||||
|
265.602 19.201 m f
|
||||||
|
278.398 19.201 m 278.398 17.431 276.969 16.002 275.199 16.002 c 273.434
|
||||||
|
16.002 272 17.431 272 19.201 c 272 20.966 273.434 22.4 275.199 22.4 c 276.969
|
||||||
|
22.4 278.398 20.966 278.398 19.201 c h
|
||||||
|
278.398 19.201 m f
|
||||||
|
342.398 19.201 m 342.398 17.431 340.969 16.002 339.199 16.002 c 337.434
|
||||||
|
16.002 336 17.431 336 19.201 c 336 20.966 337.434 22.4 339.199 22.4 c 340.969
|
||||||
|
22.4 342.398 20.966 342.398 19.201 c h
|
||||||
|
342.398 19.201 m f
|
||||||
|
355.199 19.201 m 355.199 17.431 353.766 16.002 352 16.002 c 350.234 16.002
|
||||||
|
348.801 17.431 348.801 19.201 c 348.801 20.966 350.234 22.4 352 22.4 c
|
||||||
|
353.766 22.4 355.199 20.966 355.199 19.201 c h
|
||||||
|
355.199 19.201 m f
|
||||||
|
0.501961 g
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
304 6.398 m 304 8.168 302.566 9.602 300.801 9.602 c 299.031 9.602 297.602
|
||||||
|
8.168 297.602 6.398 c 297.602 4.633 299.031 3.199 300.801 3.199 c 302.566
|
||||||
|
3.199 304 4.633 304 6.398 c h
|
||||||
|
304 6.398 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
316.801 6.398 m 316.801 8.168 315.367 9.602 313.602 9.602 c 311.832 9.602
|
||||||
|
310.398 8.168 310.398 6.398 c 310.398 4.633 311.832 3.199 313.602 3.199
|
||||||
|
c 315.367 3.199 316.801 4.633 316.801 6.398 c h
|
||||||
|
316.801 6.398 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
329.602 6.398 m 329.602 8.168 328.168 9.602 326.398 9.602 c 324.633 9.602
|
||||||
|
323.199 8.168 323.199 6.398 c 323.199 4.633 324.633 3.199 326.398 3.199
|
||||||
|
c 328.168 3.199 329.602 4.633 329.602 6.398 c h
|
||||||
|
329.602 6.398 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
342.398 6.398 m 342.398 8.168 340.969 9.602 339.199 9.602 c 337.434 9.602
|
||||||
|
336 8.168 336 6.398 c 336 4.633 337.434 3.199 339.199 3.199 c 340.969 3.199
|
||||||
|
342.398 4.633 342.398 6.398 c h
|
||||||
|
342.398 6.398 m S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
355.199 6.398 m 355.199 8.168 353.766 9.602 352 9.602 c 350.234 9.602 348.801
|
||||||
|
8.168 348.801 6.398 c 348.801 4.633 350.234 3.199 352 3.199 c 353.766 3.199
|
||||||
|
355.199 4.633 355.199 6.398 c h
|
||||||
|
355.199 6.398 m S Q
|
||||||
|
0 g
|
||||||
|
252.801 32.002 m 252.801 30.232 251.367 28.798 249.602 28.798 c 247.832
|
||||||
|
28.798 246.398 30.232 246.398 32.002 c 246.398 33.767 247.832 35.201 249.602
|
||||||
|
35.201 c 251.367 35.201 252.801 33.767 252.801 32.002 c h
|
||||||
|
252.801 32.002 m f
|
||||||
|
0.501961 g
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
316.801 19.199 m 316.801 20.969 315.367 22.398 313.602 22.398 c 311.832
|
||||||
|
22.398 310.398 20.969 310.398 19.199 c 310.398 17.434 311.832 16 313.602
|
||||||
|
16 c 315.367 16 316.801 17.434 316.801 19.199 c h
|
||||||
|
316.801 19.199 m S Q
|
||||||
|
278.398 32.002 m 278.398 30.232 276.969 28.798 275.199 28.798 c 273.434
|
||||||
|
28.798 272 30.232 272 32.002 c 272 33.767 273.434 35.201 275.199 35.201
|
||||||
|
c 276.969 35.201 278.398 33.767 278.398 32.002 c h
|
||||||
|
278.398 32.002 m f
|
||||||
|
0 g
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
278.398 6.398 m 278.398 8.168 276.969 9.602 275.199 9.602 c 273.434 9.602
|
||||||
|
272 8.168 272 6.398 c 272 4.633 273.434 3.199 275.199 3.199 c 276.969 3.199
|
||||||
|
278.398 4.633 278.398 6.398 c h
|
||||||
|
278.398 6.398 m S Q
|
||||||
|
0.501961 g
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
291.199 6.398 m 291.199 8.168 289.766 9.602 288 9.602 c 286.234 9.602 284.801
|
||||||
|
8.168 284.801 6.398 c 284.801 4.633 286.234 3.199 288 3.199 c 289.766 3.199
|
||||||
|
291.199 4.633 291.199 6.398 c h
|
||||||
|
291.199 6.398 m S Q
|
||||||
|
0 g
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
262.398 19.199 m 243.199 19.199 l S Q
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
262.398 19.199 m 262.398 3.199 l S Q
|
||||||
|
0 0 0.752941 rg
|
||||||
|
q 1 0 0 -1 0 38.400002 cm
|
||||||
|
262.398 19.199 m 275.199 6.398 l S Q
|
||||||
|
Q Q
|
||||||
|
showpage
|
||||||
|
%%Trailer
|
||||||
|
end restore
|
||||||
|
%%EOF
|
||||||
834
tex/gfx/door_pca.svg
Normal file
834
tex/gfx/door_pca.svg
Normal file
@@ -0,0 +1,834 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||||
|
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
width="448"
|
||||||
|
height="48"
|
||||||
|
viewBox="0 0 448 48"
|
||||||
|
id="svg2"
|
||||||
|
version="1.1"
|
||||||
|
inkscape:version="0.91 r13725"
|
||||||
|
sodipodi:docname="door_pca.svg">
|
||||||
|
<defs
|
||||||
|
id="defs4">
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Send"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker5095"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path5097"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 0,0 Z"
|
||||||
|
style="fill:#008000;fill-opacity:1;fill-rule:evenodd;stroke:#008000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(-0.2,0,0,-0.2,-1.2,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Send"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker4815"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path4817"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 0,0 Z"
|
||||||
|
style="fill:#008000;fill-opacity:1;fill-rule:evenodd;stroke:#008000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(-0.2,0,0,-0.2,-1.2,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Send"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="Arrow1Send"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path4452"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 0,0 Z"
|
||||||
|
style="fill:#008000;fill-opacity:1;fill-rule:evenodd;stroke:#008000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(-0.2,0,0,-0.2,-1.2,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Mend"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="Arrow1Mend"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path4446"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 0,0 Z"
|
||||||
|
style="fill:#000080;fill-opacity:1;fill-rule:evenodd;stroke:#000080;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(-0.4,0,0,-0.4,-4,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Mstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="Arrow1Mstart"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path4443"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 0,0 Z"
|
||||||
|
style="fill:#000080;fill-opacity:1;fill-rule:evenodd;stroke:#000080;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.4,0,0,0.4,4,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="Arrow1Lstart"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path4437"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 0,0 Z"
|
||||||
|
style="fill:#000080;fill-opacity:1;fill-rule:evenodd;stroke:#000080;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Send"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker5095-6"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path5097-2"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 0,0 Z"
|
||||||
|
style="fill:#008000;fill-opacity:1;fill-rule:evenodd;stroke:#008000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(-0.2,0,0,-0.2,-1.2,0)" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Send"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker4815-7"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path4817-3"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 0,0 Z"
|
||||||
|
style="fill:#008000;fill-opacity:1;fill-rule:evenodd;stroke:#008000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(-0.2,0,0,-0.2,-1.2,0)" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Send"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker5095-62"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path5097-4"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 0,0 Z"
|
||||||
|
style="fill:#008000;fill-opacity:1;fill-rule:evenodd;stroke:#008000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(-0.2,0,0,-0.2,-1.2,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Send"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker4815-3"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path4817-4"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 0,0 Z"
|
||||||
|
style="fill:#008000;fill-opacity:1;fill-rule:evenodd;stroke:#008000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(-0.2,0,0,-0.2,-1.2,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Send"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker5095-7"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path5097-6"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 0,0 Z"
|
||||||
|
style="fill:#008000;fill-opacity:1;fill-rule:evenodd;stroke:#008000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(-0.2,0,0,-0.2,-1.2,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Send"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker4815-1"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path4817-9"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 0,0 Z"
|
||||||
|
style="fill:#008000;fill-opacity:1;fill-rule:evenodd;stroke:#008000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(-0.2,0,0,-0.2,-1.2,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
id="base"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
bordercolor="#666666"
|
||||||
|
borderopacity="1.0"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:zoom="1.979899"
|
||||||
|
inkscape:cx="232.59995"
|
||||||
|
inkscape:cy="65.182272"
|
||||||
|
inkscape:document-units="px"
|
||||||
|
inkscape:current-layer="layer4"
|
||||||
|
showgrid="true"
|
||||||
|
units="px"
|
||||||
|
inkscape:window-width="1600"
|
||||||
|
inkscape:window-height="845"
|
||||||
|
inkscape:window-x="0"
|
||||||
|
inkscape:window-y="0"
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:object-nodes="true"
|
||||||
|
inkscape:snap-intersection-paths="true"
|
||||||
|
inkscape:snap-smooth-nodes="false"
|
||||||
|
inkscape:snap-object-midpoints="true">
|
||||||
|
<inkscape:grid
|
||||||
|
type="xygrid"
|
||||||
|
id="grid4136"
|
||||||
|
empspacing="8" />
|
||||||
|
</sodipodi:namedview>
|
||||||
|
<metadata
|
||||||
|
id="metadata7">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
id="layer5"
|
||||||
|
inkscape:label="ellipse2"
|
||||||
|
transform="translate(0,-132)">
|
||||||
|
<ellipse
|
||||||
|
style="fill:#ff8080;fill-opacity:1;stroke:#000000;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:1, 1;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
id="path4385-3"
|
||||||
|
cx="328"
|
||||||
|
cy="156"
|
||||||
|
rx="24"
|
||||||
|
ry="20" />
|
||||||
|
<ellipse
|
||||||
|
style="fill:#80ff80;fill-opacity:1;stroke:#000000;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:1, 1;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
id="path4385"
|
||||||
|
cx="80"
|
||||||
|
cy="156"
|
||||||
|
rx="64"
|
||||||
|
ry="8" />
|
||||||
|
<ellipse
|
||||||
|
style="fill:#ff8080;fill-opacity:1;stroke:#000000;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:1, 1;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
id="path4385-7"
|
||||||
|
cx="240"
|
||||||
|
cy="156"
|
||||||
|
rx="56"
|
||||||
|
ry="8" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
inkscape:label="Layer 1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
id="layer1"
|
||||||
|
transform="translate(0,-1004.3623)"
|
||||||
|
style="display:none" />
|
||||||
|
<g
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
id="layer2"
|
||||||
|
inkscape:label="grid"
|
||||||
|
transform="translate(0,-94)"
|
||||||
|
style="display:inline">
|
||||||
|
<circle
|
||||||
|
style="fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6"
|
||||||
|
cx="56"
|
||||||
|
cy="118"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-2"
|
||||||
|
cx="72"
|
||||||
|
cy="118"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#808080;fill-opacity:1;stroke:#000000;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-8"
|
||||||
|
cx="88"
|
||||||
|
cy="102"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-5"
|
||||||
|
cx="104"
|
||||||
|
cy="118"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2"
|
||||||
|
cx="24"
|
||||||
|
cy="134"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7"
|
||||||
|
cx="40"
|
||||||
|
cy="134"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-57-2"
|
||||||
|
cx="56"
|
||||||
|
cy="134"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-6"
|
||||||
|
cx="72"
|
||||||
|
cy="134"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-5"
|
||||||
|
cx="88"
|
||||||
|
cy="134"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-57-23"
|
||||||
|
cx="104"
|
||||||
|
cy="134"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-5"
|
||||||
|
cx="120"
|
||||||
|
cy="134"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-9"
|
||||||
|
cx="136"
|
||||||
|
cy="134"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-4"
|
||||||
|
cx="24"
|
||||||
|
cy="102"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-53"
|
||||||
|
cx="40"
|
||||||
|
cy="102"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-4"
|
||||||
|
cx="8"
|
||||||
|
cy="134"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-57-4-3-4"
|
||||||
|
cx="272"
|
||||||
|
cy="102"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-57-4-2"
|
||||||
|
cx="104"
|
||||||
|
cy="102"
|
||||||
|
r="4" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
id="layer3"
|
||||||
|
inkscape:label="grid_inv"
|
||||||
|
transform="translate(0,-94)"
|
||||||
|
style="display:inline">
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159"
|
||||||
|
cx="8"
|
||||||
|
cy="118"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6"
|
||||||
|
cx="24"
|
||||||
|
cy="118"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-0"
|
||||||
|
cx="40"
|
||||||
|
cy="118"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2"
|
||||||
|
cx="120"
|
||||||
|
cy="118"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-1"
|
||||||
|
cx="136"
|
||||||
|
cy="118"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-57-0"
|
||||||
|
cx="56"
|
||||||
|
cy="102"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-3"
|
||||||
|
cx="72"
|
||||||
|
cy="102"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-57-4"
|
||||||
|
cx="88"
|
||||||
|
cy="118"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-48"
|
||||||
|
cx="120"
|
||||||
|
cy="102"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-1"
|
||||||
|
cx="136"
|
||||||
|
cy="102"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-8"
|
||||||
|
cx="8"
|
||||||
|
cy="102"
|
||||||
|
r="4" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
id="layer4"
|
||||||
|
inkscape:label="ellipse"
|
||||||
|
transform="translate(0,-96)">
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 80,120 0,-8"
|
||||||
|
id="path4387"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 80,120 -64,0"
|
||||||
|
id="path4389"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#0000c0;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 80,120 8,-16"
|
||||||
|
id="path5147"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-4"
|
||||||
|
cx="208"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;fill-opacity:1;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-2-4"
|
||||||
|
cx="224"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-5-9"
|
||||||
|
cx="256"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-8"
|
||||||
|
cx="176"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-7"
|
||||||
|
cx="192"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-57-2-5"
|
||||||
|
cx="208"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-6-0"
|
||||||
|
cx="224"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-5-0"
|
||||||
|
cx="240"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-57-23-8"
|
||||||
|
cx="256"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-5-5"
|
||||||
|
cx="272"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-9-9"
|
||||||
|
cx="288"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-4-7"
|
||||||
|
cx="176"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-53-2"
|
||||||
|
cx="192"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-4-9"
|
||||||
|
cx="160"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-1"
|
||||||
|
cx="160"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-5"
|
||||||
|
cx="176"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-0-9"
|
||||||
|
cx="192"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-0"
|
||||||
|
cx="272"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-1-2"
|
||||||
|
cx="288"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-57-0-5"
|
||||||
|
cx="208"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-3-4"
|
||||||
|
cx="224"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-99-8"
|
||||||
|
cx="240"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-57-4-3"
|
||||||
|
cx="256"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-8-8"
|
||||||
|
cx="160"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-5-9-6"
|
||||||
|
cx="240"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:#808080;fill-opacity:1;stroke:#000000;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-8-7"
|
||||||
|
cx="288"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m 240,120 0,-8"
|
||||||
|
id="path4387-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m 240,120 -56,0"
|
||||||
|
id="path4389-2"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#0000c0;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 240,120 48,-16"
|
||||||
|
id="path5371"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-41"
|
||||||
|
cx="360"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;fill-opacity:1;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-2-9"
|
||||||
|
cx="376"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-5-0"
|
||||||
|
cx="408"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-1"
|
||||||
|
cx="328"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-52"
|
||||||
|
cx="344"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-57-2-8"
|
||||||
|
cx="360"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-6-6"
|
||||||
|
cx="376"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-5-4"
|
||||||
|
cx="392"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-57-23-2"
|
||||||
|
cx="408"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-5-1"
|
||||||
|
cx="424"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-9-8"
|
||||||
|
cx="440"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-4-2"
|
||||||
|
cx="328"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-4-5"
|
||||||
|
cx="312"
|
||||||
|
cy="136"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-0"
|
||||||
|
cx="312"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-4"
|
||||||
|
cx="328"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-0-1"
|
||||||
|
cx="344"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-54"
|
||||||
|
cx="424"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-1-9"
|
||||||
|
cx="440"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-3-8"
|
||||||
|
cx="376"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-99-6"
|
||||||
|
cx="392"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-57-4-9"
|
||||||
|
cx="408"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-2-48-0"
|
||||||
|
cx="424"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-1-3"
|
||||||
|
cx="440"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:2;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-8-5"
|
||||||
|
cx="312"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-7-5-4-5"
|
||||||
|
cx="392"
|
||||||
|
cy="120"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:#808080;fill-opacity:1;stroke:#000000;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-8-8"
|
||||||
|
cx="344"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:none;stroke:#808080;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path4159-6-2-6-41-0"
|
||||||
|
cx="360"
|
||||||
|
cy="104"
|
||||||
|
r="4" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 328,120 -24,0"
|
||||||
|
id="path4389-7"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;fill-rule:evenodd;stroke:#000000;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 328,120 0,-20"
|
||||||
|
id="path4387-5"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-rule:evenodd;stroke:#0000c0;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m 328,120 16,-16"
|
||||||
|
id="path6160"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
</svg>
|
||||||
|
After Width: | Height: | Size: 29 KiB |
31164
tex/gfx/floorplan_dijkstra_heatmap.eps
Normal file
31164
tex/gfx/floorplan_dijkstra_heatmap.eps
Normal file
File diff suppressed because it is too large
Load Diff
34863
tex/gfx/floorplan_importance.eps
Normal file
34863
tex/gfx/floorplan_importance.eps
Normal file
File diff suppressed because it is too large
Load Diff
296
tex/gfx/floorplan_paths.eps
Normal file
296
tex/gfx/floorplan_paths.eps
Normal file
@@ -0,0 +1,296 @@
|
|||||||
|
%!PS-Adobe-3.0 EPSF-3.0
|
||||||
|
%%Creator: cairo 1.14.4 (http://cairographics.org)
|
||||||
|
%%CreationDate: Wed Feb 3 21:08:47 2016
|
||||||
|
%%Pages: 1
|
||||||
|
%%DocumentData: Clean7Bit
|
||||||
|
%%LanguageLevel: 2
|
||||||
|
%%BoundingBox: 0 0 144 288
|
||||||
|
%%EndComments
|
||||||
|
%%BeginProlog
|
||||||
|
save
|
||||||
|
50 dict begin
|
||||||
|
/q { gsave } bind def
|
||||||
|
/Q { grestore } bind def
|
||||||
|
/cm { 6 array astore concat } bind def
|
||||||
|
/w { setlinewidth } bind def
|
||||||
|
/J { setlinecap } bind def
|
||||||
|
/j { setlinejoin } bind def
|
||||||
|
/M { setmiterlimit } bind def
|
||||||
|
/d { setdash } bind def
|
||||||
|
/m { moveto } bind def
|
||||||
|
/l { lineto } bind def
|
||||||
|
/c { curveto } bind def
|
||||||
|
/h { closepath } bind def
|
||||||
|
/re { exch dup neg 3 1 roll 5 3 roll moveto 0 rlineto
|
||||||
|
0 exch rlineto 0 rlineto closepath } bind def
|
||||||
|
/S { stroke } bind def
|
||||||
|
/f { fill } bind def
|
||||||
|
/f* { eofill } bind def
|
||||||
|
/n { newpath } bind def
|
||||||
|
/W { clip } bind def
|
||||||
|
/W* { eoclip } bind def
|
||||||
|
/BT { } bind def
|
||||||
|
/ET { } bind def
|
||||||
|
/pdfmark where { pop globaldict /?pdfmark /exec load put }
|
||||||
|
{ globaldict begin /?pdfmark /pop load def /pdfmark
|
||||||
|
/cleartomark load def end } ifelse
|
||||||
|
/BDC { mark 3 1 roll /BDC pdfmark } bind def
|
||||||
|
/EMC { mark /EMC pdfmark } bind def
|
||||||
|
/cairo_store_point { /cairo_point_y exch def /cairo_point_x exch def } def
|
||||||
|
/Tj { show currentpoint cairo_store_point } bind def
|
||||||
|
/TJ {
|
||||||
|
{
|
||||||
|
dup
|
||||||
|
type /stringtype eq
|
||||||
|
{ show } { -0.001 mul 0 cairo_font_matrix dtransform rmoveto } ifelse
|
||||||
|
} forall
|
||||||
|
currentpoint cairo_store_point
|
||||||
|
} bind def
|
||||||
|
/cairo_selectfont { cairo_font_matrix aload pop pop pop 0 0 6 array astore
|
||||||
|
cairo_font exch selectfont cairo_point_x cairo_point_y moveto } bind def
|
||||||
|
/Tf { pop /cairo_font exch def /cairo_font_matrix where
|
||||||
|
{ pop cairo_selectfont } if } bind def
|
||||||
|
/Td { matrix translate cairo_font_matrix matrix concatmatrix dup
|
||||||
|
/cairo_font_matrix exch def dup 4 get exch 5 get cairo_store_point
|
||||||
|
/cairo_font where { pop cairo_selectfont } if } bind def
|
||||||
|
/Tm { 2 copy 8 2 roll 6 array astore /cairo_font_matrix exch def
|
||||||
|
cairo_store_point /cairo_font where { pop cairo_selectfont } if } bind def
|
||||||
|
/g { setgray } bind def
|
||||||
|
/rg { setrgbcolor } bind def
|
||||||
|
/d1 { setcachedevice } bind def
|
||||||
|
%%EndProlog
|
||||||
|
%%BeginSetup
|
||||||
|
%%BeginResource: font Roboto-Regular
|
||||||
|
11 dict begin
|
||||||
|
/FontType 42 def
|
||||||
|
/FontName /Roboto-Regular def
|
||||||
|
/PaintType 0 def
|
||||||
|
/FontMatrix [ 1 0 0 1 0 0 ] def
|
||||||
|
/FontBBox [ 0 0 0 0 ] def
|
||||||
|
/Encoding 256 array def
|
||||||
|
0 1 255 { Encoding exch /.notdef put } for
|
||||||
|
Encoding 32 /space put
|
||||||
|
/CharStrings 2 dict dup begin
|
||||||
|
/.notdef 0 def
|
||||||
|
/space 1 def
|
||||||
|
end readonly def
|
||||||
|
/sfnts [
|
||||||
|
<000100000009008000030010637674202ba8079d00000160000000546670676d77f860ab0000
|
||||||
|
01b4000001bc676c79666fe1fe490000009c000000c468656164ff512fc30000037000000036
|
||||||
|
686865610bda0465000003a800000024686d747805870064000003cc000000086c6f63610000
|
||||||
|
0188000003d40000000c6d6178700234034f000003e00000002070726570a266fac900000400
|
||||||
|
00000149000500640000032805b0000300060009000c000f0071b20c1011111239b00c10b000
|
||||||
|
d0b00c10b006d0b00c10b009d0b00c10b00dd000b0004558b0022f1bb1021e3e59b0004558b0
|
||||||
|
002f1bb100123e59b2040200111239b2050200111239b2070200111239b2080200111239b10a
|
||||||
|
0cf4b20c0200111239b20d0200111239b00210b10e0cf4303121211121031101011101032101
|
||||||
|
3501210328fd3c02c436feeefeba010ce40203fefe0102fdfd05b0faa40507fd7d0277fb1102
|
||||||
|
78fd5e025e88025e0000002a009d0080008a007800d40064004e005a0087006000560034023c
|
||||||
|
00bc00b2008e00c400000014fe600014029b00200321000b043a0014048d001005b000140618
|
||||||
|
001501a6001106c0000e06d9000600000000b0002c4bb0095058b101018e59b801ff85b0841d
|
||||||
|
b109035f5e2db0012c2020456944b001602db0022cb0012a212db0032c2046b0032546525823
|
||||||
|
59208a208a49648a204620686164b004254620686164525823658a592f20b00053586920b000
|
||||||
|
545821b040591b6920b000545821b0406559593a2db0042c2046b00425465258238a59204620
|
||||||
|
6a6164b0042546206a61645258238a592ffd2db0052c4b20b0032650585158b080441bb04044
|
||||||
|
591b21212045b0c05058b0c0441b2159592db0062c2020456944b001602020457d691844b001
|
||||||
|
602db0072cb0062a2db0082c4b20b003265358b0401bb000598a8a20b0032653582321b0808a
|
||||||
|
8a1b8a235920b0032653582321b0c08a8a1b8a235920b0032653582321b801008a8a1b8a2359
|
||||||
|
20b0032653582321b801408a8a1b8a235920b003265358b0032545b8018050582321b8018023
|
||||||
|
211bb003254523212321591b2159442db0092c4b535845441b2121592db00a2cb028452db00b
|
||||||
|
2cb029452db00c2cb1270188208a5358b94000040063b80800885458b9002803e870591bb023
|
||||||
|
5358b02088b810005458b9002803e8705959592db00d2cb04088b820005a58b12900441bb900
|
||||||
|
2903e844592d00010000000200006b32894c5f0f3cf50019080000000000c4f0112e00000000
|
||||||
|
d1f7d34ef8dffdd5105c0873000000090002000100000000000100000862fdd500000a96f8df
|
||||||
|
fbf70a96000100000000000000000000000000000002038c006401fb000000000000000000c4
|
||||||
|
000000c400010000000200d5001600540007000100000000000e00000200022400060001b00c
|
||||||
|
2bb0002b00b20110022b01b21101022b01b7113a30251b1000082b00b701483b2e211400082b
|
||||||
|
b702584838281400082bb703524334251600082bb7045e4d3c2b1900082bb705362c22190f00
|
||||||
|
082bb706715d46321b00082bb70791775c3a2300082bb7087e6750391a00082bb70954453626
|
||||||
|
1400082bb70a76604b361d00082bb70b83644e3a2300082bb70cd9b28a633c00082bb70d1410
|
||||||
|
0c090600082bb70e3c32271c1100082bb70f4034291d1400082bb71050412e211400082b00b2
|
||||||
|
120b072bb00020457d691844b23f1a0173b25f1a0173b27f1a0173b22f1a0174b24f1a0174b2
|
||||||
|
6f1a0174b28f1a0174b2af1a0174b2ff1a0174b21f1a0175b23f1a0175b25f1a0175b27f1a01
|
||||||
|
75b20f1e0173b27f1e0173b2ef1e0173b21f1e0174b25f1e0174b28f1e0174b2cf1e0174b2ff
|
||||||
|
1e0174b23f1e0175b26f1e0175b22f200173b26f20017300000000>
|
||||||
|
] def
|
||||||
|
/f-0-0 currentdict end definefont pop
|
||||||
|
%%EndResource
|
||||||
|
%%EndSetup
|
||||||
|
%%Page: 1 1
|
||||||
|
%%BeginPageSetup
|
||||||
|
%%PageBoundingBox: 0 0 144 288
|
||||||
|
%%EndPageSetup
|
||||||
|
q 13 6 111 271 rectclip q
|
||||||
|
0 g
|
||||||
|
BT
|
||||||
|
8 0 0 8 13.996094 17.042969 Tm
|
||||||
|
/f-0-0 1 Tf
|
||||||
|
( )Tj
|
||||||
|
0 6.318848 Td
|
||||||
|
( )Tj
|
||||||
|
0 6.318359 Td
|
||||||
|
( )Tj
|
||||||
|
0 6.325195 Td
|
||||||
|
( )Tj
|
||||||
|
0 6.318848 Td
|
||||||
|
( )Tj
|
||||||
|
0 6.318848 Td
|
||||||
|
( )Tj
|
||||||
|
0.686035 -32.918945 Td
|
||||||
|
[( )-2915( )-2909( )-2915( )]TJ
|
||||||
|
12.643555 0 Td
|
||||||
|
( )Tj
|
||||||
|
ET
|
||||||
|
0.25 w
|
||||||
|
0 J
|
||||||
|
0 j
|
||||||
|
[] 0.0 d
|
||||||
|
3.8 M q 1 0 0 -1 0 288 cm
|
||||||
|
21.051 12.102 m 21.051 266.852 l 66.602 266.852 l 66.602 243.551 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
66.602 237.5 m 66.602 233.449 l 21.051 233.449 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
66.602 233.449 m 66.602 227.898 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
66.602 222.852 m 66.602 205.199 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
66.602 137.398 m 66.602 71.148 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
66.602 66.102 m 66.602 50.449 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
77.699 137.398 m 42.602 137.398 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
35.199 137.398 m 21.051 137.398 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
66.602 50.5 m 21.051 50.5 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
68.852 42.352 m 35.25 42.352 l 35.25 23.648 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
68.852 12.949 m 68.852 42.352 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
35.25 18.102 m 35.25 12 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
66.602 266.852 m 107.551 266.852 l 107.551 107.449 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
76 205.199 m 97.398 205.199 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
77.699 215 m 107.551 215 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
77.699 239 m 107.551 239 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
77.699 215 m 77.699 258.25 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
77.699 205.199 m 77.699 175.648 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
76.699 42.352 m 84.301 42.352 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
90.852 42.352 m 96.398 42.352 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
78.199 30.699 m 78.199 42.352 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
78.199 30.699 m 103 30.699 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
90.852 42.352 m 90.852 30.699 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
103 12 m 103 42.352 l 122.949 42.352 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
77.699 59.801 m 77.699 137.398 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
119.102 59.801 m 122.949 59.801 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
92.398 21.602 m 77.699 21.602 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
56.301 191.051 m 77.699 191.051 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
80.75 30.699 m 80.75 12 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
21.051 12.102 m 123.102 12.102 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
86 107.449 m 123.102 107.449 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
122.949 12.102 m 122.949 107.449 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
66.602 185.898 m 66.602 165.949 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
21.051 146.551 m 47.148 146.551 l 55.75 149.949 l 63.148 157.352 l 66.602
|
||||||
|
165.949 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
77.699 59.801 m 112.852 59.801 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
77.699 205.199 m 66.602 205.199 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
77.699 177.352 m 96.852 177.352 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
56.301 191.051 m 66.602 205.199 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
77.699 167.102 m 96.852 167.102 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
77.699 137.398 m 80.852 137.398 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
85.398 137.398 m 107.551 137.398 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
77.699 168.801 m 77.699 146.551 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
102.551 177.352 m 107.551 177.352 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
102.551 167.102 m 107.551 167.102 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
77.699 107.449 m 80.852 107.449 l S Q
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
103.102 205.199 m 107.551 205.199 l S Q
|
||||||
|
0.266667 g
|
||||||
|
0.5 w
|
||||||
|
[ 0.5 2 0.5 2 0.5 2 0.5 2] 0 d
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
66 34.852 m 65 33.801 l 63 31.801 l 61.949 30.801 l 60.949 29.75 l 58.949
|
||||||
|
27.75 l 57.898 26.75 l 56.898 25.75 l 55.898 24.699 l 53.898 22.699 l 35.648
|
||||||
|
22.699 l 34.648 23.699 l 34.648 41.898 l 39.699 46.949 l 40.75 47.949 l
|
||||||
|
41.75 49 l 67.051 49 l 68.051 50 l 68.051 66.199 l 67.051 67.199 l 66 68.199
|
||||||
|
l 64 70.199 l 63 71.25 l 61.949 72.25 l 59.949 74.25 l 58.949 75.301 l
|
||||||
|
57.898 76.301 l 54.898 79.301 l 53.898 80.352 l 52.852 81.352 l 50.852 83.352
|
||||||
|
l 49.852 84.398 l 48.801 85.398 l 41.75 92.449 l 41.75 136.949 l 42.75
|
||||||
|
137.949 l 43.75 139 l 44.75 140 l 45.801 141 l 46.801 142 l 47.801 143.051
|
||||||
|
l 48.801 144.051 l 49.852 145.051 l 51.852 147.051 l 52.852 147.051 l 53.898
|
||||||
|
148.102 l 54.898 148.102 l 57.898 151.102 l 58.949 152.148 l 61.949 155.148
|
||||||
|
l 63 156.148 l 64 157.199 l 66 159.199 l 67.051 160.199 l 68.051 161.25
|
||||||
|
l 68.051 185.5 l 67.051 186.5 l 66 186.5 l 65 187.5 l 64 188.551 l 63 189.551
|
||||||
|
l 55.898 189.551 l 54.898 190.551 l 54.898 192.551 l 55.898 193.602 l 57.898
|
||||||
|
195.602 l 57.898 196.602 l 58.949 197.648 l 59.949 198.648 l 59.949 200.648
|
||||||
|
l 60.949 201.648 l 61.949 202.699 l 63 203.699 l 63 204.699 l 64 205.699
|
||||||
|
l 65 206.75 l 65 213.801 l 66 214.801 l 66 222.898 l 67.051 223.898 l 68.051
|
||||||
|
224.949 l 75.102 232 l 75.102 255.25 l 76.148 256.301 l 76.148 257.301
|
||||||
|
l 78.148 259.301 l 80.148 257.301 l 81.199 256.301 l 82.199 255.25 l 84.199
|
||||||
|
253.25 l 85.25 252.25 l 95.352 252.25 l S Q
|
||||||
|
0 g
|
||||||
|
[] 0.0 d
|
||||||
|
q 1 0 0 -1 0 288 cm
|
||||||
|
66 34.852 m 61.949 34.852 l 60.949 33.801 l 58.949 31.801 l 54.898 31.801
|
||||||
|
l 53.898 30.801 l 52.852 29.75 l 49.852 26.75 l 48.801 25.75 l 47.801 24.699
|
||||||
|
l 45.801 22.699 l 44.75 21.699 l 41.75 21.699 l 40.75 20.648 l 34.648 20.648
|
||||||
|
l 33.648 21.699 l 31.648 23.699 l 30.602 24.699 l 30.602 41.898 l 31.648
|
||||||
|
42.898 l 32.648 43.949 l 34.648 45.949 l 68.051 45.949 l 70.051 47.949
|
||||||
|
l 71.051 49 l 72.102 50 l 72.102 64.148 l 71.051 65.148 l 70.051 66.199
|
||||||
|
l 67.051 69.199 l 66 69.199 l 65 70.199 l 64 71.25 l 63 72.25 l 61.949 73.25
|
||||||
|
l 60.949 74.25 l 59.949 75.301 l 58.949 76.301 l 57.898 77.301 l 56.898
|
||||||
|
78.301 l 56.898 84.398 l 53.898 87.398 l 52.852 88.398 l 51.852 89.449
|
||||||
|
l 49.852 91.449 l 48.801 92.449 l 47.801 93.5 l 47.801 116.75 l 46.801 117.75
|
||||||
|
l 46.801 119.75 l 45.801 120.801 l 45.801 124.801 l 42.75 127.852 l 42.75
|
||||||
|
129.898 l 40.75 131.898 l 39.699 132.898 l 39.699 137.949 l 42.75 141 l
|
||||||
|
44.75 141 l 45.801 142 l 51.852 142 l 52.852 143.051 l 55.898 143.051 l
|
||||||
|
57.898 145.051 l 58.949 146.051 l 59.949 147.051 l 60.949 148.102 l 61.949
|
||||||
|
149.102 l 63 150.102 l 64 151.102 l 65 152.148 l 66 153.148 l 67.051 154.148
|
||||||
|
l 69.051 156.148 l 70.051 157.199 l 70.051 158.199 l 71.051 159.199 l 71.051
|
||||||
|
162.25 l 72.102 163.25 l 72.102 182.449 l 71.051 183.449 l 70.051 184.5
|
||||||
|
l 68.051 186.5 l 54.898 186.5 l 53.898 187.5 l 52.852 188.551 l 51.852
|
||||||
|
189.551 l 51.852 203.699 l 52.852 204.699 l 53.898 205.699 l 53.898 206.75
|
||||||
|
l 55.898 208.75 l 55.898 209.75 l 56.898 210.75 l 56.898 215.852 l 57.898
|
||||||
|
216.852 l 58.949 217.852 l 60.949 219.852 l 61.949 220.898 l 63 221.898
|
||||||
|
l 65 223.898 l 66 224.949 l 67.051 225.949 l 68.051 225.949 l 70.051 227.949
|
||||||
|
l 71.051 229 l 72.102 230 l 72.102 251.199 l 73.102 252.25 l 73.102 258.301
|
||||||
|
l 75.102 260.301 l 76.148 261.352 l 77.148 262.352 l 86.25 262.352 l 87.25
|
||||||
|
261.352 l 88.25 260.301 l 89.301 259.301 l 92.301 256.301 l 93.301 255.25
|
||||||
|
l 94.352 254.25 l 95.352 253.25 l S Q
|
||||||
|
Q Q
|
||||||
|
showpage
|
||||||
|
%%Trailer
|
||||||
|
end restore
|
||||||
|
%%EOF
|
||||||
10
tex/make.sh
Normal file
10
tex/make.sh
Normal file
@@ -0,0 +1,10 @@
|
|||||||
|
PATH=$PATH:/mnt/data/texlive/bin/x86_64-linux/
|
||||||
|
|
||||||
|
latex bare_conf.tex
|
||||||
|
latex bare_conf.tex
|
||||||
|
|
||||||
|
dvips bare_conf.dvi
|
||||||
|
|
||||||
|
ps2pdf14 bare_conf.ps
|
||||||
|
|
||||||
|
atril bare_conf.pdf
|
||||||
10
tex/notes_frank.txt
Normal file
10
tex/notes_frank.txt
Normal file
@@ -0,0 +1,10 @@
|
|||||||
|
|
||||||
|
|
||||||
|
dijkstra-walk
|
||||||
|
(without importance the 2nd path becomes more unlikely)
|
||||||
|
heat-map shows more sticking to walls
|
||||||
|
heat-map shows issues of sticking to doors (particles running against walls)
|
||||||
|
allowed variance can be configured
|
||||||
|
heading can also be given as control-data + variance
|
||||||
|
|
||||||
|
l2.5 norm to prevent too many diagonals
|
||||||
Reference in New Issue
Block a user