diff --git a/.gitignore b/.gitignore
index d4c3a57e..55e62e88 100644
--- a/.gitignore
+++ b/.gitignore
@@ -14,3 +14,4 @@
.cxx
local.properties
/.idea/
+secrets.properties
diff --git a/README.md b/README.md
index c4a9f02d..310eaf23 100644
--- a/README.md
+++ b/README.md
@@ -1,45 +1,32 @@
-**PositionMe** is an indoor positioning data collection application initially developed for the University of Edinburgh's Embedded Wireless course. The application now includes enhanced features, including **trajectory playback**, improved UI design, and comprehensive location tracking.
-
-## Features
-
-- **Real-time Sensor Data Collection**: Captures sensor, location, and GNSS data.
-- **Trajectory Playback**: Simulates recorded movement from previously saved trajectory files (Trajectory proto files).
-- **Interactive Map Display**:
- - Visualizes the user's **PDR trajectory/path**.
- - Displays **received GNSS locations**.
- - Supports **floor changes and indoor maps** for a seamless experience.
-- **Playback Controls**:
- - **Play/Pause, Exit, Restart, Jump to End**.
- - **Progress bar for tracking playback status**.
-- **Redesigned UI**: Modern and user-friendly interface for enhanced usability.
+# PositionMe
+Indoor poistioning data collection application created for the University of Edinburgh's Embedded Wireless course.
## Requirements
-- **Android Studio 4.2** or later
-- **Android SDK 30** or later
+- Android Studio 4.2 or later
+- Android SDK 30 or later
## Installation
-1. **Clone the repository.**
-2. **Open the project in Android Studio**.
+1. Clone the repository.
+2. Open the project in Android Studio.
3. Add your own API key for Google Maps in AndroidManifest.xml
-4. Set the website where you want to send your data. The application was built for use with [openpositioning.org](http://openpositioning.org/).
-5. **Build and run the project on your Android device**.
+4. Set the website where you want to send your data. The application was built for use with openpositioning.org.
+5. Build and run the project on your device.
## Usage
-1. **Install the application** using Android Studio.
-2. **Launch the application** on your Android device.
-3. **Grant necessary permissions** when prompted:
- - Sensor access
- - Location services
- - Internet connectivity
-4. **Collect real-time positioning data**:
- - Follow on-screen instructions to record sensor data.
-5. **Replay previously recorded trajectories**:
- - Navigate to the **Files** section.
- - Select a saved trajectory and press **Play**.
- - The recorded trajectory will be simulated and displayed on the map.
-6. **Control playback**:
- - Pause, restart, or jump to the end using playback controls.
+1. Install the application on a compatible device using Android Studio.
+2. Launch the application on your device.
+3. Allow sensor, location and internet permissions when asked.
+4. Follow the instructions on the screen to start collecting sensor data.
+
+## Creators
+
+### Original contributors ([CloudWalk](https://github.com/openpositioning/DataCollectionTeam6))
+- Virginia Cangelosi (virginia-cangelosi)
+- Michal Dvorak (dvoramicha)
+- Mate Stodulka (stodimp)
+### New contributors
+- Francisco Zampella (fzampella-huawei)
diff --git a/app/build.gradle b/app/build.gradle
index 3e29b13f..6a77e413 100644
--- a/app/build.gradle
+++ b/app/build.gradle
@@ -5,7 +5,6 @@ plugins {
id 'com.google.android.libraries.mapsplatform.secrets-gradle-plugin'
}
-// (Optional) load local secrets file:
def localProperties = new Properties()
def localPropertiesFile = rootProject.file('secrets.properties')
if (localPropertiesFile.exists()) {
@@ -13,33 +12,27 @@ if (localPropertiesFile.exists()) {
}
android {
- namespace "com.openpositioning.PositionMe"
- compileSdk 34
+ namespace ="com.openpositioning.PositionMe" //fix Namespace not specified problem
+ compileSdk 33
defaultConfig {
applicationId "com.openpositioning.PositionMe"
minSdk 28
- targetSdk 34
+ targetSdk 33
versionCode 1
versionName "1.0"
testInstrumentationRunner "androidx.test.runner.AndroidJUnitRunner"
-
- // Example of referencing secrets (if you use secrets.properties):
buildConfigField "String", "MAPS_API_KEY",
"\"${localProperties['MAPS_API_KEY'] ?: ''}\""
+
buildConfigField "String", "OPENPOSITIONING_API_KEY",
"\"${localProperties['OPENPOSITIONING_API_KEY'] ?: ''}\""
+
buildConfigField "String", "OPENPOSITIONING_MASTER_KEY",
"\"${localProperties['OPENPOSITIONING_MASTER_KEY'] ?: ''}\""
}
- buildFeatures {
- // For example:
- // compose true // if you want Jetpack Compose
- // viewBinding true
- }
-
buildFeatures {
buildConfig true
}
@@ -48,48 +41,52 @@ android {
release {
minifyEnabled false
proguardFiles getDefaultProguardFile('proguard-android-optimize.txt'), 'proguard-rules.pro'
+
+
}
- }
+
+ }
compileOptions {
- sourceCompatibility JavaVersion.VERSION_17
- targetCompatibility JavaVersion.VERSION_17
+ sourceCompatibility JavaVersion.VERSION_1_8
+ targetCompatibility JavaVersion.VERSION_1_8
}
}
dependencies {
- // Core AndroidX
- implementation 'androidx.appcompat:appcompat:1.7.0-alpha03' // or stable: 1.6.1
- implementation 'androidx.core:core-ktx:1.12.0'
- implementation 'androidx.constraintlayout:constraintlayout:2.2.0'
- implementation 'androidx.preference:preference:1.2.1'
+
+ implementation 'androidx.appcompat:appcompat:1.4.1'
+ implementation 'com.google.android.material:material:1.6.0'
+ implementation 'androidx.constraintlayout:constraintlayout:2.1.4'
+ implementation 'androidx.preference:preference:1.2.0'
implementation 'androidx.legacy:legacy-support-v4:1.0.0'
implementation 'com.android.volley:volley:1.2.1'
- implementation 'androidx.gridlayout:gridlayout:1.0.0'
-
- // Material Components (Material 3 support is in 1.12.0+)
- testImplementation 'junit:junit:4.13.2'
- androidTestImplementation 'androidx.test.ext:junit:1.2.1'
- androidTestImplementation 'androidx.test.espresso:espresso-core:3.6.1'
- implementation 'com.google.android.material:material:1.12.0'
-
+ testImplementation 'junit:junit:4.+'
+ androidTestImplementation 'androidx.test.ext:junit:1.1.5'
+ androidTestImplementation 'androidx.test.espresso:espresso-core:3.5.1'
implementation 'com.google.protobuf:protobuf-java:3.0.0'
implementation 'com.squareup.okhttp3:okhttp:4.10.0'
implementation "com.google.protobuf:protobuf-java-util:3.0.0"
implementation "com.google.guava:listenablefuture:9999.0-empty-to-avoid-conflict-with-guava"
- implementation 'com.google.android.gms:play-services-maps:19.0.0'
-
+ implementation 'com.google.android.gms:play-services-maps:18.1.0'
// Navigation components
- def nav_version = "2.8.6"
+ def nav_version = "2.5.3"
implementation "androidx.navigation:navigation-fragment-ktx:$nav_version"
implementation "androidx.navigation:navigation-ui-ktx:$nav_version"
-
- // Optional: Jetpack Compose (Material 3)
- // implementation "androidx.compose.material3:material3:1.3.1"
- // implementation "androidx.activity:activity-compose:1.7.2"
-
- // Testing
- testImplementation 'junit:junit:4.13.2'
- androidTestImplementation 'androidx.test.ext:junit:1.2.1'
- androidTestImplementation 'androidx.test.espresso:espresso-core:3.5.1'
+ implementation 'org.ejml:ejml-all:0.43'
}
+
+//secrets {
+// // Optionally specify a different file name containing your secrets.
+// // The plugin defaults to "local.properties"
+// propertiesFileName = "secrets.properties"
+//
+// // A properties file containing default secret values. This file can be
+// // checked in version control.
+// defaultPropertiesFileName = "local.defaults.properties"
+//
+// // Configure which keys should be ignored by the plugin by providing regular expressions.
+// // "sdk.dir" is ignored by default.
+// ignoreList.add("keyToIgnore") // Ignore the key "keyToIgnore"
+// ignoreList.add("sdk.*") // Ignore all keys matching the regexp "sdk.*"
+//}
diff --git a/app/src/main/AndroidManifest.xml b/app/src/main/AndroidManifest.xml
index 678711fd..f89ffb5f 100644
--- a/app/src/main/AndroidManifest.xml
+++ b/app/src/main/AndroidManifest.xml
@@ -2,67 +2,24 @@
-
-
-
-
-
+
-
-
+
-
-
+
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+ android:theme="@style/Theme.Cloud">
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/app/src/main/java/com/openpositioning/PositionMe/BuildingPolygon.java b/app/src/main/java/com/openpositioning/PositionMe/BuildingPolygon.java
new file mode 100644
index 00000000..0e5939bf
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/BuildingPolygon.java
@@ -0,0 +1,130 @@
+package com.openpositioning.PositionMe;
+
+
+import com.google.android.gms.maps.model.LatLng;
+
+import java.util.ArrayList;
+import java.util.List;
+
+/**
+ * Class used to check for a pre-defined set of coordinates if it is in a Building (Nucleus, Library)
+ * (Can be used to add more buildings by adding the coordinates of the buildings and adding methods)
+ * @see IndoorMapManager Used by the the IndoorFloorManager class
+ * @author Arun Gopalakrishnan
+ */
+public class BuildingPolygon {
+ // Defining the coordinates of the building boundaries (rectangular boundaries based on floor map shape)
+ // North-East and South-West Coordinates for the Nucleus Building
+ public static final LatLng NUCLEUS_NE=new LatLng(55.92332001571212, -3.1738768212979593);
+ public static final LatLng NUCLEUS_SW=new LatLng(55.92282257022002, -3.1745956532857647);
+ // North-East and South-West Coordinates for the Kenneth and Murray Library Building
+ public static final LatLng LIBRARY_NE=new LatLng(55.92306692576906, -3.174771893078224);
+ public static final LatLng LIBRARY_SW=new LatLng(55.92281045664704, -3.175184089079065);
+ // Boundary coordinates of the Nucleus building (clockwise)
+
+ public static final List NUCLEUS_POLYGON = new ArrayList() {{
+ add(BuildingPolygon.NUCLEUS_NE);
+ add(new LatLng(BuildingPolygon.NUCLEUS_SW.latitude, BuildingPolygon.NUCLEUS_NE.longitude)); // South-East
+ add(BuildingPolygon.NUCLEUS_SW);
+ add(new LatLng(BuildingPolygon.NUCLEUS_NE.latitude, BuildingPolygon.NUCLEUS_SW.longitude)); // North-West
+ }};
+ //Boundary coordinates of the Library building (clockwise)
+ public static final List LIBRARY_POLYGON = new ArrayList() {{
+ add(BuildingPolygon.LIBRARY_NE);
+ add(new LatLng(BuildingPolygon.LIBRARY_SW.latitude,BuildingPolygon.LIBRARY_NE.longitude));//(South-East)
+ add(BuildingPolygon.LIBRARY_SW);
+ add(new LatLng(BuildingPolygon.LIBRARY_NE.latitude,BuildingPolygon.LIBRARY_SW.longitude));//(North-West)
+ }};
+
+ /**
+ * Function to check if a point is in the Nucleus Building
+ * @param point the point to be checked if inside the building
+ * @return True if point is in Nucleus building else False
+ */
+ public static boolean inNucleus(LatLng point){
+ return (pointInPolygon(point,NUCLEUS_POLYGON));
+
+ }
+ /**
+ * Function to check if a point is in the Library Building
+ * @param point the point which is checked if inside the building
+ * @return True if point is in Library building else False
+ */
+ public static boolean inLibrary(LatLng point){
+ return (pointInPolygon(point,LIBRARY_POLYGON));
+ }
+
+ /**
+ * Function to check if point in polygon (approximates earth to be flat)
+ * Ray casting algorithm https://en.wikipedia.org/wiki/Point_in_polygon
+ * @param point point to be checked if in polygon
+ * @param polygon Boundaries of the building
+ * @return True if point in polygon
+ * False otherwise
+ */
+ private static boolean pointInPolygon(LatLng point, List polygon) {
+ int numCrossings = 0;
+ List path=polygon;
+ // For each edge
+ for (int i=0; i < path.size(); i++) {
+ LatLng a = path.get(i);
+ int j = i + 1;
+ // Last edge (includes first point of Polygon)
+ if (j >= path.size()) {
+ j = 0;
+ }
+ LatLng b = path.get(j);
+ if (crossingSegment(point, a, b)) {
+ numCrossings++;
+ }
+ }
+
+ //if odd number of numCrossings return true (point is in polygon)
+ return (numCrossings % 2 == 1);
+ }
+
+ /**
+ * Ray Casting algorithm for a segment joining ab
+ * @param point the point we check
+ * @param a the line segment's starting point
+ * @param b the line segment's ending point
+ * @return True if the point is
+ * 1) To the left of the segment ab
+ * 2) Not above nor below the segment ab
+ * Otherwise False
+ */
+ private static boolean crossingSegment(LatLng point, LatLng a,LatLng b) {
+ double pointLng = point.longitude,
+ pointLat = point.latitude,
+ aLng = a.longitude,
+ aLat = a.latitude,
+ bLng = b.longitude,
+ bLat = b.latitude;
+ if (aLat > bLat) {
+ aLng = b.longitude;
+ aLat = b.latitude;
+ bLng = a.longitude;
+ bLat = a.latitude;
+ }
+ // Alter longitude to correct for 180 degree crossings
+ if (pointLng < 0 || aLng <0 || bLng <0) { pointLng += 360; aLng+=360; bLng+=360; }
+ // If point has same latitude as a or b, increase slightly pointLat
+ if (pointLat == aLat || pointLat == bLat) pointLat += 0.00000001;
+
+ //If the point is above, below or to the right of the segment,return false
+ if ((pointLat > bLat || pointLat < aLat) || (pointLng > Math.max(aLng, bLng))){
+ return false;
+ }
+ // If the point is not above, below or to the right and is to the left, return true
+ else if (pointLng < Math.min(aLng, bLng)){
+ return true;
+ }
+ // Comparing the slope of segment [a,b] (slope1)
+ // and segment [a,point] (slope2) to check if to the left of segment [a,b] or not
+ else {
+ double slope1 = (aLng != bLng) ? ((bLat - aLat) / (bLng - aLng)) : Double.POSITIVE_INFINITY;
+ double slope2 = (aLng != pointLng) ? ((pointLat - aLat) / (pointLng - aLng)) : Double.POSITIVE_INFINITY;
+ return (slope2 >= slope1);
+ }
+ }
+}
diff --git a/app/src/main/java/com/openpositioning/PositionMe/CircularFloatBuffer.java b/app/src/main/java/com/openpositioning/PositionMe/CircularFloatBuffer.java
new file mode 100644
index 00000000..bbd2804e
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/CircularFloatBuffer.java
@@ -0,0 +1,114 @@
+package com.openpositioning.PositionMe;
+
+import java.util.List;
+import java.util.Optional;
+import java.util.stream.Collectors;
+import java.util.stream.IntStream;
+
+/**
+ * Ring buffer for floats that can constantly update values in a fixed sized array.
+ *
+ * @author Mate Stodulka
+ */
+public class CircularFloatBuffer {
+ // Default capacity for the buffer in case initial capacity is invalid
+ private static final int DEFAULT_CAPACITY = 10;
+
+ // Data array and pointers
+ private final int capacity;
+ private final float[] data;
+ private volatile int writeSequence, readSequence;
+
+ /**
+ * Default constructor for a Circular Float Buffer with a given capacity.
+ *
+ * @param capacity size of the array.
+ */
+ public CircularFloatBuffer(int capacity) {
+ this.capacity = (capacity < 1) ? DEFAULT_CAPACITY : capacity;
+ this.data = new float[capacity];
+ this.readSequence = 0;
+ this.writeSequence = -1;
+ }
+
+ /**
+ * Put in a new element to the array.
+ * Overwrites the existing values if present already and moves the write head forward.
+ *
+ * @param element float value to be added to the array.
+ * @return true if adding to the element was successful.
+ */
+ public boolean putNewest(float element) {
+ int nextWriteSeq = writeSequence + 1;
+ data[nextWriteSeq % capacity] = element;
+ writeSequence++;
+ return true;
+ }
+
+ /**
+ * Get the oldest element in the array.
+ * If empty, return an empty Optional. Moves the read head forward.
+ *
+ * @return Optional float of the oldest element.
+ *
+ * @see Optional
+ */
+ public Optional getOldest() {
+ if (!isEmpty()) {
+ float nextValue = data[readSequence % capacity];
+ readSequence++;
+ return Optional.of(nextValue);
+ }
+ return Optional.empty();
+ }
+
+ /**
+ * Get the capacity of the buffer.
+ *
+ * @return int capacity, size of the underlying array.
+ */
+ public int getCapacity() {
+ return capacity;
+ }
+
+ /**
+ * Get the number of elements currently in the buffer.
+ *
+ * @return int number of floats in the buffer.
+ */
+ public int getCurrentSize() {
+ return (writeSequence - readSequence) + 1;
+ }
+
+ /**
+ * Checks if the buffer is empty.
+ *
+ * @return true if there are no elements in the buffer, false otherwise
+ */
+ public boolean isEmpty() {
+ return writeSequence < readSequence;
+ }
+
+ /**
+ * Check if the buffer is full.
+ *
+ * @return true if the number of elements in the buffer matches the capacity, false otherwise.
+ */
+ public boolean isFull() {
+ return getCurrentSize() >= capacity;
+ }
+
+ /**
+ * Get a copy of the buffer as a list starting with the oldest element.
+ * If the list is not full return null.
+ *
+ * @return List of Floats contained in the buffer from oldest to newest.
+ */
+ public List getListCopy() {
+ if(!isFull()) return null;
+ return IntStream.range(readSequence, readSequence + capacity)
+ .mapToObj(i -> this.data[i % capacity])
+ .collect(Collectors.toList());
+ }
+
+}
diff --git a/app/src/main/java/com/openpositioning/PositionMe/FusionAlgorithms/ExtendedKalmanFilter.java b/app/src/main/java/com/openpositioning/PositionMe/FusionAlgorithms/ExtendedKalmanFilter.java
new file mode 100644
index 00000000..5bce5689
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/FusionAlgorithms/ExtendedKalmanFilter.java
@@ -0,0 +1,332 @@
+package com.openpositioning.PositionMe.FusionAlgorithms;
+
+import android.os.Handler;
+import android.os.HandlerThread;
+import android.util.Log;
+
+import com.openpositioning.PositionMe.Method.CoordinateTransform;
+import com.openpositioning.PositionMe.Method.ExponentialSmoothingFilter;
+import com.openpositioning.PositionMe.Method.OutlierDetector;
+import com.openpositioning.PositionMe.Method.TurnDetector;
+import com.google.android.gms.maps.model.LatLng;
+
+import org.ejml.simple.SimpleMatrix;
+
+/**
+ * ExtendedKalmanFilter is used to fuse data from Traj (e.g., PDR, GNSS, WiFi, pressure, etc.)
+ * and handle heading, step length, time delay, etc., to output fused position information
+ * (including relative timestamp).
+ *
+ * In replay mode, the system does not rely on the real-time system clock,
+ * but instead uses the relative_timestamp recorded within Traj to calculate delays,
+ * allowing the replay to follow the original capture timing.
+ *
+ * Core state Xk = [ heading, east, north ]^T
+ * heading is the direction (radian), east/north are displacements in the ENU coordinate system (unit: meters)
+ */
+public class ExtendedKalmanFilter {
+
+ // Parameters
+ private final static long relevanceThreshold = 5000;
+ private final static double stepPercentageError = 0.1;
+ private final static double stepMisdirection = 0.2;
+ private final static double defaultStepLength = 0.7;
+ private final static long maxElapsedTimeForMaxPenalty = 6000;
+ private final static long maxElapsedTimeForBearingPenalty = 15;
+ private final static double maxBearingPenalty = Math.toRadians(22.5);
+ private final static double sigma_dTheta = Math.toRadians(15);
+ private final static double sigma_dPseudo = Math.toRadians(8);
+ private final static double sigma_dStraight = Math.toRadians(2);
+ private final static double smoothingFactor = 0.35;
+ private double sigma_ds = 1;
+ private double sigma_north_meas = 10;
+ private double sigma_east_meas = 10;
+ private double wifi_std = 10;
+ private double gnss_std = 5;
+
+ // Matrices and state
+ private SimpleMatrix Fk;
+ private SimpleMatrix Qk;
+ private SimpleMatrix Hk;
+ private SimpleMatrix Rk;
+ private SimpleMatrix Pk;
+ private SimpleMatrix Xk;
+
+ // For replay
+ private long initialiseTime;
+
+ // Flags
+ private boolean usingWifi;
+ private boolean stopEKF;
+ private double prevStepLength;
+
+ // Handler thread for asynchronous processing
+ private HandlerThread ekfThread;
+ private Handler ekfHandler;
+
+ // External modules
+ private OutlierDetector outlierDetector;
+ private ExponentialSmoothingFilter smoothingFilter;
+
+ // --- Replay extension: initial reference point and conversion parameters ---
+ // startPosition = [latitude, longitude, altitude]
+ // ecefRefCoords = corresponding ECEF coordinates
+ private double[] startPosition;
+ private double[] ecefRefCoords;
+
+ public ExtendedKalmanFilter() {
+ this.outlierDetector = new OutlierDetector();
+ this.smoothingFilter = new ExponentialSmoothingFilter(smoothingFactor, 2);
+ this.stopEKF = false;
+
+ // Initialize state vector Xk: [heading, East, North]
+ this.Xk = new SimpleMatrix(new double[][]{{0}, {0}, {0}});
+ // Initial covariance
+ this.Pk = SimpleMatrix.diag(0, 0, 0);
+ // Process noise covariance
+ this.Qk = SimpleMatrix.diag(
+ (sigma_dTheta * sigma_dTheta),
+ sigma_ds,
+ sigma_ds);
+ // Measurement noise covariance
+ this.Rk = SimpleMatrix.diag((sigma_east_meas * sigma_east_meas), (sigma_north_meas * sigma_north_meas));
+ // Observation matrix
+ this.Hk = new SimpleMatrix(new double[][]{{0, 1, 0}, {0, 0, 1}});
+
+ this.initialiseTime = 0;
+ this.prevStepLength = defaultStepLength;
+ this.usingWifi = false;
+
+ initialiseBackgroundHandler();
+ }
+
+ private void initialiseBackgroundHandler() {
+ ekfThread = new HandlerThread("EKFProcessingThread");
+ ekfThread.start();
+ ekfHandler = new Handler(ekfThread.getLooper());
+ }
+
+ // Set initial GNSS reference coordinates for ENU conversion
+ public void setInitialReference(double[] startPosition, double[] ecefRefCoords) {
+ this.startPosition = startPosition;
+ this.ecefRefCoords = ecefRefCoords;
+ }
+
+ // Set initial timestamp
+ public void setInitialTime(long initTime) {
+ this.initialiseTime = initTime;
+ }
+
+ // Reset the EKF
+ public void reset() {
+ this.stopEKF = false;
+ // Reset state vector
+ Xk.set(0, 0, 0); // heading
+ Xk.set(1, 0, 0); // east
+ Xk.set(2, 0, 0); // north
+ // Reset covariance
+ Pk = SimpleMatrix.diag(0, 0, 0);
+ // Reset previous step length
+ this.prevStepLength = defaultStepLength;
+ }
+
+ public void stopFusion() {
+ this.stopEKF = true;
+ Log.d("EKF:", "Stopping EKF handler");
+ this.smoothingFilter.reset();
+ ekfThread.quitSafely();
+ }
+
+ // Set whether WiFi is being used
+ public void setUsingWifi(boolean update) {
+ if (stopEKF) return;
+ ekfHandler.post(() -> usingWifi = update);
+ }
+
+ /**
+ * Get internal ECEF reference coordinates (used externally for precise ENU→LatLng conversion of PDR markers).
+ */
+ public double[] getEcefRefCoords() {
+ return ecefRefCoords;
+ }
+
+ /**
+ * Return current ENU position (east, north) estimated by the Kalman filter.
+ * heading = Xk.get(0), east = Xk.get(1), north = Xk.get(2)
+ */
+ public double[] getEnuPosition() {
+ return new double[]{Xk.get(1, 0), Xk.get(2, 0)};
+ }
+
+ // Prediction
+ public void predict(double theta_k, double step_k, double averageStepLength, long refTime, TurnDetector.MovementType userMovement) {
+ if (stopEKF) return;
+
+ ekfHandler.post(() -> {
+ double adaptedHeading = wrapToPi((Math.PI / 2 - theta_k)); // Correct heading
+ // Update state vector
+ double oldHeading = Xk.get(0, 0);
+ double oldEast = Xk.get(1, 0);
+ double oldNorth = Xk.get(2, 0);
+
+ // Compute delta for east and north
+ double deltaEast = step_k * Math.cos(theta_k);
+ double deltaNorth = step_k * Math.sin(theta_k);
+
+ // Update Xk
+ double newHeading = wrapToPi(adaptedHeading);
+ double newEast = oldEast + deltaEast;
+ double newNorth = oldNorth + deltaNorth;
+
+ Xk.set(0, 0, newHeading);
+ Xk.set(1, 0, newEast);
+ Xk.set(2, 0, newNorth);
+
+ // Update Fk
+ updateFk(newHeading, step_k);
+ // Update Qk
+ updateQk(averageStepLength, newHeading, (refTime - initialiseTime), getThetaStd(userMovement));
+
+ // Pk = Fk * Pk * Fk^T + Qk
+ SimpleMatrix FkP = Fk.mult(Pk);
+ Pk = FkP.mult(Fk.transpose()).plus(Qk);
+
+ prevStepLength = step_k;
+ });
+ }
+
+ // observeEast / observeNorth / pdrEast / pdrNorth are all in ENU coordinates
+ public void onObservationUpdate(double observeEast, double observeNorth,
+ double pdrEast, double pdrNorth,
+ double altitude, double penaltyFactor) {
+ if (stopEKF) return;
+
+ ekfHandler.post(() -> {
+ // Construct observation vector Zk = [ observeEast, observeNorth ]^T
+ // Predicted Hk*Xk = [ Xk[1], Xk[2] ] = [ pdrEast, pdrNorth ]
+ // Compute difference between observation and prediction: y_pred = Zk - Hk*Xk
+ double zEast = observeEast;
+ double zNorth = observeNorth;
+
+ // Predicted East, North
+ double predEast = pdrEast;
+ double predNorth = pdrNorth;
+
+ double diffEast = zEast - predEast;
+ double diffNorth = zNorth - predNorth;
+
+ SimpleMatrix Zk = new SimpleMatrix(2, 1);
+ Zk.set(0, 0, zEast);
+ Zk.set(1, 0, zNorth);
+
+ SimpleMatrix yPred = new SimpleMatrix(2, 1);
+ yPred.set(0, 0, diffEast);
+ yPred.set(1, 0, diffNorth);
+
+ // Update measurement covariance Rk
+ updateRk(penaltyFactor);
+
+ // S = Hk * Pk * Hk^T + Rk
+ SimpleMatrix Hp = Hk.mult(Pk);
+ SimpleMatrix S = Hp.mult(Hk.transpose()).plus(Rk);
+
+ // K = Pk * Hk^T * S^-1
+ SimpleMatrix K = Pk.mult(Hk.transpose()).mult(S.invert());
+
+ // Xk = Xk + K*yPred
+ Xk = Xk.plus(K.mult(yPred));
+
+ // Wrap heading
+ double heading = wrapToPi(Xk.get(0, 0));
+ Xk.set(0, 0, heading);
+
+ // Pk = (I - K*Hk)*Pk
+ SimpleMatrix I = SimpleMatrix.identity(Pk.numRows());
+ Pk = (I.minus(K.mult(Hk))).mult(Pk);
+ });
+ }
+
+ /**
+ * Get the current fused LatLng.
+ * Xk(1) = east, Xk(2) = north, altitude can be from latest GNSS or barometer reading.
+ */
+ public LatLng getCurrentLatLng(double altitude) {
+ if (this.startPosition == null || this.ecefRefCoords == null) {
+ return null; // Not initialized yet
+ }
+ double east = Xk.get(1, 0);
+ double north = Xk.get(2, 0);
+ // Convert ENU to LatLng using CoordinateTransform
+ double[] ecefRef = this.ecefRefCoords;
+ return CoordinateTransform.enuToGeodetic(east, north, altitude,
+ startPosition[0], startPosition[1], ecefRef);
+ }
+
+ // ---------------------- Internal methods ----------------------
+
+ private void updateFk(double theta_k, double step_k) {
+ double cosTheta = Math.cos(theta_k);
+ double sinTheta = Math.sin(theta_k);
+ // Fk is a 3x3 matrix
+ this.Fk = new SimpleMatrix(new double[][]{
+ {1, 0, 0},
+ {step_k * cosTheta, 1, 0},
+ {-step_k * sinTheta, 0, 1}
+ });
+ }
+
+ private void updateQk(double averageStepLength, double theta_k, long dt, double thetaStd) {
+ double penaltyFactor = calculateTimePenalty(dt);
+ double step_error = (stepPercentageError * averageStepLength + stepMisdirection) * penaltyFactor;
+ double bearing_error = calculateBearingPenalty(thetaStd, dt);
+
+ // (0,0) corresponds to heading; (1,1) and (2,2) to east / north
+ this.Qk.set(0, 0, bearing_error * bearing_error);
+ this.Qk.set(1, 1, step_error * step_error);
+ this.Qk.set(2, 2, step_error * step_error);
+ }
+
+ private void updateRk(double penaltyFactor) {
+ double stdVal = usingWifi ? wifi_std : gnss_std;
+ double val = stdVal * stdVal * penaltyFactor;
+ // Rk is a 2x2 matrix
+ this.Rk.set(0, 0, val);
+ this.Rk.set(1, 1, val);
+ }
+
+ private double calculateTimePenalty(long dt) {
+ // dt is the time difference from the initial timestamp
+ double penaltyFactor = 1.0 + 0.5 * Math.min(dt, maxElapsedTimeForMaxPenalty) / maxElapsedTimeForMaxPenalty;
+ return penaltyFactor;
+ }
+
+ private double calculateBearingPenalty(double thetaStd, long dt) {
+ double elapsedTimeFraction = Math.min(dt / 60000.0, maxElapsedTimeForBearingPenalty) / maxElapsedTimeForBearingPenalty;
+ double penalty = thetaStd + (maxBearingPenalty - thetaStd) * elapsedTimeFraction;
+ return penalty;
+ }
+
+ private double getThetaStd(TurnDetector.MovementType userMovement) {
+ switch (userMovement) {
+ case TURN:
+ return sigma_dTheta;
+ case PSEUDO_TURN:
+ return sigma_dPseudo;
+ case STRAIGHT:
+ return sigma_dStraight;
+ default:
+ return sigma_dTheta;
+ }
+ }
+
+ // Wrap angle to [-pi, pi]
+ private static double wrapToPi(double x) {
+ double bearing = x % (2 * Math.PI);
+ if (bearing < -Math.PI) {
+ bearing += 2 * Math.PI;
+ } else if (bearing > Math.PI) {
+ bearing -= 2 * Math.PI;
+ }
+ return bearing;
+ }
+}
diff --git a/app/src/main/java/com/openpositioning/PositionMe/FusionAlgorithms/ParticleFilter.java b/app/src/main/java/com/openpositioning/PositionMe/FusionAlgorithms/ParticleFilter.java
new file mode 100644
index 00000000..e7bfb382
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/FusionAlgorithms/ParticleFilter.java
@@ -0,0 +1,272 @@
+package com.openpositioning.PositionMe.FusionAlgorithms;
+
+import android.location.Location;
+import android.util.Log;
+
+import com.google.android.gms.maps.model.LatLng;
+import com.openpositioning.PositionMe.Method.CoordinateTransform;
+import com.openpositioning.PositionMe.Method.OutlierDetector;
+import com.openpositioning.PositionMe.sensors.SensorFusion;
+import java.util.Random;
+
+/**
+ * Modified Particle Filter implementation with particle injection strategy
+ * to enhance correction from GNSS/WiFi measurement data
+ */
+public class ParticleFilter {
+ // Number of particles
+ private static final int NUM_PARTICLES = 200;
+ // Initial standard deviation near the reference point (in lat/lon units, roughly meters to tens of meters)
+ private static final double INITIAL_STD_DEV = 0.001;
+ // Motion noise (added to particles during resampling), increased to 0.3 to enhance diffusion
+ private static final double MOTION_NOISE = 0.3;
+
+ // Particle injection parameters
+ private static final double INJECTION_FRACTION = 0.3; // Inject 30% of particles
+ private static final double INJECTION_NOISE = 0.005; // Noise std. dev. during injection
+
+ private Particle[] particles;
+ private final Random random;
+
+ // Reference location (lat/lon/alt), used for ENU conversion
+ private final double refLatitude;
+ private final double refLongitude;
+ private final double refAlt;
+
+ // ENU coordinates after initialization (typically close to 0,0,0)
+ private final double initialTrueEasting;
+ private final double initialTrueNorthing;
+
+ // Outlier detector (currently disabled)
+ private OutlierDetector outlierDetector;
+
+ /**
+ * Main constructor: initializes filter with a reference point (lat, lon, alt)
+ */
+ public ParticleFilter(double[] initialStartRef) {
+ this.outlierDetector = new OutlierDetector();
+ this.random = new Random();
+
+ // Store the reference point
+ this.refLatitude = initialStartRef[0];
+ this.refLongitude = initialStartRef[1];
+ this.refAlt = initialStartRef[2];
+
+ Log.d("PF_DEBUG", String.format("Reference point: lat=%.6f, lon=%.6f, alt=%.1f",
+ refLatitude, refLongitude, refAlt));
+
+ // Convert the reference point to ENU coordinates (usually (0,0))
+ double[] enuCoords = CoordinateTransform.geodeticToEnu(
+ refLatitude, refLongitude, refAlt,
+ refLatitude, refLongitude, refAlt
+ );
+ this.initialTrueEasting = enuCoords[0];
+ this.initialTrueNorthing = enuCoords[1];
+
+ Log.d("PF_DEBUG", String.format("Initial ENU: east=%.3f, north=%.3f",
+ initialTrueEasting, initialTrueNorthing));
+
+ // Initialize all particles
+ initializeParticles();
+ }
+
+ /**
+ * No-argument constructor to maintain compatibility:
+ * defaults to using SensorFusion.getInstance().getGNSSLatLngAlt(true) as the reference
+ */
+ public ParticleFilter() {
+ this(SensorFusion.getInstance().getGNSSLatLngAlt(true));
+ }
+
+ /**
+ * Initializes particles randomly around the reference point
+ */
+ private void initializeParticles() {
+ particles = new Particle[NUM_PARTICLES];
+ for (int i = 0; i < NUM_PARTICLES; i++) {
+ double easting = initialTrueEasting + random.nextGaussian() * INITIAL_STD_DEV;
+ double northing = initialTrueNorthing + random.nextGaussian() * INITIAL_STD_DEV;
+ particles[i] = new Particle(easting, northing, 1.0 / NUM_PARTICLES);
+ Log.v("PF_INIT", String.format("Particle %d: east=%.6f, north=%.6f",
+ i, easting, northing));
+ }
+ }
+
+ /**
+ * Motion model update (using PDR data)
+ * @param stepLength Step length (in meters)
+ * @param heading Heading (in radians, 0 = north, π/2 = east, clockwise)
+ */
+ public void predictMotion(double stepLength, double heading) {
+ for (Particle particle : particles) {
+ // Add random noise to step length and heading
+ double noisyStep = stepLength * (1 + random.nextGaussian() * 0.1);
+ double noisyHeading = heading + random.nextGaussian() * 0.1;
+
+ double deltaEasting = noisyStep * Math.cos(noisyHeading);
+ double deltaNorthing = noisyStep * Math.sin(noisyHeading);
+
+ particle.update(deltaEasting, deltaNorthing);
+ }
+ }
+
+ /**
+ * Measurement update (GNSS/WiFi)
+ * @param measuredLat Measured latitude
+ * @param measuredLong Measured longitude
+ */
+ public void measurementUpdate(double measuredLat, double measuredLong) {
+ // 1) Convert measurement to ENU coordinates
+ double[] enuCoords = CoordinateTransform.geodeticToEnu(
+ measuredLat, measuredLong, refAlt,
+ refLatitude, refLongitude, refAlt
+ );
+ double measuredEast = enuCoords[0];
+ double measuredNorth = enuCoords[1];
+
+ // 2) Compute weighted average of current particle positions
+ double fusedEast = 0, fusedNorth = 0;
+ for (Particle p : particles) {
+ fusedEast += p.getEasting() * p.getWeight();
+ fusedNorth += p.getNorthing() * p.getWeight();
+ }
+ double dx = measuredEast - fusedEast;
+ double dy = measuredNorth - fusedNorth;
+ double distance = Math.sqrt(dx * dx + dy * dy);
+
+ // 3) Outlier detection is disabled to ensure all measurements are used
+ // boolean isOutlier = outlierDetector.detectOutliers(distance);
+ // if (isOutlier) {
+ // Log.w("PF", "Outlier detected! distance=" + distance + ", skip update.");
+ // return;
+ // }
+
+ // 4) Update weights based on distance from measurement
+ double totalWeight = 0;
+ for (Particle particle : particles) {
+ double pdx = measuredEast - particle.getEasting();
+ double pdy = measuredNorth - particle.getNorthing();
+ double d = Math.sqrt(pdx * pdx + pdy * pdy);
+ double sigma = Math.max(0.01, d * 0.05);
+ double gain = 100.0;
+ double likelihood = Math.exp(-0.5 * (d * d) / (sigma * sigma)) * gain;
+ particle.setWeight(particle.getWeight() * likelihood);
+ totalWeight += particle.getWeight();
+ }
+
+ // Normalize weights
+ if (totalWeight > 0) {
+ for (Particle particle : particles) {
+ particle.setWeight(particle.getWeight() / totalWeight);
+ }
+ } else {
+ Log.w("PF", "Weight degeneracy detected, reinitializing particles");
+ initializeParticles();
+ return;
+ }
+
+ // 5) Particle injection: force a fraction of particles near the measurement
+ int injectionCount = (int) (NUM_PARTICLES * INJECTION_FRACTION);
+ for (int i = 0; i < injectionCount; i++) {
+ int index = random.nextInt(NUM_PARTICLES);
+ double noiseE = random.nextGaussian() * INJECTION_NOISE;
+ double noiseN = random.nextGaussian() * INJECTION_NOISE;
+ particles[index] = new Particle(measuredEast + noiseE, measuredNorth + noiseN, 1.0 / NUM_PARTICLES);
+ }
+
+ // 6) Resample if effective number of particles is too low
+ if (calculateEffectiveParticles() < NUM_PARTICLES * 0.5) {
+ resampleParticles();
+ }
+ }
+
+ /**
+ * Calculates effective number of particles (to detect degeneracy)
+ */
+ private double calculateEffectiveParticles() {
+ double sumSq = 0;
+ for (Particle p : particles) {
+ sumSq += p.getWeight() * p.getWeight();
+ }
+ return 1.0 / sumSq;
+ }
+
+ /**
+ * Low-variance resampling
+ */
+ private void resampleParticles() {
+ Particle[] newParticles = new Particle[NUM_PARTICLES];
+ double[] cumulativeWeights = new double[NUM_PARTICLES];
+
+ cumulativeWeights[0] = particles[0].getWeight();
+ for (int i = 1; i < NUM_PARTICLES; i++) {
+ cumulativeWeights[i] = cumulativeWeights[i - 1] + particles[i].getWeight();
+ }
+
+ double step = 1.0 / NUM_PARTICLES;
+ double position = random.nextDouble() * step;
+ int index = 0;
+
+ for (int i = 0; i < NUM_PARTICLES; i++) {
+ // Add index boundary check to prevent out-of-bounds error
+ while (index < NUM_PARTICLES - 1 && position > cumulativeWeights[index]) {
+ index++;
+ }
+ double noiseE = random.nextGaussian() * MOTION_NOISE;
+ double noiseN = random.nextGaussian() * MOTION_NOISE;
+
+ newParticles[i] = new Particle(
+ particles[index].getEasting() + noiseE,
+ particles[index].getNorthing() + noiseN,
+ 1.0 / NUM_PARTICLES
+ );
+ position += step;
+ }
+ particles = newParticles;
+ }
+
+ /**
+ * Get fused position (convert weighted ENU average back to lat/lon)
+ */
+ public LatLng getFusedPosition() {
+ double eastSum = 0, northSum = 0;
+ for (Particle particle : particles) {
+ eastSum += particle.getEasting() * particle.getWeight();
+ northSum += particle.getNorthing() * particle.getWeight();
+ }
+ LatLng result = CoordinateTransform.enuToGeodetic(
+ eastSum, northSum, refAlt,
+ refLatitude, refLongitude, refAlt
+ );
+ Log.d("PF_OUTPUT", String.format(
+ "Fused position: lat=%.6f, lon=%.6f (ENU: %.2f, %.2f)",
+ result.latitude, result.longitude, eastSum, northSum
+ ));
+ return result;
+ }
+
+ /**
+ * Inner Particle class
+ */
+ private static class Particle {
+ private double easting;
+ private double northing;
+ private double weight;
+
+ Particle(double easting, double northing, double weight) {
+ this.easting = easting;
+ this.northing = northing;
+ this.weight = weight;
+ }
+
+ void update(double deltaEasting, double deltaNorthing) {
+ this.easting += deltaEasting;
+ this.northing += deltaNorthing;
+ }
+
+ double getEasting() { return easting; }
+ double getNorthing() { return northing; }
+ double getWeight() { return weight; }
+ void setWeight(double weight) { this.weight = weight; }
+ }
+}
diff --git a/app/src/main/java/com/openpositioning/PositionMe/IndoorMapManager.java b/app/src/main/java/com/openpositioning/PositionMe/IndoorMapManager.java
new file mode 100644
index 00000000..5f0d9163
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/IndoorMapManager.java
@@ -0,0 +1,194 @@
+package com.openpositioning.PositionMe;
+
+import android.graphics.Color;
+import android.util.Log;
+
+import com.google.android.gms.maps.GoogleMap;
+import com.google.android.gms.maps.model.BitmapDescriptorFactory;
+import com.google.android.gms.maps.model.GroundOverlay;
+import com.google.android.gms.maps.model.GroundOverlayOptions;
+import com.google.android.gms.maps.model.LatLng;
+import com.google.android.gms.maps.model.LatLngBounds;
+import com.google.android.gms.maps.model.Polyline;
+import com.google.android.gms.maps.model.PolylineOptions;
+
+
+import java.util.Arrays;
+import java.util.List;
+
+/**
+ * Class used to manage indoor floor map overlays
+ * Currently used by RecordingFragment
+ * @see BuildingPolygon Describes the bounds of buildings and the methods to check if point is
+ * in the building
+ * @author Arun Gopalakrishnan
+ */
+public class IndoorMapManager {
+ // To store the map instance
+ private GoogleMap gMap;
+ //Stores the overlay of the indoor maps
+ private GroundOverlay groundOverlay;
+ // Stores the current Location of user
+ private LatLng currentLocation;
+ // Stores if indoor map overlay is currently set
+ private boolean isIndoorMapSet=false;
+ //Stores the current floor in building
+ private int currentFloor;
+ // Floor height of current building
+ private float floorHeight;
+ //Images of the Nucleus Building and Library indoor floor maps
+ private final List NUCLEUS_MAPS =Arrays.asList(
+ R.drawable.nucleuslg, R.drawable.nucleusg, R.drawable.nucleus1,
+ R.drawable.nucleus2,R.drawable.nucleus3);
+ private final List LIBRARY_MAPS =Arrays.asList(
+ R.drawable.libraryg, R.drawable.library1, R.drawable.library2,
+ R.drawable.library3);
+ // South-west and north east Bounds of Nucleus building and library to set the Overlay
+ LatLngBounds NUCLEUS=new LatLngBounds(
+ BuildingPolygon.NUCLEUS_SW,
+ BuildingPolygon.NUCLEUS_NE
+ );
+ LatLngBounds LIBRARY=new LatLngBounds(
+ BuildingPolygon.LIBRARY_SW,
+ BuildingPolygon.LIBRARY_NE
+ );
+ //Average Floor Heights of the Buildings
+ public static final float NUCLEUS_FLOOR_HEIGHT=4.2F;
+ public static final float LIBRARY_FLOOR_HEIGHT=3.6F;
+
+ /**
+ * Constructor to set the map instance
+ * @param map The map on which the indoor floor map overlays are set
+ */
+ public IndoorMapManager(GoogleMap map){
+ this.gMap=map;
+ }
+
+ /**
+ * Function to update the current location of user and display the indoor map
+ * if user in building with indoor map available
+ * @param currentLocation new location of user
+ */
+ public void setCurrentLocation(LatLng currentLocation){
+ this.currentLocation=currentLocation;
+ setBuildingOverlay();
+ }
+
+ /**
+ * Function to obtain the current building's floor height
+ * @return the floor height of the current building the user is in
+ */
+ public float getFloorHeight() {
+ return floorHeight;
+ }
+
+ /**
+ * Getter to obtain if currently an indoor floor map is being displayed
+ * @return true if an indoor map is visible to the user, false otherwise
+ */
+ public boolean getIsIndoorMapSet(){
+ return isIndoorMapSet;
+ }
+
+ /**
+ * Setting the new floor of a user and displaying the indoor floor map accordingly
+ * (if floor exists in building)
+ * @param newFloor the floor the user is at
+ * @param autoFloor flag if function called by auto-floor feature
+ */
+ public void setCurrentFloor(int newFloor, boolean autoFloor) {
+ if (BuildingPolygon.inNucleus(currentLocation)){
+ //Special case for nucleus when auto-floor is being used
+ if (autoFloor) {
+ // If nucleus add bias floor as lower-ground floor referred to as floor 0
+ newFloor += 1;
+ }
+ // If within bounds and different from floor map currently being shown
+ if (newFloor>=0 && newFloor=0 && newFloor points=BuildingPolygon.NUCLEUS_POLYGON;
+ // Closing Boundary
+ points.add(BuildingPolygon.NUCLEUS_POLYGON.get(0));
+ gMap.addPolyline(new PolylineOptions().color(Color.GREEN)
+ .addAll(points));
+
+ // Indicator for the Library Building
+ points=BuildingPolygon.LIBRARY_POLYGON;
+ // Closing Boundary
+ points.add(BuildingPolygon.LIBRARY_POLYGON.get(0));
+ gMap.addPolyline(new PolylineOptions().color(Color.GREEN)
+ .addAll(points));
+ }
+}
diff --git a/app/src/main/java/com/openpositioning/PositionMe/MainActivity.java b/app/src/main/java/com/openpositioning/PositionMe/MainActivity.java
new file mode 100644
index 00000000..97b73d2f
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/MainActivity.java
@@ -0,0 +1,584 @@
+package com.openpositioning.PositionMe;
+
+import android.Manifest;
+import android.app.AlertDialog;
+import android.content.DialogInterface;
+import android.content.Intent;
+import android.content.SharedPreferences;
+import android.content.pm.PackageManager;
+import android.net.Uri;
+import android.os.Build;
+import android.os.Bundle;
+import android.os.Handler;
+import android.provider.Settings;
+import android.view.Menu;
+import android.view.MenuItem;
+import android.widget.Toast;
+
+import androidx.annotation.NonNull;
+import androidx.appcompat.app.AppCompatActivity;
+import androidx.appcompat.app.AppCompatDelegate;
+import androidx.appcompat.widget.Toolbar;
+import androidx.core.app.ActivityCompat;
+import androidx.core.content.ContextCompat;
+import androidx.navigation.NavController;
+import androidx.navigation.NavOptions;
+import androidx.navigation.fragment.NavHostFragment;
+import androidx.navigation.ui.AppBarConfiguration;
+import androidx.navigation.ui.NavigationUI;
+import androidx.preference.PreferenceManager;
+
+import com.openpositioning.PositionMe.sensors.Observer;
+import com.openpositioning.PositionMe.sensors.SensorFusion;
+
+/**
+ * The Main Activity of the application, handling setup, permissions and starting all other fragments
+ * and processes.
+ * The Main Activity takes care of most essential tasks before the app can run. Such as setting up
+ * the views, and enforcing light mode so the colour scheme is consistent. It initialises the
+ * various fragments and the navigation between them, getting the Navigation controller. It also
+ * loads the custom action bar with the set theme and icons, and enables back-navigation. The shared
+ * preferences are also loaded.
+ *
+ * The most important task of the main activity is check and asking for the necessary permissions to
+ * enable the application to use the required hardware devices. This is done through a number of
+ * functions that call the OS, as well as pop-up messages warning the user if permissions are denied.
+ *
+ * Once all permissions are granted, the Main Activity obtains the Sensor Fusion instance and sets
+ * the context, enabling the Fragments to interact with the class without setting it up again.
+ *
+ * @see com.openpositioning.PositionMe.fragments.HomeFragment the initial fragment displayed.
+ * @see com.openpositioning.PositionMe.R.navigation the navigation graph.
+ * @see SensorFusion the singletion data processing class.
+ *
+ * @author Mate Stodulka
+ * @author Virginia Cangelosi
+ */
+public class MainActivity extends AppCompatActivity implements Observer {
+
+ //region Static variables
+ // Static IDs for permission responses.
+ private static final int REQUEST_ID_WIFI_PERMISSION = 99;
+ private static final int REQUEST_ID_LOCATION_PERMISSION = 98;
+ private static final int REQUEST_ID_READ_WRITE_PERMISSION = 97;
+ private static final int REQUEST_ID_ACTIVITY_PERMISSION = 96;
+ //endregion
+
+ //region Instance variables
+ private NavController navController;
+
+ private SharedPreferences settings;
+ private SensorFusion sensorFusion;
+ private Handler httpResponseHandler;
+
+ //endregion
+
+ //region Activity Lifecycle
+
+ /**
+ * {@inheritDoc}
+ * Forces light mode, sets up the navigation graph, initialises the toolbar with back action on
+ * the nav controller, loads the shared preferences and checks for all permissions necessary.
+ * Sets up a Handler for displaying messages from other classes.
+ */
+ @Override
+ protected void onCreate(Bundle savedInstanceState) {
+ super.onCreate(savedInstanceState);
+ AppCompatDelegate.setDefaultNightMode(AppCompatDelegate.MODE_NIGHT_NO);
+ setContentView(R.layout.activity_main);
+
+ // Set up navigation and fragments
+ NavHostFragment navHostFragment = (NavHostFragment) getSupportFragmentManager().findFragmentById(R.id.nav_host_fragment);
+ navController = navHostFragment.getNavController();
+
+ // Set action bar
+ Toolbar toolbar = findViewById(R.id.main_toolbar);
+ setSupportActionBar(toolbar);
+ toolbar.showOverflowMenu();
+ toolbar.setBackgroundColor(ContextCompat.getColor(getApplicationContext(), R.color.primaryBlue));
+ toolbar.setTitleTextColor(ContextCompat.getColor(getApplicationContext(), R.color.white));
+
+ // Set up back action
+ AppBarConfiguration appBarConfiguration = new AppBarConfiguration.Builder(navController.getGraph()).build();
+ NavigationUI.setupWithNavController(toolbar, navController, appBarConfiguration);
+
+ // Get handle for settings
+ this.settings = PreferenceManager.getDefaultSharedPreferences(this);
+ settings.edit().putBoolean("permanentDeny", false).apply();
+
+ //Check Permissions
+ if(ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.ACCESS_FINE_LOCATION) != PackageManager.PERMISSION_GRANTED ||
+ ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.ACCESS_COARSE_LOCATION) != PackageManager.PERMISSION_GRANTED ||
+ ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.ACCESS_WIFI_STATE) != PackageManager.PERMISSION_GRANTED ||
+ ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.CHANGE_WIFI_STATE) != PackageManager.PERMISSION_GRANTED ||
+ ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.INTERNET) != PackageManager.PERMISSION_GRANTED ||
+ ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.READ_EXTERNAL_STORAGE) != PackageManager.PERMISSION_GRANTED ||
+ ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.WRITE_EXTERNAL_STORAGE) != PackageManager.PERMISSION_GRANTED ||
+ ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.ACTIVITY_RECOGNITION) != PackageManager.PERMISSION_GRANTED){
+ askLocationPermissions();
+ }
+ // Handler for global toasts and popups from other classes
+ this.httpResponseHandler = new Handler();
+ }
+
+ /**
+ * {@inheritDoc}
+ */
+ @Override
+ public void onPause() {
+ super.onPause();
+ //Ensure sensorFusion has been initialised before unregistering listeners
+ if(sensorFusion != null) {
+ sensorFusion.stopListening();
+ }
+ }
+
+ /**
+ * {@inheritDoc}
+ * Checks for activities in case the app was closed without granting them, or if they were
+ * granted through the settings page. Repeats the startup checks done in
+ * {@link MainActivity#onCreate(Bundle)}. Starts listening in the SensorFusion class.
+ *
+ * @see SensorFusion the main data processing class.
+ */
+ @Override
+ public void onResume() {
+ super.onResume();
+ //Check if permissions are granted before resuming listeners
+ if(ActivityCompat.checkSelfPermission(this, Manifest.permission.ACCESS_FINE_LOCATION)
+ != PackageManager.PERMISSION_GRANTED || ActivityCompat.checkSelfPermission
+ (this, Manifest.permission.ACCESS_COARSE_LOCATION)
+ != PackageManager.PERMISSION_GRANTED || ActivityCompat.checkSelfPermission
+ (this,Manifest.permission.ACCESS_WIFI_STATE)
+ != PackageManager.PERMISSION_GRANTED || ActivityCompat.checkSelfPermission
+ (this,Manifest.permission.CHANGE_WIFI_STATE)
+ != PackageManager.PERMISSION_GRANTED || ActivityCompat.checkSelfPermission
+ (this,Manifest.permission.INTERNET)
+ != PackageManager.PERMISSION_GRANTED){
+ askLocationPermissions();
+ }
+ //If permissions are granted resume listeners
+ else {
+ if(sensorFusion == null) {
+ allPermissionsObtained();
+ }
+ else{
+ sensorFusion.resumeListening();
+ }
+ }
+ }
+
+ /**
+ * Unregisters sensor listeners when the app closes. Not in {@link MainActivity#onPause()} to
+ * enable recording data with a locked screen.
+ *
+ * @see SensorFusion the main data processing class.
+ */
+ @Override
+ protected void onDestroy() {
+ if(sensorFusion != null) {
+ sensorFusion.stopListening();
+ }
+ super.onDestroy();
+ }
+
+ //endregion
+
+ //region Permissions
+
+ /**
+ * Checks for location permissions.
+ * If location permissions are not present, request the permissions through the OS.
+ * If permissions are present, check for the next set of required permissions with
+ * {@link MainActivity#askWifiPermissions()}
+ *
+ * @see MainActivity#onRequestPermissionsResult(int, String[], int[]) handling request responses.
+ */
+ private void askLocationPermissions() {
+ // Check for location permission
+ int coarseLocationPermission = ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.ACCESS_COARSE_LOCATION);
+ int fineLocationPermission = ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.ACCESS_FINE_LOCATION);
+ int internetPermission = ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.INTERNET);
+
+ // Request if not present
+ if(coarseLocationPermission != PackageManager.PERMISSION_GRANTED ||
+ fineLocationPermission != PackageManager.PERMISSION_GRANTED ||
+ internetPermission != PackageManager.PERMISSION_GRANTED) {
+ this.requestPermissions(
+ new String[]{
+ Manifest.permission.ACCESS_COARSE_LOCATION,
+ Manifest.permission.ACCESS_FINE_LOCATION,
+ Manifest.permission.INTERNET},
+ REQUEST_ID_LOCATION_PERMISSION
+ );
+ }
+ else{
+ // Check other permissions if present
+ askWifiPermissions();
+ }
+ }
+
+ /**
+ * Checks for wifi permissions.
+ * If wifi permissions are not present, request the permissions through the OS.
+ * If permissions are present, check for the next set of required permissions with
+ * {@link MainActivity#askStoragePermission()}
+ *
+ * @see MainActivity#onRequestPermissionsResult(int, String[], int[]) handling request responses.
+ */
+ private void askWifiPermissions() {
+ // Check for wifi permissions
+ int wifiAccessPermission = ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.ACCESS_WIFI_STATE);
+ int wifiChangePermission = ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.CHANGE_WIFI_STATE);
+
+ // Request if not present
+ if(wifiAccessPermission != PackageManager.PERMISSION_GRANTED ||
+ wifiChangePermission != PackageManager.PERMISSION_GRANTED) {
+ requestPermissions(
+ new String[]{Manifest.permission.ACCESS_WIFI_STATE,
+ Manifest.permission.CHANGE_WIFI_STATE},
+ REQUEST_ID_WIFI_PERMISSION
+ );
+ }
+ else{
+ // Check other permissions if present
+ askStoragePermission();
+ }
+ }
+
+ /**
+ * Checks for storage permissions.
+ * If storage permissions are not present, request the permissions through the OS.
+ * If permissions are present, check for the next set of required permissions with
+ * {@link MainActivity#askMotionPermissions()}
+ *
+ * @see MainActivity#onRequestPermissionsResult(int, String[], int[]) handling request responses.
+ */
+ private void askStoragePermission() {
+ // Check for storage permission
+ int writeStoragePermission = ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.WRITE_EXTERNAL_STORAGE);
+ int readStoragePermission = ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.READ_EXTERNAL_STORAGE);
+ // Request if not present
+ if(writeStoragePermission != PackageManager.PERMISSION_GRANTED ||
+ readStoragePermission != PackageManager.PERMISSION_GRANTED) {
+ this.requestPermissions(
+ new String[]{
+ Manifest.permission.WRITE_EXTERNAL_STORAGE,
+ Manifest.permission.READ_EXTERNAL_STORAGE},
+ REQUEST_ID_READ_WRITE_PERMISSION
+ );
+ }
+ else {
+ // Check other permissions if present
+ askMotionPermissions();
+ }
+ }
+
+ /**
+ * Checks for motion activity permissions.
+ * If storage permissions are not present, request the permissions through the OS.
+ * If permissions are present, all permissions have been granted, move on to
+ * {@link MainActivity#allPermissionsObtained()} to initialise SensorFusion.
+ *
+ * @see MainActivity#onRequestPermissionsResult(int, String[], int[]) handling request responses.
+ */
+ private void askMotionPermissions() {
+ // Check for motion activity permission
+ if(Build.VERSION.SDK_INT >= 29) {
+ int activityPermission = ActivityCompat.checkSelfPermission(this,
+ Manifest.permission.ACTIVITY_RECOGNITION);
+ // Request if not present
+ if(activityPermission != PackageManager.PERMISSION_GRANTED) {
+ this.requestPermissions(
+ new String[]{
+ Manifest.permission.ACTIVITY_RECOGNITION},
+ REQUEST_ID_ACTIVITY_PERMISSION
+ );
+ }
+ // Move to finishing function if present
+ else allPermissionsObtained();
+ }
+
+ else allPermissionsObtained();
+ }
+
+ /**
+ * {@inheritDoc}
+ * When a new set of permissions are granted, move on to the next on in the chain of permissions.
+ * Once all permissions are granted, call {@link MainActivity#allPermissionsObtained()}. If any
+ * permissions are denied display 1st time warning pop-up message as the application cannot
+ * function without the required permissions. If permissions are denied twice, display a new
+ * pop-up message, as the OS will not ask for them again, and the user will need to enter the
+ * app settings menu.
+ *
+ * @see MainActivity#askLocationPermissions() first permission request function in the chain.
+ * @see MainActivity#askWifiPermissions() second permission request function in the chain.
+ * @see MainActivity#askStoragePermission() third permission request function in the chain.
+ * @see MainActivity#askMotionPermissions() last permission request function in the chain.
+ * @see MainActivity#allPermissionsObtained() once all permissions are granted.
+ * @see MainActivity#permissionsDeniedFirst() display first pop-up message.
+ * @see MainActivity#permissionsDeniedPermanent() permissions denied twice, pop-up with link to
+ * the appropiate settings menu.
+ */
+ @Override
+ public void onRequestPermissionsResult(int requestCode, @NonNull String[] permissions, @NonNull int[] grantResults) {
+ super.onRequestPermissionsResult(requestCode, permissions, grantResults);
+ switch (requestCode) {
+ case REQUEST_ID_LOCATION_PERMISSION: { // Location permissions
+ // If request is cancelled results are empty
+ if (grantResults.length > 1 &&
+ grantResults[0] == PackageManager.PERMISSION_GRANTED &&
+ grantResults[1] == PackageManager.PERMISSION_GRANTED &&
+ grantResults[2] == PackageManager.PERMISSION_GRANTED) {
+ Toast.makeText(this, "Location permissions granted!", Toast.LENGTH_SHORT).show();
+ this.settings.edit().putBoolean("gps", true).apply();
+ askWifiPermissions();
+ }
+ else {
+ if(!settings.getBoolean("permanentDeny", false)) {
+ permissionsDeniedFirst();
+ }
+ else permissionsDeniedPermanent();
+ Toast.makeText(this, "Location permissions denied!", Toast.LENGTH_SHORT).show();
+ // Unset setting
+ this.settings.edit().putBoolean("gps", false).apply();
+ }
+ break;
+
+ }
+ case REQUEST_ID_WIFI_PERMISSION: { // Wifi permissions
+ // If request is cancelled results are empty
+ if (grantResults.length > 1 &&
+ grantResults[0] == PackageManager.PERMISSION_GRANTED &&
+ grantResults[1] == PackageManager.PERMISSION_GRANTED) {
+ Toast.makeText(this, "Permissions granted!", Toast.LENGTH_SHORT).show();
+ this.settings.edit().putBoolean("wifi", true).apply();
+ askStoragePermission();
+ }
+ else {
+ if(!settings.getBoolean("permanentDeny", false)) {
+ permissionsDeniedFirst();
+ }
+ else permissionsDeniedPermanent();
+ Toast.makeText(this, "Wifi permissions denied!", Toast.LENGTH_SHORT).show();
+ // Unset setting
+ this.settings.edit().putBoolean("wifi", false).apply();
+ }
+ break;
+ }
+ case REQUEST_ID_READ_WRITE_PERMISSION: { // Read write permissions
+ // If request is cancelled results are empty
+ if (grantResults.length > 1 &&
+ grantResults[0] == PackageManager.PERMISSION_GRANTED &&
+ grantResults[1] == PackageManager.PERMISSION_GRANTED) {
+ Toast.makeText(this, "Permissions granted!", Toast.LENGTH_SHORT).show();
+ askMotionPermissions();
+ }
+ else {
+ if(!settings.getBoolean("permanentDeny", false)) {
+ permissionsDeniedFirst();
+ }
+ else permissionsDeniedPermanent();
+ Toast.makeText(this, "Storage permissions denied!", Toast.LENGTH_SHORT).show();
+ }
+ break;
+ }
+ case REQUEST_ID_ACTIVITY_PERMISSION: { // Activity permissions
+ // If request is cancelled results are empty
+ if (grantResults.length >= 1 &&
+ grantResults[0] == PackageManager.PERMISSION_GRANTED) {
+ Toast.makeText(this, "Permissions granted!", Toast.LENGTH_SHORT).show();
+ allPermissionsObtained();
+ }
+ else {
+ if(!settings.getBoolean("permanentDeny", false)) {
+ permissionsDeniedFirst();
+ }
+ else permissionsDeniedPermanent();
+ Toast.makeText(this, "Activity permissions denied!", Toast.LENGTH_SHORT).show();
+ }
+ break;
+ }
+ }
+ }
+
+ /**
+ * Displays a pop-up alert the first time the permissions have been denied.
+ * The pop-up explains the purpose of the application and the necessity of the permissions, and
+ * displays two options. If the "Grant permissions" button is clicked, the permission request
+ * chain is restarted. If the "Exit application" button is clicked, the app closes.
+ *
+ * @see MainActivity#askLocationPermissions() the first in the permission request chain.
+ * @see MainActivity#onRequestPermissionsResult(int, String[], int[]) handling permission results.
+ * @see com.openpositioning.PositionMe.R.string button text resources.
+ */
+ private void permissionsDeniedFirst() {
+ new AlertDialog.Builder(this)
+ .setTitle("Permissions denied")
+ .setMessage("You have denied access to data gathering devices. The primary purpose of this application is to record data.")
+ .setPositiveButton(R.string.grant, new DialogInterface.OnClickListener() {
+ @Override
+ public void onClick(DialogInterface dialogInterface, int i) {
+ settings.edit().putBoolean("permanentDeny", true).apply();
+ askLocationPermissions();
+ }
+ })
+ .setNegativeButton(R.string.exit, new DialogInterface.OnClickListener() {
+ @Override
+ public void onClick(DialogInterface dialogInterface, int i) {
+ settings.edit().putBoolean("permanentDeny", true).apply();
+ finishAffinity();
+ }
+ })
+ .setIcon(R.mipmap.ic_launcher_simple)
+ .show();
+ }
+
+ /**
+ * Displays a pop-up alert when permissions have been denied twice.
+ * The OS will not ask for permissions again on the application's behalf. The pop-up explains
+ * the purpose of the application and the necessity of the permissions, and displays a button.
+ * When the "Settings" button is clicked, the app opens the relevant settings menu where
+ * permissions can be adjusted through an intent. Otherwise the app must be closed by the user
+ *
+ * @see com.openpositioning.PositionMe.R.string button text resources.
+ */
+ private void permissionsDeniedPermanent() {
+ AlertDialog alertDialog = new AlertDialog.Builder(this)
+ .setTitle("Permissions are denied, enable them in settings manually")
+ .setMessage("You have denied necessary sensor permissions for the data recording app. You need to manually enable them in your device's settings.")
+ .setCancelable(false)
+ .setPositiveButton("Settings", new DialogInterface.OnClickListener() {
+ @Override
+ public void onClick(DialogInterface dialogInterface, int i) {
+ Intent intent = new Intent(Settings.ACTION_APPLICATION_DETAILS_SETTINGS);
+ Uri uri = Uri.fromParts("package", getPackageName(), null);
+ intent.setData(uri);
+ startActivityForResult(intent, 1000);
+ }
+ })
+ .setIcon(R.mipmap.ic_launcher_simple)
+ .create();
+ alertDialog.show();
+ }
+
+ /**
+ * Prepares global resources when all permissions are granted.
+ * Resets the permissions tracking boolean in shared preferences, and initialises the
+ * {@link SensorFusion} class with the application context, and registers the main activity to
+ * listen for server responses that SensorFusion receives.
+ *
+ * @see SensorFusion the main data processing class.
+ * @see ServerCommunications the communication class sending and recieving data from the server.
+ */
+ private void allPermissionsObtained() {
+ settings.edit().putBoolean("permanentDeny", false).apply();
+ this.sensorFusion = SensorFusion.getInstance();
+ this.sensorFusion.setContext(getApplicationContext());
+ sensorFusion.registerForServerUpdate(this);
+ }
+
+ //endregion
+
+ //region Navigation
+
+ /**
+ * {@inheritDoc}
+ * Sets desired animations and navigates to {@link com.openpositioning.PositionMe.fragments.SettingsFragment}
+ * when the settings wheel in the action bar is clicked.
+ */
+ @Override
+ public boolean onOptionsItemSelected(@NonNull MenuItem item) {
+ if(navController.getCurrentDestination().getId() == item.getItemId())
+ return super.onOptionsItemSelected(item);
+ else {
+ NavOptions options = new NavOptions.Builder()
+ .setLaunchSingleTop(true)
+ .setEnterAnim(R.anim.slide_in_bottom)
+ .setExitAnim(R.anim.slide_out_top)
+ .setPopEnterAnim(R.anim.slide_in_top)
+ .setPopExitAnim(R.anim.slide_out_bottom).build();
+ navController.navigate(R.id.action_global_settingsFragment, null, options);
+ return true;
+ }
+ }
+
+ /**
+ * {@inheritDoc}
+ * Enables navigating back between fragments.
+ */
+ @Override
+ public boolean onSupportNavigateUp() {
+ return navController.navigateUp() || super.onSupportNavigateUp();
+ }
+
+ /**
+ * {@inheritDoc}
+ * Inflate the designed menu view.
+ *
+ * @see com.openpositioning.PositionMe.R.menu for the xml file.
+ */
+ @Override
+ public boolean onCreateOptionsMenu(Menu menu) {
+ getMenuInflater().inflate(R.menu.menu_items, menu);
+ return true;
+ }
+
+ //endregion
+
+ //region Global toasts
+
+ /**
+ * {@inheritDoc}
+ * Calls the corresponding handler that runs a toast on the Main UI thread.
+ */
+ @Override
+ public void update(Object[] objList) {
+ assert objList[0] instanceof Boolean;
+ if((Boolean) objList[0]) {
+ this.httpResponseHandler.post(displayToastTaskSuccess);
+ }
+ else {
+ this.httpResponseHandler.post(displayToastTaskFailure);
+ }
+ }
+
+ /**
+ * Task that displays positive toast on the main UI thread.
+ * Called when {@link ServerCommunications} successfully uploads a trajectory.
+ */
+ private final Runnable displayToastTaskSuccess = new Runnable() {
+ @Override
+ public void run() {
+ Toast.makeText(MainActivity.this, "Trajectory uploaded", Toast.LENGTH_SHORT).show();
+ }
+ };
+
+ /**
+ * Task that displays negative toast on the main UI thread.
+ * Called when {@link ServerCommunications} fails to upload a trajectory.
+ */
+ private final Runnable displayToastTaskFailure = new Runnable() {
+ @Override
+ public void run() {
+// Toast.makeText(MainActivity.this, "Failed to complete trajectory upload", Toast.LENGTH_SHORT).show();
+ }
+ };
+
+ //endregion
+}
\ No newline at end of file
diff --git a/app/src/main/java/com/openpositioning/PositionMe/Method/CoordinateTransform.java b/app/src/main/java/com/openpositioning/PositionMe/Method/CoordinateTransform.java
new file mode 100644
index 00000000..41dd410b
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/Method/CoordinateTransform.java
@@ -0,0 +1,207 @@
+package com.openpositioning.PositionMe.Method;
+
+import android.util.Log;
+
+import com.google.android.gms.maps.model.LatLng;
+
+/**
+ * A utility class used to convert the PDR coordinates which are relative East North Up (ENU) on a tangent plane to the earths surface to
+ * WSG84 coordinates that google maps uses. This allows the relative coordinates to be accurately transformed into longitude and latitude
+ * coordinates used by google maps. Largely adapted from the pymap3D library.
+ *
+ * @author Thomas Deppe
+ */
+public final class CoordinateTransform {
+
+ //Constants used in calculations
+ public static final double semimajor_axis = 6378137.0;
+ public static final double semiminor_axis = 6356752.31424518;
+ public static final double flattening = (semimajor_axis-semiminor_axis)/semimajor_axis;
+ public static final double eccentricity_squared = flattening * (2-flattening);
+
+ /**
+ * An empty constructor as this is a utility class no constructor is needed.
+ */
+ private CoordinateTransform(){
+ }
+
+ /**
+ * Converts WSG84 coordinates to Earth-Centered, Earth-Fixed (ECEF) coordinates.
+ *
+ * @param latitude The latitude of the coordinate to convert.
+ * @param longitude The longitude of the coordinate to convert.
+ * @param altitude The altitude of the coordinate to convert.
+ * @return The converted ECEF coordinates as a double array with X, Y, and Z coordinates.
+ */
+ public static double[] geodeticToEcef(double latitude, double longitude, double altitude){
+ double[] ecefCoords = new double[3];
+ double latRad = Math.toRadians(latitude);
+ double lngRad = Math.toRadians(longitude);
+
+ //Calculate Prime Vertical Radius of Curvature
+ double N = Math.pow(semimajor_axis,2) /
+ Math.hypot((semimajor_axis*Math.cos(latRad)), (semiminor_axis * Math.sin(latRad)));
+
+ ecefCoords[0] = (N + altitude) * Math.cos(latRad) * Math.cos(lngRad);
+ ecefCoords[1] = (N + altitude) * Math.cos(latRad) * Math.sin(lngRad);
+ ecefCoords[2] = (N * Math.pow((semiminor_axis / semimajor_axis),2) + altitude) * Math.sin(latRad);
+
+ return ecefCoords;
+ }
+
+ /**
+ * Converts Earth-Centered, Earth-Fixed (ECEF) coordinates to East-North-Up (ENU) coordinates
+ * relative to a reference point specified by latitude and longitude.
+ *
+ * @param east The east displacement in meters.
+ * @param north The north displacement in meters.
+ * @param up The altitude displacement in meters.
+ * @param refLatitude The reference point latitude.
+ * @param refLongitude The reference point longitude.
+ * @return A double array containing the East, North, and Up displacements in meters.
+ */
+ public static double[] ecefToENU(double east, double north, double up, double refLatitude, double refLongitude){
+ double[] enuCoords = new double[3];
+ double latRad = Math.toRadians(refLatitude);
+ double lngRad = Math.toRadians(refLongitude);
+
+ double t = Math.cos(lngRad) * east + Math.sin(lngRad) * north;
+ enuCoords[0] = -Math.sin(lngRad) * east + Math.cos(lngRad) * north;
+ enuCoords[2] = Math.cos(latRad)*t + Math.sin(latRad) * up;
+ enuCoords[1] = -Math.sin(latRad) *t + Math.cos(latRad) * up;
+
+ return enuCoords;
+ }
+
+ /**
+ * Converts ENU coordinates to ECEF coordinates from a reference point which is the users start location.
+ * The reference ECEF coordinates are calculated from the WSG84 coordinates.
+ *
+ * @param east The east displacement in meters
+ * @param north The north displacement in meters
+ * @param up The altitude in meters
+ * @param refLatitude The reference point latitude
+ * @param refLongitude the reference point longitude
+ * @param refAlt the reference point altitude
+ * @return a double array with the X, Y and Z coordinates
+ */
+ public static double[] enuToEcef(double east, double north, double up, double refLatitude, double refLongitude, double refAlt){
+ double[] calCoords = new double[3];
+ double[] ecefRefCoords = geodeticToEcef(refLatitude, refLongitude, refAlt);
+ double latRad = Math.toRadians(refLatitude);
+ double lngRad = Math.toRadians(refLongitude);
+
+ calCoords[0] = (Math.cos(lngRad) * (Math.cos(latRad)*up - Math.sin(latRad)*north) - Math.sin(lngRad)*east) + ecefRefCoords[0];
+ calCoords[1] = (Math.sin(lngRad)*(Math.cos(latRad)*up - Math.sin(latRad)*north) + Math.cos(lngRad)*east) + ecefRefCoords[1];
+ calCoords[2] = (Math.sin(latRad)*up + Math.cos(latRad)*north) + ecefRefCoords[2];
+
+ return calCoords;
+ }
+
+ /**
+ * An overloaded method the same as the previous, but with the ECEF reference coordinates already calculated
+ */
+ public static double[] enuToEcef(double east, double north, double up, double refLatitude, double refLongitude, double[] ecefRefCoords){
+ double[] calCoords = new double[3];
+ double latRad = Math.toRadians(refLatitude);
+ double lngRad = Math.toRadians(refLongitude);
+
+ calCoords[0] = (Math.cos(lngRad) * (Math.cos(latRad)*up - Math.sin(latRad)*north) - Math.sin(lngRad)*east) + ecefRefCoords[0];
+ calCoords[1] = (Math.sin(lngRad)*(Math.cos(latRad)*up - Math.sin(latRad)*north) + Math.cos(lngRad)*east) + ecefRefCoords[1];
+ calCoords[2] = (Math.sin(latRad)*up + Math.cos(latRad)*north) + ecefRefCoords[2];
+
+ return calCoords;
+ }
+
+ /**
+ * Converts the ECEF coordinates to WSG84 coordinates.
+ * @param ecefCoords The ECEF X, Y and Z coordinates
+ * @return the WSG84 coordiantes as a LatLng
+ */
+ public static LatLng ecefToGeodetic(double[] ecefCoords) {
+
+ double asq = Math.pow(semimajor_axis,2);
+ double bsq = Math.pow(semiminor_axis,2);
+
+ double ep = Math.sqrt((asq-bsq)/bsq);
+
+ double p = Math.sqrt(Math.pow(ecefCoords[0],2) + Math.pow(ecefCoords[1],2));
+
+ double th = Math.atan2(semimajor_axis *
+ ecefCoords[2], semiminor_axis * p);
+
+ double longitude = Math.atan2(ecefCoords[1],ecefCoords[0]);
+
+ double latitude = Math.atan2((ecefCoords[2] + Math.pow(ep,2) *
+ semiminor_axis * Math.pow(Math.sin(th),3)),
+ (p - eccentricity_squared*semimajor_axis*Math.pow(Math.cos(th),3)));
+
+ double N = semimajor_axis/
+ (Math.sqrt(1-eccentricity_squared*
+ Math.pow(Math.sin(latitude),2)));
+
+ double altitude = p / Math.cos(latitude) - N;
+ Log.d("UserLocation", "alt: "+altitude);
+
+ longitude = longitude % (2*Math.PI);
+
+ return new LatLng(toDegrees(latitude), toDegrees(longitude));
+ }
+
+ /**
+ * Converts the ENU coordiantes to WSG84 coordiantes.
+ * First the ENU coordinates have to be converted to ECEF and then they can be converted to WSG84.
+ * @param east The east displacement in meters
+ * @param north The north displacement in meters
+ * @param up The altitude in meters
+ * @param refLatitude The reference point latitude
+ * @param refLongitude the reference point longitude
+ * @param ecefRefCoords the ECEF reference coordinates
+ * @return LatLng of the converted coordinates.
+ */
+ public static LatLng enuToGeodetic(double east, double north, double up, double refLatitude, double refLongitude, double[] ecefRefCoords) {
+ double[] ecefCoords = enuToEcef(east, north, up, refLatitude, refLongitude, ecefRefCoords);
+
+ return ecefToGeodetic(ecefCoords);
+ }
+
+ /**
+ * An overloadden method similar to the previous, but the reference coordinates have not been calculated. They will be
+ * calculated.
+ */
+ public static LatLng enuToGeodetic(double east, double north, double up, double refLatitude, double refLongitude, double refAlt) {
+ double[] ecefCoords = enuToEcef(east, north, up, refLatitude, refLongitude, refAlt);
+ Log.d("ECEFCOORDS", "x: "+ecefCoords[0]+" y: "+ecefCoords[1]+" z: "+ecefCoords[2]);
+
+ return ecefToGeodetic(ecefCoords);
+ }
+
+ /**
+ * Converts geodetic coordinates (latitude, longitude, altitude) to East-North-Up (ENU) coordinates
+ * relative to a reference point specified by its geodetic coordinates.
+ *
+ * @param latitude The latitude of the point to convert.
+ * @param longitude The longitude of the point to convert.
+ * @param altitude The altitude of the point to convert.
+ * @param refLatitude The latitude of the reference point.
+ * @param refLongitude The longitude of the reference point.
+ * @param refAltitude The altitude of the reference point.
+ * @return A double array containing the East, North, and Up displacements in meters.
+ */
+ public static double[] geodeticToEnu(double latitude, double longitude, double altitude, double refLatitude, double refLongitude, double refAltitude){
+ double[] newPosition = geodeticToEcef(latitude, longitude, altitude);
+ double[] ecefRefCoords = geodeticToEcef(refLatitude, refLongitude, refAltitude);
+
+ return ecefToENU((newPosition[0]-ecefRefCoords[0]), (newPosition[1]-ecefRefCoords[1]), (newPosition[2]-ecefRefCoords[2]), refLatitude, refLongitude);
+ }
+
+ /**
+ * Helper method to convert radians to degrees.
+ * @param val The value to convert in degrees.
+ * @return The value in radians
+ */
+ public static double toDegrees(double val) {
+ return val * (180/Math.PI);
+ }
+
+}
diff --git a/app/src/main/java/com/openpositioning/PositionMe/Method/ExponentialSmoothingFilter.java b/app/src/main/java/com/openpositioning/PositionMe/Method/ExponentialSmoothingFilter.java
new file mode 100644
index 00000000..da173ee6
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/Method/ExponentialSmoothingFilter.java
@@ -0,0 +1,70 @@
+package com.openpositioning.PositionMe.Method;
+
+import java.util.Arrays;
+/**
+ * A class implementing an Exponential Smoothing Filter.
+ *
+ * This filter is used to smooth a sequence of values using exponential smoothing.
+ * It calculates a weighted average of current and past values, with the weight of each value determined by a smoothing factor alpha.
+ * A higher alpha value discounts older observations faster, giving more weight to recent observations.
+ *
+ * Smoothing is applied independently to each value in the sequence.
+ *
+ * @author Thomas Deppe
+ */
+public class ExponentialSmoothingFilter {
+
+ private final double alpha; // Smoothing factor between 0 and 1
+ private Double[] smoothedValues; // Stores the last smoothed value
+ private int valueCount; // The number of values to be smoothed
+
+ /**
+ * Constructor for the exponential smoothing filter.
+ *
+ * @param alpha The smoothing factor used, between 0 (no smoothing) and 1 (ignore all but the most recent value).
+ */
+ public ExponentialSmoothingFilter(double alpha, int valueCount) {
+ if (alpha < 0 || alpha > 1) {
+ throw new IllegalArgumentException("Alpha must be between 0 and 1");
+ }
+ if (valueCount <= 0) {
+ throw new IllegalArgumentException("Value count must be greater than 0");
+ }
+ this.alpha = alpha;
+ this.valueCount = valueCount;
+ this.smoothedValues = new Double[valueCount];
+ }
+
+ /**
+ * Applies exponential smoothing to new values.
+ *
+ * @param newValues An array containing the new values to be smoothed. Its length must match valueCount.
+ * @return An array containing the smoothed values.
+ */
+ public double[] applySmoothing(double[] newValues) {
+ if (newValues.length != valueCount) {
+ throw new IllegalArgumentException("The length of newValues must match valueCount");
+ }
+
+ for (int i = 0; i < valueCount; i++) {
+ if (smoothedValues[i] == null) {
+ // First value, just use it as is for initialization
+ smoothedValues[i] = newValues[i];
+ } else {
+ // Apply exponential smoothing formula
+ smoothedValues[i] = alpha * newValues[i] + (1 - alpha) * smoothedValues[i];
+ }
+ }
+
+ // Convert the Double array to double array for return
+ return Arrays.stream(smoothedValues).mapToDouble(Double::doubleValue).toArray();
+ }
+
+
+ /**
+ * Resets the filter, clearing the last smoothed value.
+ */
+ public void reset() {
+ Arrays.fill(smoothedValues, null);
+ }
+}
diff --git a/app/src/main/java/com/openpositioning/PositionMe/Method/OutlierDetector.java b/app/src/main/java/com/openpositioning/PositionMe/Method/OutlierDetector.java
new file mode 100644
index 00000000..4551c1fe
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/Method/OutlierDetector.java
@@ -0,0 +1,115 @@
+package com.openpositioning.PositionMe.Method;
+
+import android.util.Log;
+
+import java.util.ArrayList;
+import java.util.Collections;
+import java.util.List;
+
+/**
+ * Utility class for detecting outliers in a list of distances by employing the modified Z score.
+ *
+ * @author Thomas Deppe
+ * @author Alexandra Geciova
+ * @author Christopher Khoo
+ */
+public class OutlierDetector {
+ // Threshold for outlier detection
+ private static final double OUTLIER_THRESHOLD = 3.0;
+ // Factor for computing modified Z-score
+ private static final double Z_SCORE_FACTOR = 0.6745;
+ private static final double max_distance_threshold = 10;
+ // List to store distances
+ private final List distances;
+
+ /**
+ * Constructor to initialize the outlier detector.
+ */
+ public OutlierDetector() {
+ this.distances = new ArrayList<>();
+ }
+
+ /**
+ * Detects outliers in the provided distance.
+ *
+ * @param newDistance The new distance to check for outliers.
+ * @return True if an outlier is detected, false otherwise.
+ */
+ public boolean detectOutliers(double newDistance) {
+ // Add the new distance to the list
+ distances.add(newDistance);
+
+ if (newDistance > max_distance_threshold) {
+ return true;
+ }
+
+ // Calculate the median of distances
+ double median = calculateMedian();
+
+ // Calculate the Median Absolute Deviation (MAD)
+ double mad = calculateMAD(median);
+
+ // Calculate the modified Z-score
+ double modifiedZScore = Z_SCORE_FACTOR * ((Math.abs(newDistance - median)) / mad);
+
+ // Check if the modified Z-score exceeds the outlier threshold
+ if (modifiedZScore > OUTLIER_THRESHOLD) {
+ // Remove the outlier from the list
+ int index = distances.indexOf(newDistance);
+ distances.remove(index);
+ return true;
+ }
+
+ return false;
+ }
+
+ /**
+ * Calculates the median of distances.
+ *
+ * @return The median value.
+ */
+ private double calculateMedian() {
+ // Sort distances in order to determine median
+ Collections.sort(this.distances);
+
+ // calculate median based on length of list
+ int size = this.distances.size();
+ if (size % 2 != 0) {
+ return distances.get(size / 2);
+ } else {
+ return (distances.get((size - 1) / 2) + distances.get(size / 2)) / 2.0;
+ }
+ }
+
+ /**
+ * Calculates the Median Absolute Deviation (MAD) of distances.
+ *
+ * @param median The median value of distances.
+ * @return The MAD value.
+ */
+ private double calculateMAD(double median) {
+ List absoluteDeviations = new ArrayList<>();
+ for (double distance : distances) {
+ double deviation = Math.abs(distance - median);
+ absoluteDeviations.add(deviation);
+ }
+ return calculateMedian(absoluteDeviations);
+ }
+
+ /**
+ * Calculates the median of a list of absolute deviations.
+ *
+ * @param absoluteDeviations The list of absolute deviations.
+ * @return The median of absolute deviations.
+ */
+ private double calculateMedian(List absoluteDeviations) {
+ Collections.sort(absoluteDeviations);
+ int size = absoluteDeviations.size();
+ if (size % 2 != 0) {
+ return absoluteDeviations.get(size / 2);
+ } else {
+ return (absoluteDeviations.get((size - 1) / 2) + absoluteDeviations.get(size / 2)) / 2.0;
+ }
+ }
+}
+
diff --git a/app/src/main/java/com/openpositioning/PositionMe/Method/TurnDetector.java b/app/src/main/java/com/openpositioning/PositionMe/Method/TurnDetector.java
new file mode 100644
index 00000000..162e23a8
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/Method/TurnDetector.java
@@ -0,0 +1,124 @@
+package com.openpositioning.PositionMe.Method;
+
+import android.util.Log;
+
+/**
+ * This class represents a Turn Detector used for monitoring user movement based on orientation data.
+ * It detects turns and pseudo-turns and provides the corresponding movement type.
+ *
+ * @author Thomas Deppe
+ * @author Alexandra Geciova
+ * @author Christopher Khoo
+ */
+public class TurnDetector {
+ //Threshold to be classed as turn
+ private static final float TURN_THRESHOLD = 1.2f;
+ //Threshold for small orientation changes that are not indicative of a turn or straight
+ private static final float PSEUDO_TURN = 0.6f;
+ //The previous value
+ private float orientationPrev;
+ //Whether to start monitoring, to stop unnecessary computations
+ private boolean startMonitoring;
+ //The users movement
+ private MovementType userMovement;
+
+ // A enum storing the users movement type
+ public enum MovementType {
+ STRAIGHT,
+ PSEUDO_TURN,
+ TURN;
+
+ /**
+ * Compares this type with another type to determine if it should be updated
+ * based on specific rules. The rules are as follows:
+ * 1. If the current type is TURN, it remains unchanged.
+ * 2. If the current type is PSEUDO_TURN and the new type is TURN, update to TURN.
+ * 3. STRAIGHT updates to any type.
+ *
+ * @param newType The new type to compare with the current one.
+ * @return The updated type, or the current type if no update should be made according to the rules.
+ */
+ public MovementType compareAndUpdate(MovementType newType) {
+ if (this == TURN) {
+ // If the current type is TURN, it remains unchanged.
+ return this;
+ } else if (this == PSEUDO_TURN && newType == TURN) {
+ // Allows updating from PSEUDO_TURN to TURN.
+ return TURN;
+ } else if (this == PSEUDO_TURN && newType == STRAIGHT){
+ // If new type is STRAIGHT do not update PSEUDO_TURN.
+ return this;
+ }
+
+ // STRAIGHT updates to any type.
+ return newType;
+ }
+ }
+
+ /**
+ * Initializes a new TurnDetector instance.
+ * Sets the initial orientation and user movement type.
+ */
+ public TurnDetector() {
+ this.orientationPrev = 0;
+ this.userMovement = MovementType.STRAIGHT;
+ }
+
+ /**
+ * Processes orientation data to detect turns.
+ * Updates the user movement type based on the change in orientation.
+ *
+ * @param orientationUpdate The updated orientation value.
+ */
+ public void ProcessOrientationData(double orientationUpdate){
+ if (!this.startMonitoring) return;
+
+ float azimuthInDegrees = (float) (Math.toDegrees(orientationUpdate) + 360) % 360;
+ float azimuthChange = Math.abs(azimuthInDegrees - orientationPrev);
+ //double azimuthChange = wraptopi(Math.abs(orientationUpdate - orientationPrev));
+ if (azimuthChange > 180) {
+ azimuthChange = 360 - azimuthChange;
+ }
+
+ if (azimuthChange > TURN_THRESHOLD){
+ userMovement = userMovement.compareAndUpdate(MovementType.TURN);
+ } else if (azimuthChange > PSEUDO_TURN){
+ userMovement = userMovement.compareAndUpdate(MovementType.PSEUDO_TURN);
+ } else if (azimuthChange < PSEUDO_TURN){
+ userMovement = userMovement.compareAndUpdate(MovementType.STRAIGHT);
+ }
+
+ orientationPrev = azimuthInDegrees;
+ }
+
+ /**
+ * Processes a detected step event, updating the user movement type.
+ * Resets the user movement type to straight after processing.
+ *
+ * @param orientation The orientation at the time of the step event.
+ * @return The movement type detected for the step.
+ */
+ public MovementType onStepDetected(double orientation){
+ ProcessOrientationData(orientation);
+ MovementType resultForStep = this.userMovement;
+ Log.d("EKF", "OUTPUT from turn detector "+userMovement.toString());
+ this.userMovement = MovementType.STRAIGHT;
+ return resultForStep;
+ }
+
+ /**
+ * Starts monitoring orientation changes.
+ */
+ public void startMonitoring(){
+ this.startMonitoring = true;
+ }
+
+ /**
+ * Stops monitoring orientation changes and resets the user movement type to straight.
+ */
+ public void stopMonitoring(){
+ this.startMonitoring = false;
+ this.userMovement = MovementType.STRAIGHT;
+
+ }
+}
diff --git a/app/src/main/java/com/openpositioning/PositionMe/PathView.java b/app/src/main/java/com/openpositioning/PositionMe/PathView.java
new file mode 100644
index 00000000..cc8087ff
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/PathView.java
@@ -0,0 +1,247 @@
+package com.openpositioning.PositionMe;
+
+import android.content.Context;
+import android.graphics.Canvas;
+import android.graphics.Color;
+import android.graphics.Paint;
+import android.graphics.Path;
+import android.util.AttributeSet;
+import android.view.View;
+
+import com.openpositioning.PositionMe.fragments.CorrectionFragment;
+import com.openpositioning.PositionMe.sensors.SensorFusion;
+
+import java.util.ArrayList;
+import java.util.Collections;
+
+/**
+ * This View class displays the path taken in the UI.
+ * A path of straight lines is drawn based on PDR coordinates. The coordinates are passed to
+ * PathView by calling method {@link PathView#drawTrajectory(float[])} in {@link SensorFusion}.
+ * The coordinates are scaled and centered in {@link PathView#scaleTrajectory()} to fill the
+ * device's screen. The scaling ratio is passed to the {@link CorrectionFragment} for calculating
+ * the Google Maps zoom ratio.
+ *
+ * @author Michal Dvorak
+ * @author Virginia Cangelosi
+ */
+public class PathView extends View {
+ // Set up drawing colour
+ private final int paintColor = Color.BLUE;
+ // Defines paint and canvas
+ private Paint drawPaint;
+ // Path of straight lines
+ private Path path = new Path();
+ // Array lists of integers to store coordinates
+ private static ArrayList xCoords = new ArrayList();
+ private static ArrayList yCoords = new ArrayList();
+ // Scaling ratio for multiplying PDR coordinates to fill the screen size
+ private static float scalingRatio;
+ // Instantiate correction fragment for passing it the scaling ratio
+ private CorrectionFragment correctionFragment = new CorrectionFragment();
+ // Boolean flag to avoid rescaling trajectory when view is redrawn
+ private static boolean firstTimeOnDraw = true;
+ //Variable to only draw when the variable is true
+ private static boolean draw = true;
+ //Variable to only draw when the variable is true
+ private static boolean reDraw = false;
+
+ /**
+ * Public default constructor for PathView. The constructor initialises the view with a context
+ * and attribute set, sets the view as focusable and focusable in touch mode and calls
+ * {@link PathView#setupPaint()} to initialise the paint object with colour and style.
+ *
+ * @param context Application Context to be used for permissions and device accesses.
+ * @param attrs The attribute set of the view.
+ */
+ public PathView(Context context, AttributeSet attrs) {
+ super(context, attrs);
+ setFocusable(true);
+ setFocusableInTouchMode(true);
+ setupPaint();
+ }
+
+ /**
+ * Method used for setting up paint object for drawing the path with colour and stroke styles.
+ */
+ private void setupPaint() {
+ drawPaint = new Paint();
+ // Set the color of the paint object to paintColor
+ drawPaint.setColor(paintColor);
+ // Enable anti-aliasing to smooth out the edges of the lines
+ drawPaint.setAntiAlias(true);
+ // Set the width of path
+ drawPaint.setStrokeWidth(5);
+ // Set the style of path to be drawn
+ drawPaint.setStyle(Paint.Style.STROKE);
+ // Set the type of join to use between line segments
+ drawPaint.setStrokeJoin(Paint.Join.ROUND);
+ // Set the type of cap to use at the end of the line
+ drawPaint.setStrokeCap(Paint.Cap.ROUND);
+ }
+
+ /**
+ * {@inheritDoc}
+ *
+ * Method drawing the created path with our paint.
+ *
+ * @param canvas The canvas on which the path will be drawn
+ */
+ @Override
+ protected void onDraw(Canvas canvas) {
+ super.onDraw(canvas);
+ //If drawing for first time scale trajectory to fit screen
+ if(this.draw){
+ // If there are no coordinates, don't draw anything
+ if (xCoords.size() == 0)
+ return;
+
+ //Scale trajectory to fit screen
+ scaleTrajectory();
+
+ // Start a new path at the center of the view
+ path.moveTo(getWidth()/2, getHeight()/2);
+
+ // Draw line between last point and this point
+ for (int i = 1; i < xCoords.size(); i++) {
+ path.lineTo(xCoords.get(i), yCoords.get(i));
+ }
+
+ //Draw path
+ canvas.drawPath(path, drawPaint);
+
+ //Ensure path not redrawn
+ draw = false;
+
+ }
+ //If redrawing due to scaling of the average step length
+ else if(reDraw){
+ // If there are no coordinates, don't draw anything
+ if (xCoords.size() == 0)
+ return;
+
+ //Clear old path
+ path.reset();
+
+ // Iterate over all coordinates, shifting to the center and scaling then returning to original location
+ for (int i = 0; i < xCoords.size(); i++) {
+ float newXCoord = (xCoords.get(i) - getWidth()/2) * scalingRatio + getWidth()/2;
+ xCoords.set(i, newXCoord);
+ float newYCoord = (yCoords.get(i) - getHeight()/2) * scalingRatio + getHeight()/2;
+ yCoords.set(i, newYCoord);
+ }
+
+ // Start a new path at the center of the view
+ path.moveTo(getWidth()/2, getHeight()/2);
+
+ // Draw line between last point and this point
+ for (int i = 1; i < xCoords.size(); i++) {
+ path.lineTo(xCoords.get(i), yCoords.get(i));
+ }
+
+ canvas.drawPath(path, drawPaint);
+
+ //Ensure path not redrawn when screen is resized
+ reDraw = false;
+ }
+ else{
+
+ // If there are no coordinates, don't draw anything
+ if (xCoords.size() == 0)
+ return;
+
+ // Start a new path at the center of the view
+ path.moveTo(getWidth()/2, getHeight()/2);
+
+ // Draw line between last point and this point
+ for (int i = 1; i < xCoords.size(); i++) {
+ path.lineTo(xCoords.get(i), yCoords.get(i));
+ }
+
+ canvas.drawPath(path, drawPaint);
+ }
+ }
+
+ /**
+ * Method called from {@link SensorFusion} used for adding PDR coordinates to the path to be
+ * drawn.
+ *
+ * @param newCords An array containing the newly calculated coordinates to be added.
+ */
+ public void drawTrajectory(float[] newCords) {
+ // Add x coordinates
+ xCoords.add(newCords[0]);
+ // Negate the y coordinate and add it to the yCoords list, since screen coordinates
+ // start from top to bottom
+ yCoords.add(-newCords[1]);
+ }
+
+ /**
+ * Method used for scaling PDR coordinates to fill the screen.
+ * Center of the view is used as the origin, scaling ratio is calculated for the path to fit
+ * the screen with margins included.
+ */
+ private void scaleTrajectory() {
+ // Get the center coordinates of the view
+ int centerX = getWidth() / 2;
+ int centerY = getHeight() / 2;
+
+ // Calculate the scaling that would be required in each direction
+ float xRightRange = (getWidth() / 2) / (Math.abs(Collections.max(xCoords)));
+ float xLeftRange = (getWidth() / 2) / (Math.abs(Collections.min(xCoords)));
+ float yTopRange = (getHeight() / 2) / (Math.abs(Collections.max(yCoords)));
+ float yBottomRange = (getHeight() / 2) / (Math.abs(Collections.min(yCoords)));
+
+ // Take the minimum scaling ratio to ensure all points fit within the view
+ float minRatio = Math.min(Math.min(xRightRange, xLeftRange), Math.min(yTopRange, yBottomRange));
+
+ // Add margins to the scaling ratio
+ scalingRatio = 0.9f * minRatio;
+
+ // Limit scaling ratio to an equivalent of zoom of 21 in google maps
+ if (scalingRatio >= 23.926) {
+ scalingRatio = 23.926f;
+ }
+ System.out.println("Adjusted scaling ratio: " + scalingRatio);
+
+ // Set the scaling ratio for the correction fragment for setting Google Maps zoom
+ correctionFragment.setScalingRatio(scalingRatio);
+
+ // Iterate over all coordinates, shifting to the center and scaling
+ for (int i = 0; i < xCoords.size(); i++) {
+ float newXCoord = xCoords.get(i) * scalingRatio + centerX;
+ xCoords.set(i, newXCoord);
+ float newYCoord = yCoords.get(i) * scalingRatio + centerY;
+ yCoords.set(i, newYCoord);
+ }
+ }
+
+ /**
+ * Method called when PathView is detached from its window. {@link PathView#xCoords} and
+ * {@link PathView#yCoords} are cleared so that path can start from 0 for next recording.
+ */
+ @Override
+ protected void onDetachedFromWindow() {
+ super.onDetachedFromWindow();
+ // Reset trajectory
+ xCoords.clear();
+ yCoords.clear();
+ //New recording so must scale trajectory
+ draw = true;
+ }
+
+ /**
+ * Redraw trajectory to rescale the path.
+ * Called by {@link CorrectionFragment} through {@link SensorFusion} to reset the scaling ratio
+ * which will resize the path. It enables the redraw flag so new path is drawn.
+ *
+ * @param newScale
+ */
+ public void redraw(float newScale){
+ //Set scaling ratio based on user input
+ scalingRatio = newScale;
+ //Enable redrawing of path
+ reDraw = true;
+ }
+
+}
diff --git a/app/src/main/java/com/openpositioning/PositionMe/PdrProcessing.java b/app/src/main/java/com/openpositioning/PositionMe/PdrProcessing.java
new file mode 100644
index 00000000..2cc778ba
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/PdrProcessing.java
@@ -0,0 +1,405 @@
+package com.openpositioning.PositionMe;
+
+import android.content.Context;
+import android.content.SharedPreferences;
+import android.hardware.SensorManager;
+
+import androidx.preference.PreferenceManager;
+
+import android.util.Log;
+
+
+import com.openpositioning.PositionMe.sensors.SensorFusion;
+
+import java.util.Arrays;
+import java.util.Collections;
+import java.util.List;
+import java.util.OptionalDouble;
+
+/**
+ * Processes data recorded in the {@link SensorFusion} class and calculates live PDR estimates.
+ * It calculates the position from the steps and directions detected, using either estimated values
+ * (eg. stride length from the Weiberg algorithm) or provided constants, calculates the elevation
+ * and attempts to estimate the current floor as well as elevators.
+ *
+ * @author Mate Stodulka
+ * @author Michal Dvorak
+ */
+public class PdrProcessing {
+
+ //region Static variables
+ // Weiberg algorithm coefficient for stride calculations
+ private static final float K = 0.364f;
+ // Number of samples (seconds) to keep as memory for elevation calculation
+ private static final int elevationSeconds = 4;
+ // Number of samples (0.01 seconds)
+ private static final int accelSamples = 100;
+ // Threshold used to detect significant movement
+ private static final float movementThreshold = 0.3f; // m/s^2
+ // Threshold under which movement is considered non-existent
+ private static final float epsilon = 0.18f;
+ //endregion
+
+ //region Instance variables
+ // Settings for accessing shared variables
+ private SharedPreferences settings;
+
+ // Step length
+ private float stepLength;
+ // Using manually input constants instead of estimated values
+ private boolean useManualStep;
+
+ // Current 2D position coordinates
+ private float positionX;
+ private float positionY;
+
+ // Vertical movement calculation
+ private Float[] startElevationBuffer;
+ private float startElevation;
+ private int setupIndex = 0;
+ private float elevation;
+ private int floorHeight;
+ private int currentFloor;
+
+ // Buffer of most recent elevations calculated
+ private CircularFloatBuffer elevationList;
+
+ // Buffer for most recent directional acceleration magnitudes
+ private CircularFloatBuffer verticalAccel;
+ private CircularFloatBuffer horizontalAccel;
+
+ // Step sum and length aggregation variables
+ private float sumStepLength = 0;
+ private int stepCount = 0;
+
+ private static final String TAG = "PdrProcessing";
+
+ //endregion
+
+ /**
+ * Public constructor for the PDR class.
+ * Takes context for variable access. Sets initial values based on settings.
+ *
+ * @param context Application context for variable access.
+ */
+ public PdrProcessing(Context context) {
+ // Initialise settings
+ this.settings = PreferenceManager.getDefaultSharedPreferences(context);
+ // Check if estimate or manual values should be used
+ this.useManualStep = this.settings.getBoolean("manual_step_values", false);
+ if(useManualStep) {
+ try {
+ // Retrieve manual step length
+ this.stepLength = this.settings.getInt("user_step_length", 75) / 100f;
+ } catch (Exception e) {
+ // Invalid values - reset to defaults
+ this.stepLength = 0.75f;
+ this.settings.edit().putInt("user_step_length", 75).apply();
+ }
+ }
+ else {
+ // Using estimated step length - set to zero
+ this.stepLength = 0;
+ }
+
+ // Initial position and elevation - starts from zero
+ this.positionX = 0f;
+ this.positionY = 0f;
+ this.elevation = 0f;
+
+
+ if(this.settings.getBoolean("overwrite_constants", false)) {
+ // Capacity - pressure is read with 1Hz - store values of past 10 seconds
+ this.elevationList = new CircularFloatBuffer(Integer.parseInt(settings.getString("elevation_seconds", "4")));
+
+ // Buffer for most recent acceleration values
+ this.verticalAccel = new CircularFloatBuffer(Integer.parseInt(settings.getString("accel_samples", "4")));
+ this.horizontalAccel = new CircularFloatBuffer(Integer.parseInt(settings.getString("accel_samples", "4")));
+ }
+ else {
+ // Capacity - pressure is read with 1Hz - store values of past 10 seconds
+ this.elevationList = new CircularFloatBuffer(elevationSeconds);
+
+ // Buffer for most recent acceleration values
+ this.verticalAccel = new CircularFloatBuffer(accelSamples);
+ this.horizontalAccel = new CircularFloatBuffer(accelSamples);
+ }
+
+ // Distance between floors is building dependent, use manual value
+ this.floorHeight = settings.getInt("floor_height", 4);
+ // Array for holding initial values
+ this.startElevationBuffer = new Float[3];
+ // Start floor - assumed to be zero
+ this.currentFloor = 0;
+ }
+
+ /**
+ * Function to calculate PDR coordinates from sensor values.
+ * Should be called from the step detector sensor's event with the sensor values since the last
+ * step.
+ *
+ * @param currentStepEnd relative time in milliseconds since the start of the recording.
+ * @param accelMagnitudeOvertime recorded acceleration magnitudes since the last step.
+ * @param headingRad heading relative to magnetic north in radians.
+ */
+ public float[] updatePdr(long currentStepEnd, List accelMagnitudeOvertime, float headingRad) {
+
+ // Change angle so zero rad is east
+ float adaptedHeading = (float) (Math.PI/2 - headingRad);
+
+ // Calculate step length
+ if(!useManualStep) {
+ if(accelMagnitudeOvertime == null || accelMagnitudeOvertime.isEmpty()){
+ Log.w(TAG,"AccelMagnitude is null or empty");
+ this.stepLength =0.0f;
+ }
+ else {
+ //ArrayList accelMagnitudeFiltered = filter(accelMagnitudeOvertime);
+ // Estimate stride
+
+ this.stepLength = weibergMinMax(accelMagnitudeOvertime);
+ }
+ // System.err.println("Step Length" + stepLength);
+ }
+
+ // Increment aggregate variables
+ sumStepLength += stepLength;
+ stepCount++;
+
+ // Translate to cartesian coordinate system
+ float x = (float) (stepLength * Math.cos(adaptedHeading));
+ float y = (float) (stepLength * Math.sin(adaptedHeading));
+
+ // Update position values
+ this.positionX += x;
+ this.positionY += y;
+
+ // return current position
+ return new float[]{this.positionX, this.positionY};
+ }
+
+ /**
+ * Calculates the relative elevation compared to the start position.
+ * The start elevation is the median of the first three seconds of data to give the sensor time
+ * to settle. The sea level is irrelevant as only values relative to the initial position are
+ * reported.
+ *
+ * @param absoluteElevation absolute elevation in meters compared to sea level.
+ * @return current elevation in meters relative to the start position.
+ */
+ public float updateElevation(float absoluteElevation) {
+ // Set start to median of first three values
+ if(setupIndex < 3) {
+ // Add values to buffer until it's full
+ this.startElevationBuffer[setupIndex] = absoluteElevation;
+ // When buffer is full, find median, assign as startElevation
+ if(setupIndex == 2) {
+ Arrays.sort(startElevationBuffer);
+ startElevation = startElevationBuffer[1];
+ }
+ this.setupIndex++;
+ }
+ else {
+ // Get relative elevation in meters
+ this.elevation = absoluteElevation - startElevation;
+ // Add to buffer
+ this.elevationList.putNewest(absoluteElevation);
+
+ // Check if there was floor movement
+ // Check if there is enough data to evaluate
+ if(this.elevationList.isFull()) {
+ // Check average of elevation array
+ List elevationMemory = this.elevationList.getListCopy();
+ OptionalDouble currentAvg = elevationMemory.stream().mapToDouble(f -> f).average();
+ float finishAvg = currentAvg.isPresent() ? (float) currentAvg.getAsDouble() : 0;
+
+ // Check if we moved floor by comparing with start position
+ if(Math.abs(finishAvg - startElevation) > this.floorHeight) {
+ // Change floors - 'floor' division
+ this.currentFloor += (finishAvg - startElevation)/this.floorHeight;
+ }
+ }
+ // Return current elevation
+ return elevation;
+ }
+ // Keep elevation at zero if there is no calculated value
+ return 0;
+ }
+
+ /**
+ * Uses the Weiberg Stride Length formula to calculate step length from accelerometer values.
+ *
+ * @param accelMagnitude magnitude of acceleration values between the last and current step.
+ * @return float stride length in meters.
+ */
+ private float weibergMinMax(List accelMagnitude) {
+ if(accelMagnitude == null || accelMagnitude.isEmpty()) {
+ Log.w(TAG,"AccelMagnitude is null or empty");
+ return 0.0f;
+ }
+ double maxAccel = Collections.max(accelMagnitude);
+ double minAccel = Collections.min(accelMagnitude);
+ float bounce = (float) Math.pow((maxAccel-minAccel), 0.25);
+ if(this.settings.getBoolean("overwrite_constants", false)) {
+ return bounce * Float.parseFloat(settings.getString("weiberg_k", "0.934")) * 2;
+ }
+ return bounce*K*2;
+ }
+
+ /**
+ * Get the current X and Y coordinates from the PDR processing class.
+ * The coordinates are in meters, the start of the recording is the (0,0)
+ *
+ * @return float array of size 2, with the X and Y coordinates respectively.
+ */
+ public float[] getPDRMovement() {
+ float [] pdrPosition= new float[] {positionX,positionY};
+ return pdrPosition;
+
+ }
+
+ /**
+ * Get the current elevation as calculated by the PDR class.
+ *
+ * @return current elevation in meters, relative to the start position.
+ */
+ public float getCurrentElevation() {
+ return this.elevation;
+ }
+
+ /**
+ * Get the current floor number as estimated by the PDR class.
+ *
+ * @return current floor number, assuming start position is on level zero.
+ */
+ public int getCurrentFloor() {
+ return this.currentFloor;
+ }
+
+ /**
+ * Estimates if the user is currently taking an elevator.
+ * From the gravity and gravity-removed acceleration values the magnitude of horizontal and
+ * vertical acceleration is calculated and stored over time. Averaging these values and
+ * comparing with the thresholds set for this class, it estimates if the current movement
+ * matches what is expected from an elevator ride.
+ *
+ * @param gravity array of size three, strength of gravity along the phone's x-y-z axis.
+ * @param acc array of size three, acceleration other than gravity detected by the phone.
+ * @return boolean true if currently in an elevator, false otherwise.
+ */
+ public boolean estimateElevator(float[] gravity, float[] acc) {
+ // Standard gravity
+ float g = SensorManager.STANDARD_GRAVITY;
+ // get horizontal and vertical acceleration magnitude
+ float verticalAcc = (float) Math.sqrt(
+ Math.pow((acc[0] * gravity[0]/g),2) +
+ Math.pow((acc[1] * gravity[1]/g), 2) +
+ Math.pow((acc[2] * gravity[2]/g), 2));
+ float horizontalAcc = (float) Math.sqrt(
+ Math.pow((acc[0] * (1 - gravity[0]/g)), 2) +
+ Math.pow((acc[1] * (1 - gravity[1]/g)), 2) +
+ Math.pow((acc[2] * (1 - gravity[2]/g)), 2));
+ // Save into buffer to compare with past values
+ this.verticalAccel.putNewest(verticalAcc);
+ this.horizontalAccel.putNewest(horizontalAcc);
+ // Once buffer is full, evaluate data
+ if(this.verticalAccel.isFull() && this.horizontalAccel.isFull()) {
+
+ // calculate average vertical accel
+ List verticalMemory = this.verticalAccel.getListCopy();
+ OptionalDouble optVerticalAvg = verticalMemory.stream().mapToDouble(Math::abs).average();
+ float verticalAvg = optVerticalAvg.isPresent() ? (float) optVerticalAvg.getAsDouble() : 0;
+
+
+ // calculate average horizontal accel
+ List horizontalMemory = this.horizontalAccel.getListCopy();
+ OptionalDouble optHorizontalAvg = horizontalMemory.stream().mapToDouble(Math::abs).average();
+ float horizontalAvg = optHorizontalAvg.isPresent() ? (float) optHorizontalAvg.getAsDouble() : 0;
+
+ //System.err.println("LIFT: Vertical: " + verticalAvg);
+ //System.err.println("LIFT: Horizontal: " + horizontalAvg);
+
+ if(this.settings.getBoolean("overwrite_constants", false)) {
+ float eps = Float.parseFloat(settings.getString("epsilon", "0.18"));
+ return horizontalAvg < eps && verticalAvg > movementThreshold;
+ }
+ // Check if there is minimal horizontal and significant vertical movement
+ return horizontalAvg < epsilon && verticalAvg > movementThreshold;
+ }
+ return false;
+
+ }
+
+ /**
+ * Resets all values stored in the PDR function and re-initialises all buffers.
+ * Used to reset to zero position and remove existing history.
+ */
+ public void resetPDR() {
+ // Check if estimate or manual values should be used
+ this.useManualStep = this.settings.getBoolean("manual_step_values", false);
+ if(useManualStep) {
+ try {
+ // Retrieve manual step length
+ this.stepLength = this.settings.getInt("user_step_length", 75) / 100f;
+ } catch (Exception e) {
+ // Invalid values - reset to defaults
+ this.stepLength = 0.75f;
+ this.settings.edit().putInt("user_step_length", 75).apply();
+ }
+ }
+ else {
+ // Using estimated step length - set to zero
+ this.stepLength = 0;
+ }
+
+ // Initial position and elevation - starts from zero
+ this.positionX = 0f;
+ this.positionY = 0f;
+ this.elevation = 0f;
+
+ if(this.settings.getBoolean("overwrite_constants", false)) {
+ // Capacity - pressure is read with 1Hz - store values of past 10 seconds
+ this.elevationList = new CircularFloatBuffer(Integer.parseInt(settings.getString("elevation_seconds", "4")));
+
+ // Buffer for most recent acceleration values
+ this.verticalAccel = new CircularFloatBuffer(Integer.parseInt(settings.getString("accel_samples", "4")));
+ this.horizontalAccel = new CircularFloatBuffer(Integer.parseInt(settings.getString("accel_samples", "4")));
+ }
+ else {
+ // Capacity - pressure is read with 1Hz - store values of past 10 seconds
+ this.elevationList = new CircularFloatBuffer(elevationSeconds);
+
+ // Buffer for most recent acceleration values
+ this.verticalAccel = new CircularFloatBuffer(accelSamples);
+ this.horizontalAccel = new CircularFloatBuffer(accelSamples);
+ }
+
+ // Distance between floors is building dependent, use manual value
+ this.floorHeight = settings.getInt("floor_height", 4);
+ // Array for holding initial values
+ this.startElevationBuffer = new Float[3];
+ // Start floor - assumed to be zero
+ this.currentFloor = 0;
+ }
+
+ /**
+ * Getter for the average step length calculated from the aggregated distance and step count.
+ *
+ * @return average step length in meters.
+ */
+ public float getAverageStepLength(){
+ //Calculate average step length
+ if (stepCount == 0) {
+ return 0f;
+ }
+ float averageStepLength = sumStepLength/(float) stepCount;
+
+ //Reset sum and number of steps
+ stepCount = 0;
+ sumStepLength = 0;
+
+ //Return average step length
+ return averageStepLength;
+ }
+
+}
diff --git a/app/src/main/java/com/openpositioning/PositionMe/ServerCommunications.java b/app/src/main/java/com/openpositioning/PositionMe/ServerCommunications.java
new file mode 100644
index 00000000..12fad20c
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/ServerCommunications.java
@@ -0,0 +1,528 @@
+package com.openpositioning.PositionMe;
+
+import android.content.Context;
+import android.content.SharedPreferences;
+import android.net.ConnectivityManager;
+import android.net.NetworkInfo;
+import android.os.Handler;
+import android.os.Looper;
+import android.widget.Toast;
+
+import androidx.preference.PreferenceManager;
+
+import com.google.protobuf.util.JsonFormat;
+import com.openpositioning.PositionMe.fragments.FilesFragment;
+import com.openpositioning.PositionMe.sensors.Observable;
+import com.openpositioning.PositionMe.sensors.Observer;
+
+import java.io.ByteArrayOutputStream;
+import java.io.File;
+import java.io.FileOutputStream;
+import java.io.FileWriter;
+import java.io.IOException;
+import java.io.InputStream;
+import java.text.SimpleDateFormat;
+import java.util.ArrayList;
+import java.util.Date;
+import java.util.List;
+import java.util.zip.ZipInputStream;
+
+import okhttp3.Call;
+import okhttp3.Headers;
+import okhttp3.MediaType;
+import okhttp3.MultipartBody;
+import okhttp3.OkHttpClient;
+import okhttp3.RequestBody;
+import okhttp3.Response;
+import okhttp3.ResponseBody;
+
+/**
+ * This class handles communications with the server through HTTPs. The class uses an
+ * {@link OkHttpClient} for making requests to the server. The class includes methods for sending
+ * a recorded trajectory, uploading locally-stored trajectories, downloading trajectories from the
+ * server and requesting information about the uploaded trajectories.
+ *
+ * Keys and URLs are hardcoded strings, given the simple and academic nature of the project.
+ *
+ * @author Michal Dvorak
+ * @author Mate Stodulka
+ */
+//这个用来通信
+public class ServerCommunications implements Observable {
+
+ // Application context for handling permissions and devices
+ private final Context context;
+ // Network status checking
+ private ConnectivityManager connMgr;
+ private boolean isWifiConn;
+ private boolean isMobileConn;
+ private SharedPreferences settings;
+
+ private String infoResponse;
+ private boolean success;
+ private List observers;
+
+ // Static constants necessary for communications
+ private static final String userKey = BuildConfig.OPENPOSITIONING_API_KEY;
+ private static final String masterKey = BuildConfig.OPENPOSITIONING_MASTER_KEY;
+ private static final String uploadURL =
+ "https://openpositioning.org/api/live/trajectory/upload/" + userKey
+ + "/?key=" + masterKey;
+ private static final String downloadURL =
+ "https://openpositioning.org/api/live/trajectory/download/" + userKey
+ + "?skip=0&limit=30&key=" + masterKey;
+ private static final String infoRequestURL =
+ "https://openpositioning.org/api/live/users/trajectories/" + userKey
+ + "?key=" + masterKey;
+ private static final String PROTOCOL_CONTENT_TYPE = "multipart/form-data";
+ private static final String PROTOCOL_ACCEPT_TYPE = "application/json";
+
+
+
+ /**
+ * Public default constructor of {@link ServerCommunications}. The constructor saves context,
+ * initialises a {@link ConnectivityManager}, {@link Observer} and gets the user preferences.
+ * Boolean variables storing WiFi and Mobile Data connection status are initialised to false.
+ *
+ * @param context application context for handling permissions and devices.
+ */
+ public ServerCommunications(Context context) {
+ this.context = context;
+ this.connMgr = (ConnectivityManager) context.getSystemService(Context.CONNECTIVITY_SERVICE);
+ this.settings = PreferenceManager.getDefaultSharedPreferences(context);
+ this.isWifiConn = false;
+ this.isMobileConn = false;
+ checkNetworkStatus();
+
+ this.observers = new ArrayList<>();
+ }
+
+ /**
+ * Outgoing communication request with a {@link Traj trajectory} object. The recorded
+ * trajectory is passed to the method. It is processed into the right format for sending
+ * to the API server.
+ *
+ * @param trajectory Traj object matching all the timing and formal restrictions.
+ */
+ public void sendTrajectory(Traj.Trajectory trajectory){
+
+ // Convert the trajectory to byte array
+ byte[] binaryTrajectory = trajectory.toByteArray();
+
+ // Get the directory path for storing the file with the trajectory
+ File path = context.getFilesDir();
+
+ // Format the file name according to date
+ SimpleDateFormat dateFormat = new SimpleDateFormat("dd-MM-yy-HH-mm-ss");
+ Date date = new Date();
+ File file = new File(path, "trajectory_" + dateFormat.format(date) + ".txt");
+
+ try {
+ // Write the binary data to the file
+ FileOutputStream stream = new FileOutputStream(file);
+ stream.write(binaryTrajectory);
+ stream.close();
+ System.out.println("Recorded binary trajectory for debugging stored in: " + path);
+ } catch (IOException ee) {
+ // Catch and print if writing to the file fails
+ System.err.println("Storing of recorded binary trajectory failed: " + ee.getMessage());
+ }
+
+ // Check connections available before sending data
+ checkNetworkStatus();
+
+ // Check if user preference allows for syncing with mobile data
+ // TODO: add sync delay and enforce settings
+ boolean enableMobileData = this.settings.getBoolean("mobile_sync", false);
+ // Check if device is connected to WiFi or to mobile data with enabled preference
+ if(this.isWifiConn || (enableMobileData && isMobileConn)) {
+ // Instantiate client for HTTP requests
+ OkHttpClient client = new OkHttpClient();
+
+ // Creaet a equest body with a file to upload in multipart/form-data format
+ RequestBody requestBody = new MultipartBody.Builder().setType(MultipartBody.FORM)
+ .addFormDataPart("file", file.getName(),
+ RequestBody.create(MediaType.parse("text/plain"), file))
+ .build();
+
+ // Create a POST request with the required headers
+ okhttp3.Request request = new okhttp3.Request.Builder().url(uploadURL).post(requestBody)
+ .addHeader("accept", PROTOCOL_ACCEPT_TYPE)
+ .addHeader("Content-Type", PROTOCOL_CONTENT_TYPE).build();
+
+ // Enqueue the request to be executed asynchronously and handle the response
+ client.newCall(request).enqueue(new okhttp3.Callback() {
+
+ // Handle failure to get response from the server
+ @Override public void onFailure(Call call, IOException e) {
+ e.printStackTrace();
+ System.err.println("Failure to get response");
+ // Delete the local file and set success to false
+ //file.delete();
+ success = false;
+ notifyObservers(1);
+ }
+
+ // Process the server's response
+ @Override public void onResponse(Call call, Response response) throws IOException {
+ try (ResponseBody responseBody = response.body()) {
+ // If the response is unsuccessful, delete the local file and throw an
+ // exception
+ if (!response.isSuccessful()) {
+ //file.delete();
+// System.err.println("POST error response: " + responseBody.string());
+
+ String errorBody = responseBody.string();
+ infoResponse = "Upload failed: " + errorBody;
+ new Handler(Looper.getMainLooper()).post(() -> Toast.makeText(context, infoResponse, Toast.LENGTH_SHORT).show());//show error message to users
+
+ System.err.println("POST error response: " + errorBody);
+ success = false;
+ notifyObservers(1);
+ throw new IOException("Unexpected code " + response);
+ }
+
+ // Print the response headers
+ Headers responseHeaders = response.headers();
+ for (int i = 0, size = responseHeaders.size(); i < size; i++) {
+ System.out.println(responseHeaders.name(i) + ": " + responseHeaders.value(i));
+ }
+ // Print a confirmation of a successful POST to API
+ System.out.println("Successful post response: " + responseBody.string());
+
+ // Delete local file and set success to true
+ success = file.delete();
+ notifyObservers(1);
+ }
+ }
+ });
+ }
+ else {
+ // If the device is not connected to network or allowed to send, do not send trajectory
+ // and notify observers and user
+ System.err.println("No uploading allowed right now!");
+ success = false;
+ notifyObservers(1);
+ }
+
+ }
+
+ /**
+ * Uploads a local trajectory file to the API server in the specified format.
+ * {@link okhttp3.OkHttp} library is used for the asynchronous POST request.
+ *
+ * @param localTrajectory the File object of the local trajectory to be uploaded
+ */
+ public void uploadLocalTrajectory(File localTrajectory) {
+ // Instantiate client for HTTP requests
+ OkHttpClient client = new OkHttpClient();
+
+ // Create request body with a file to upload in multipart/form-data format
+ RequestBody requestBody = new MultipartBody.Builder().setType(MultipartBody.FORM)
+ .addFormDataPart("file", localTrajectory.getName(),
+ RequestBody.create(MediaType.parse("text/plain"), localTrajectory))
+ .build();
+
+ // Create a POST request with the required headers
+ okhttp3.Request request = new okhttp3.Request.Builder().url(uploadURL).post(requestBody)
+ .addHeader("accept", PROTOCOL_ACCEPT_TYPE)
+ .addHeader("Content-Type", PROTOCOL_CONTENT_TYPE).build();
+
+ // Enqueue the request to be executed asynchronously and handle the response
+ client.newCall(request).enqueue(new okhttp3.Callback() {
+ @Override public void onFailure(Call call, IOException e) {
+ // Print error message, set success to false and notify observers
+ e.printStackTrace();
+// localTrajectory.delete();
+ success = false;
+ System.err.println("UPLOAD: Failure to get response");
+ notifyObservers(1);
+ infoResponse = "Upload failed: " + e.getMessage(); // Store error message
+ new Handler(Looper.getMainLooper()).post(() -> Toast.makeText(context, infoResponse, Toast.LENGTH_SHORT).show());//show error message to users
+ }
+
+ @Override public void onResponse(Call call, Response response) throws IOException {
+ try (ResponseBody responseBody = response.body()) {
+ if (!response.isSuccessful()) {
+ // Print error message, set success to false and throw an exception
+ success = false;
+// System.err.println("UPLOAD unsuccessful: " + responseBody.string());
+ notifyObservers(1);
+// localTrajectory.delete();
+ String errorBody = responseBody.string();
+ System.err.println("UPLOAD unsuccessful: " + errorBody);
+ infoResponse = "Upload failed: " + errorBody;
+ new Handler(Looper.getMainLooper()).post(() -> Toast.makeText(context, infoResponse, Toast.LENGTH_SHORT).show());
+ throw new IOException("UPLOAD failed with code " + response);
+ }
+
+ // Print the response headers
+ Headers responseHeaders = response.headers();
+ for (int i = 0, size = responseHeaders.size(); i < size; i++) {
+ System.out.println(responseHeaders.name(i) + ": " + responseHeaders.value(i));
+ }
+
+ // Print a confirmation of a successful POST to API
+ System.out.println("UPLOAD SUCCESSFUL: " + responseBody.string());
+
+ // Delete local file, set success to true and notify observers
+ success = localTrajectory.delete();
+ notifyObservers(1);
+ }
+ }
+ });
+ }
+
+ /**
+ * Perform API request for downloading a Trajectory uploaded to the server. The trajectory is
+ * retrieved from a zip file, with the method accepting a position argument specifying the
+ * trajectory to be downloaded. The trajectory is then converted to a protobuf object and
+ * then to a JSON string to be downloaded to the device's Downloads folder.
+ *
+ * @param position the position of the trajectory in the zip file to retrieve
+ */
+ public void downloadTrajectoryToTempFile(int position, TrajectoryFileCallback callback) {
+ // 初始化 OkHttp 客户端
+ OkHttpClient client = new OkHttpClient();
+
+ // 构造 GET 请求,使用 downloadURL 常量
+ okhttp3.Request request = new okhttp3.Request.Builder()
+ .url(downloadURL)
+ .addHeader("accept", PROTOCOL_ACCEPT_TYPE)
+ .get()
+ .build();
+
+ // 异步执行请求
+ client.newCall(request).enqueue(new okhttp3.Callback() {
+ @Override
+ public void onFailure(Call call, IOException e) {
+ e.printStackTrace();
+ // 在主线程中通知回调出错
+ new Handler(Looper.getMainLooper()).post(() -> {
+ callback.onError(e.getMessage());
+ });
+ }
+
+ @Override
+ public void onResponse(Call call, Response response) throws IOException {
+ try (ResponseBody responseBody = response.body()) {
+ if (!response.isSuccessful()) {
+ throw new IOException("Unexpected code " + response);
+ }
+
+ // 从响应获取输入流
+ InputStream inputStream = responseBody.byteStream();
+ // 使用 ZipInputStream 处理返回的 zip 数据
+ ZipInputStream zipInputStream = new ZipInputStream(inputStream);
+ java.util.zip.ZipEntry zipEntry;
+ int zipCount = 0;
+ // 遍历 zip 条目,直到找到指定位置的轨迹
+ while ((zipEntry = zipInputStream.getNextEntry()) != null) {
+ if (zipCount == position) {
+ break;
+ }
+ zipCount++;
+ }
+ if (zipEntry == null) {
+ throw new IOException("No zip entry found at position: " + position);
+ }
+
+ // 在缓存目录中创建一个临时文件用于保存下载的数据
+ File tempFile = new File(context.getCacheDir(), "temp_downloaded_trajectory.txt");
+ try (FileOutputStream fos = new FileOutputStream(tempFile)) {
+ byte[] buffer = new byte[1024];
+ int bytesRead;
+ while ((bytesRead = zipInputStream.read(buffer)) != -1) {
+ fos.write(buffer, 0, bytesRead);
+ }
+ }
+ // 关闭输入流
+ zipInputStream.close();
+ inputStream.close();
+
+ // 在主线程中调用回调,传递临时文件的引用
+ new Handler(Looper.getMainLooper()).post(() -> {
+ callback.onFileReady(tempFile);
+ });
+ } catch (Exception e) {
+ e.printStackTrace();
+ new Handler(Looper.getMainLooper()).post(() -> {
+ callback.onError(e.getMessage());
+ });
+ }
+ }
+ });
+ }
+
+ public void downloadTrajectory(int position) {
+ // Initialise OkHttp client
+ OkHttpClient client = new OkHttpClient();
+
+ // Create GET request with required header
+ okhttp3.Request request = new okhttp3.Request.Builder()
+ .url(downloadURL)
+ .addHeader("accept", PROTOCOL_ACCEPT_TYPE)
+ .get()
+ .build();
+
+ // Enqueue the GET request for asynchronous execution
+ client.newCall(request).enqueue(new okhttp3.Callback() {
+ @Override public void onFailure(Call call, IOException e) {
+ e.printStackTrace();
+ }
+
+ @Override public void onResponse(Call call, Response response) throws IOException {
+ try (ResponseBody responseBody = response.body()) {
+ if (!response.isSuccessful()) throw new IOException("Unexpected code "
+ + response);
+
+ // Create input streams to process the response
+ InputStream inputStream = responseBody.byteStream();
+ ZipInputStream zipInputStream = new ZipInputStream(inputStream);
+
+ // Get the nth entry in the zip file
+ java.util.zip.ZipEntry zipEntry;
+ int zipCount = 0;
+ while ((zipEntry = zipInputStream.getNextEntry()) != null) {
+ if (zipCount == position) {
+ // break if zip entry position matches the desired position
+ break;
+ }
+ zipCount++;
+ }
+
+ // Initialise a byte array output stream
+ ByteArrayOutputStream byteArrayOutputStream = new ByteArrayOutputStream();
+
+ // Read the zipped data and write it to the byte array output stream
+ byte[] buffer = new byte[1024];
+ int bytesRead;
+ while ((bytesRead = zipInputStream.read(buffer)) != -1) {
+ byteArrayOutputStream.write(buffer, 0, bytesRead);
+ }
+
+ // Convert the byte array to a protobuf object
+ byte[] byteArray = byteArrayOutputStream.toByteArray();
+ Traj.Trajectory receivedTrajectory = Traj.Trajectory.parseFrom(byteArray);
+
+ // Convert the protobuf object to a string
+ JsonFormat.Printer printer = JsonFormat.printer();
+ String receivedTrajectoryString = printer.print(receivedTrajectory);
+ System.out.println("Successful download: "
+ + receivedTrajectoryString.substring(0, 100));
+
+ // Save the received trajectory to a file in the Downloads folder
+ //String storagePath = Environment.getExternalStoragePublicDirectory(Environment
+ // .DIRECTORY_DOWNLOADS).toString();
+ String storagePath = context.getFilesDir().toString();
+
+ File file = new File(storagePath, "received_trajectory.txt");
+ try (FileWriter fileWriter = new FileWriter(file)) {
+ fileWriter.write(receivedTrajectoryString);
+ fileWriter.flush();
+ System.err.println("Received trajectory stored in: " + storagePath);
+ } catch (IOException ee) {
+ System.err.println("Trajectory download failed");
+ } finally {
+ // Close all streams and entries to release resources
+ zipInputStream.closeEntry();
+ byteArrayOutputStream.close();
+ zipInputStream.close();
+ inputStream.close();
+ }
+ }
+ }
+ });
+
+ }
+
+ /**
+ * API request for information about submitted trajectories. If the response is successful,
+ * the {@link ServerCommunications#infoResponse} field is updated and observes notified.
+ *
+ */
+ public void sendInfoRequest() {
+ // Create a new OkHttpclient
+ OkHttpClient client = new OkHttpClient();
+
+ // Create GET info request with appropriate URL and header
+ okhttp3.Request request = new okhttp3.Request.Builder()
+ .url(infoRequestURL)
+ .addHeader("accept", PROTOCOL_ACCEPT_TYPE)
+ .get()
+ .build();
+
+ // Enqueue the GET request for asynchronous execution
+ client.newCall(request).enqueue(new okhttp3.Callback() {
+ @Override public void onFailure(Call call, IOException e) {
+ e.printStackTrace();
+ }
+
+ @Override public void onResponse(Call call, Response response) throws IOException {
+ try (ResponseBody responseBody = response.body()) {
+ // Check if the response is successful
+ if (!response.isSuccessful()) throw new IOException("Unexpected code " +
+ response);
+
+ // Get the requested information from the response body and save it in a string
+ // TODO: add printing to the screen somewhere
+ infoResponse = responseBody.string();
+ // Print a message in the console and notify observers
+ System.out.println("Response received");
+ notifyObservers(0);// 触发所有注册的 observer 调用 update()
+ }
+ }
+ });
+ }
+
+ /**
+ * This method checks the device's connection status. It sets boolean variables depending on
+ * the type of active network connection.
+ */
+ private void checkNetworkStatus() {
+ // Get active network information
+ NetworkInfo activeInfo = connMgr.getActiveNetworkInfo();
+
+ // Check for active connection and set flags accordingly
+ if (activeInfo != null && activeInfo.isConnected()) {
+ isWifiConn = activeInfo.getType() == ConnectivityManager.TYPE_WIFI;
+ isMobileConn = activeInfo.getType() == ConnectivityManager.TYPE_MOBILE;
+ } else {
+ isWifiConn = false;
+ isMobileConn = false;
+ }
+ }
+
+ /**
+ * {@inheritDoc}
+ *
+ * Implement default method from Observable Interface to add new observers to the list of
+ * registered observers.
+ *
+ * @param o Classes which implement the Observer interface to receive updates from the class.
+ */
+ @Override
+ public void registerObserver(Observer o) {
+ this.observers.add(o);
+ }
+
+ /**
+ * {@inheritDoc}
+ *
+ * Method for notifying all registered observers. The observer is notified based on the index
+ * passed to the method.
+ *
+ * @param index Index for identifying the observer to be notified.
+ */
+ @Override
+ public void notifyObservers(int index) {
+ for(Observer o : observers) {
+ if(index == 0 && o instanceof FilesFragment) {
+ o.update(new String[] {infoResponse});
+ }
+ else if (index == 1 && o instanceof MainActivity) {
+ o.update(new Boolean[] {success});
+ }
+ }
+ }
+}
diff --git a/app/src/main/java/com/openpositioning/PositionMe/TrajectoryFileCallback.java b/app/src/main/java/com/openpositioning/PositionMe/TrajectoryFileCallback.java
new file mode 100644
index 00000000..06d4e71e
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/TrajectoryFileCallback.java
@@ -0,0 +1,20 @@
+package com.openpositioning.PositionMe; // 或者放到你喜欢的合适包下
+
+import java.io.File;
+
+public interface TrajectoryFileCallback {
+ /**
+ * 当临时文件准备好时调用
+ * @param file 临时文件,包含下载的轨迹数据
+ */
+ void onFileReady(File file);
+
+
+
+ /**
+ * 当发生错误时调用
+ * @param errorMessage 错误信息
+ */
+ void onError(String errorMessage);
+}
+
diff --git a/app/src/main/java/com/openpositioning/PositionMe/UtilFunctions.java b/app/src/main/java/com/openpositioning/PositionMe/UtilFunctions.java
new file mode 100644
index 00000000..5a0729fc
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/UtilFunctions.java
@@ -0,0 +1,98 @@
+package com.openpositioning.PositionMe;
+
+import android.content.Context;
+import android.graphics.Bitmap;
+import android.graphics.Canvas;
+import android.graphics.drawable.Drawable;
+
+import androidx.core.content.ContextCompat;
+
+import com.google.android.gms.maps.model.LatLng;
+
+import kotlin.text.MatchGroup;
+
+/**
+ * Class containing utility functions which can used by other classes.
+ * @see com.openpositioning.PositionMe.fragments.RecordingFragment Currently used by RecordingFragment
+ */
+public class UtilFunctions {
+ // Constant 1degree of latitiude/longitude (in m)
+ private static final int DEGREE_IN_M=111111;
+ /**
+ * Simple function to calculate the angle between two close points
+ * @param pointA Starting point
+ * @param pointB Ending point
+ * @return Angle between the points
+ */
+ public static double calculateAngleSimple(LatLng pointA, LatLng pointB) {
+ // Simple formula for close-by points
+ return Math.toDegrees( Math.atan2(pointB.latitude-pointA.latitude,
+ (pointB.longitude- pointA.longitude)*Math.cos(Math.toRadians(pointA.latitude))));
+ }
+
+ /**
+ * Calculate new coordinates based on net distance moved in PDR
+ * (as per WGS84 datum)
+ * @param initialLocation Current Location of user
+ * @param pdrMoved Amount of movement along X and Y
+ * @return new Coordinates based on the movement
+ */
+ public static LatLng calculateNewPos(LatLng initialLocation,float[] pdrMoved){
+ // Changes Euclidean movement into maps latitude and longitude as per WGS84 datum
+ double newLatitude=initialLocation.latitude+(pdrMoved[1]/(DEGREE_IN_M));
+ double newLongitude=initialLocation.longitude+(pdrMoved[0]/(DEGREE_IN_M))
+ *Math.cos(Math.toRadians(initialLocation.latitude));
+ return new LatLng(newLatitude, newLongitude);
+ }
+ /**
+ * Converts a degree value of Latitude into meters
+ * (as per WGS84 datum)
+ * @param degreeVal Value in degrees to convert to meters
+ * @return double corresponding to the value in meters.
+ */
+ public static double degreesToMetersLat(double degreeVal) {
+ return degreeVal*DEGREE_IN_M;
+ }
+ /**
+ * Converts a degree value of Longitude into meters
+ * (as per WGS84 datum)
+ * @param degreeVal Value in degrees to convert to meters
+ * @param latitude the latitude of the current position
+ * @return double corresponding to the value in meters.
+ */
+ public static double degreesToMetersLng(double degreeVal, double latitude) {
+ return degreeVal*DEGREE_IN_M/Math.cos(Math.toRadians(latitude));
+ }
+
+ /**
+ * Calculates the distance between two LatLng points A and B (in meters)
+ * (Note: approximation: for short distances)
+ * @param pointA initial point
+ * @param pointB final point
+ * @return the distance between the two points
+ */
+ public static double distanceBetweenPoints(LatLng pointA, LatLng pointB){
+ return Math.sqrt(Math.pow(degreesToMetersLat(pointA.latitude-pointB.latitude),2) +
+ Math.pow(degreesToMetersLng(pointA.longitude-pointB.longitude,pointA.latitude),2));
+ }
+
+ /**
+ * Creates a bitmap from a vector
+ * @param context Context of activity being used
+ * @param vectorResourceID Resource id whose vector get converted to a Bitmap
+ * @return Bitmap of the resource vector
+ */
+ public static Bitmap getBitmapFromVector(Context context, int vectorResourceID) {
+ // Get drawable vector
+ Drawable vectorDrawable = ContextCompat.getDrawable(context, vectorResourceID);
+ // Bitmap created to draw the vector in
+ Bitmap bitmap = Bitmap.createBitmap(vectorDrawable.getIntrinsicWidth(), vectorDrawable.getIntrinsicHeight(), Bitmap.Config.ARGB_8888);
+ // Canvas to draw the bitmap on
+ Canvas canvas = new Canvas(bitmap);
+ // Drawing on canvas
+ vectorDrawable.setBounds(0, 0, canvas.getWidth(), canvas.getHeight());
+ vectorDrawable.draw(canvas);
+ return bitmap;
+ }
+
+}
diff --git a/app/src/main/java/com/openpositioning/PositionMe/data/local/TrajParser.java b/app/src/main/java/com/openpositioning/PositionMe/data/local/TrajParser.java
index 2d2b1cbf..04e7d357 100644
--- a/app/src/main/java/com/openpositioning/PositionMe/data/local/TrajParser.java
+++ b/app/src/main/java/com/openpositioning/PositionMe/data/local/TrajParser.java
@@ -4,6 +4,9 @@
import android.hardware.SensorManager;
import android.util.Log;
+import com.android.volley.RequestQueue;
+import com.android.volley.toolbox.JsonObjectRequest;
+import com.android.volley.toolbox.Volley;
import com.google.android.gms.maps.model.LatLng;
import com.google.gson.Gson;
import com.google.gson.JsonArray;
@@ -11,6 +14,10 @@
import com.google.gson.JsonParser;
import com.openpositioning.PositionMe.presentation.fragment.ReplayFragment;
import com.openpositioning.PositionMe.sensors.SensorFusion;
+import com.openpositioning.PositionMe.sensors.WiFiPositioning;
+import com.android.volley.Request;
+import org.json.JSONException;
+import org.json.JSONObject;
import java.io.BufferedReader;
import java.io.File;
@@ -19,6 +26,8 @@
import java.util.Collections;
import java.util.Comparator;
import java.util.List;
+import java.util.concurrent.atomic.AtomicInteger;
+import java.util.concurrent.atomic.AtomicReference;
/**
* Handles parsing of trajectory data stored in JSON files, combining IMU, PDR, and GNSS data
@@ -46,7 +55,7 @@
*
* @see ReplayFragment which uses parsed trajectory data for visualization.
* @see SensorFusion for motion processing and sensor integration.
- * @see com.openpositioning.PositionMe.presentation.fragment.ReplayFragment for implementation details.
+ * @see ReplayFragment for implementation details.
*
* @author Shu Gu
* @author Lin Cheng
@@ -55,13 +64,17 @@ public class TrajParser {
private static final String TAG = "TrajParser";
+ private WiFiPositioning wiFiPositioning;
+
/**
- * Represents a single replay point containing estimated PDR position, GNSS location,
+ * Represents a single replay point containing estimated PDR position, GNSS location, WiFi location
* orientation, speed, and timestamp.
*/
public static class ReplayPoint {
+ public LatLng wifiLocation;
public LatLng pdrLocation; // PDR-derived location estimate
public LatLng gnssLocation; // GNSS location (may be null if unavailable)
+ public LatLng wifiLocation; // WiFi location (may be null if unavailable)
public float orientation; // Orientation in degrees
public float speed; // Speed in meters per second
public long timestamp; // Relative timestamp
@@ -75,9 +88,10 @@ public static class ReplayPoint {
* @param speed The speed in meters per second.
* @param timestamp The timestamp associated with this point.
*/
- public ReplayPoint(LatLng pdrLocation, LatLng gnssLocation, float orientation, float speed, long timestamp) {
+ public ReplayPoint(LatLng pdrLocation, LatLng gnssLocation, LatLng wifiLocation, float orientation, float speed, long timestamp) {
this.pdrLocation = pdrLocation;
this.gnssLocation = gnssLocation;
+ this.wifiLocation = wifiLocation;//更改构造函数,添加wifiLocation参数
this.orientation = orientation;
this.speed = speed;
this.timestamp = timestamp;
@@ -104,6 +118,17 @@ private static class GnssRecord {
public double latitude, longitude; // GNSS coordinates
}
+ private static class MacScan {
+ public String mac;
+ public double rssi;
+ public int timestamp;
+ }
+
+ private static class WiFiRecord{
+ public long relativeTimestamp;
+ public List macScans;
+ }
+
/**
* Parses trajectory data from a JSON file and reconstructs a list of replay points.
*
@@ -184,8 +209,80 @@ public static List parseTrajectoryData(String filePath, Context con
GnssRecord closestGnss = findClosestGnssRecord(gnssList, pdr.relativeTimestamp);
LatLng gnssLocation = closestGnss != null ?
new LatLng(closestGnss.latitude, closestGnss.longitude) : null;
+ WifiRecord closestWifi = findClosestWifiRecord(wifiList, pdr.relativeTimestamp);
+ LatLng wifiLocation = closestWifi != null ?
+ new LatLng(closestWifi.latitude, closestWifi.longitude) : null;
+
+ WiFiRecord closestWiFi = findClosestWiFiRecord(WiFiList, pdr.relativeTimestamp);
+ AtomicReference wifilocation = new AtomicReference<>();
+ AtomicInteger floor = new AtomicInteger();
+ try {
+ // Creating a JSON object to store the WiFi access points
+ JSONObject wifiAccessPoints = new JSONObject();
+ for (MacScan scan : closestWiFi.macScans) {
+ wifiAccessPoints.put(scan.mac, scan.rssi);
+ }
+ // Creating POST Request
+ JSONObject wifiFingerPrint = new JSONObject();
+ wifiFingerPrint.put("wf", wifiAccessPoints);
+ JsonObjectRequest jsonObjectRequest = new JsonObjectRequest(
+ Request.Method.POST, "https://openpositioning.org/api/position/fine", wifiFingerPrint,
+ // Parses the response to obtain the WiFi location and WiFi floor
+ response -> {
+ try {
+ wifilocation.set(new LatLng(response.getDouble("lat"), response.getDouble("lon")));
+ floor.set(response.getInt("floor"));
+ } catch (JSONException e) {
+ // Error log to keep record of errors (for secure programming and maintainability)
+ Log.e("jsonErrors", "Error parsing response: " + e.getMessage() + " " + response);
+ }
+ // Block return when a message is received
+ synchronized (TrajParser.class) {
+ TrajParser.class.notify();
+ }
+ },
+ // Handles the errors obtained from the POST request
+ error -> {
+ // Validation Error
+ if (error.networkResponse != null && error.networkResponse.statusCode == 422) {
+ Log.e("WiFiPositioning", "Validation Error " + error.getMessage());
+ }
+ // Other Errors
+ else {
+ // When Response code is available
+ if (error.networkResponse != null) {
+ Log.e("WiFiPositioning", "Response Code: " + error.networkResponse.statusCode + ", " + error.getMessage());
+ } else {
+ Log.e("WiFiPositioning", "Error message: " + error.getMessage());
+ }
+ }
+ // Block return when an error occurs
+ synchronized (TrajParser.class) {
+ TrajParser.class.notify();
+ }
+ }
+ );
+
+ // Add the request to the RequestQueue
+ RequestQueue requestQueue = Volley.newRequestQueue(context);
+ requestQueue.add(jsonObjectRequest);
+
+ } catch (JSONException e) {
+ // Catching error while making JSON object, to prevent crashes
+ // Error log to keep record of errors (for secure programming and maintainability)
+ Log.e("jsonErrors","Error creating json object"+e.toString());
+ }
+
+ // Wait for the response or error to be processed
+ synchronized (TrajParser.class) {
+ try {
+ TrajParser.class.wait(1000); // Sleep for 1 second
+ } catch (InterruptedException e) {
+ Log.e(TAG, "Thread interrupted while waiting for WiFi positioning response", e);
+ }
+ }
- result.add(new ReplayPoint(pdrLocation, gnssLocation, orientationDeg,
+ result.add(new ReplayPoint(pdrLocation, gnssLocation, wifilocation.get(), orientationDeg,
0f, pdr.relativeTimestamp));
}
@@ -229,17 +326,31 @@ private static List parseGnssData(JsonArray gnssArray) {
gnssList.add(record);
}
return gnssList;
-}/** Finds the closest IMU record to the given timestamp. */
+}/**
+ * Finds the closest IMU record to the given timestamp.
+ */
+private static List parseWiFiData(JsonArray WiFiArray) {
+ List WiFiList = new ArrayList<>();
+ if (WiFiArray == null) return WiFiList;
+ Gson gson = new Gson();
+ for (int i = 0; i < WiFiArray.size(); i++) {
+ WiFiRecord record = gson.fromJson(WiFiArray.get(i), WiFiRecord.class);
+ WiFiList.add(record);
+ }
+ return WiFiList;
+}
private static ImuRecord findClosestImuRecord(List imuList, long targetTimestamp) {
return imuList.stream().min(Comparator.comparingLong(imu -> Math.abs(imu.relativeTimestamp - targetTimestamp)))
.orElse(null);
-
}/** Finds the closest GNSS record to the given timestamp. */
private static GnssRecord findClosestGnssRecord(List gnssList, long targetTimestamp) {
return gnssList.stream().min(Comparator.comparingLong(gnss -> Math.abs(gnss.relativeTimestamp - targetTimestamp)))
.orElse(null);
-
}/** Computes the orientation from a rotation vector. */
+private static WiFiRecord findClosestWiFiRecord(List WiFiList, long targetTimestamp) {
+ return WiFiList.stream().min(Comparator.comparingLong(wifi -> Math.abs(wifi.relativeTimestamp - targetTimestamp)))
+ .orElse(null);
+}
private static float computeOrientationFromRotationVector(float rx, float ry, float rz, float rw, Context context) {
float[] rotationVector = new float[]{rx, ry, rz, rw};
float[] rotationMatrix = new float[9];
diff --git a/app/src/main/java/com/openpositioning/PositionMe/fragments/CorrectionFragment.java b/app/src/main/java/com/openpositioning/PositionMe/fragments/CorrectionFragment.java
new file mode 100644
index 00000000..2a7c5442
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/fragments/CorrectionFragment.java
@@ -0,0 +1,230 @@
+package com.openpositioning.PositionMe.fragments;
+
+import android.os.Bundle;
+import android.text.Editable;
+import android.text.TextWatcher;
+import android.view.KeyEvent;
+import android.view.LayoutInflater;
+import android.view.View;
+import android.view.ViewGroup;
+import android.widget.Button;
+import android.widget.EditText;
+import android.widget.TextView;
+
+import androidx.annotation.NonNull;
+import androidx.annotation.Nullable;
+import androidx.appcompat.app.AppCompatActivity;
+import androidx.fragment.app.Fragment;
+import androidx.navigation.NavDirections;
+import androidx.navigation.Navigation;
+
+import com.openpositioning.PositionMe.PathView;
+import com.openpositioning.PositionMe.R;
+import com.openpositioning.PositionMe.sensors.SensorFusion;
+import com.google.android.gms.maps.CameraUpdateFactory;
+import com.google.android.gms.maps.GoogleMap;
+import com.google.android.gms.maps.OnMapReadyCallback;
+import com.google.android.gms.maps.SupportMapFragment;
+import com.google.android.gms.maps.model.LatLng;
+import com.google.android.gms.maps.model.MarkerOptions;
+
+/**
+ * A simple {@link Fragment} subclass. Corrections Fragment is displayed after a recording session
+ * is finished to enable manual adjustments to the PDR. The adjustments are not saved as of now.
+ *
+ * @see RecordingFragment the preceeding fragment in the nav graph.
+ * @see HomeFragment the next fragment in the nav graph.
+ *
+ *
+ * @author Michal Dvorak
+ * @author Mate Stodulka
+ * @author Virginia Cangelosi
+ */
+public class CorrectionFragment extends Fragment {
+
+ //Map variable to assign to map fragment
+ public GoogleMap mMap;
+ //Button to go to next fragment and save the corrections
+ private Button button;
+ //Singleton SensorFusion class which stores data from all sensors
+ private SensorFusion sensorFusion = SensorFusion.getInstance();
+ //TextView to display user instructions
+ private TextView averageStepLengthText;
+ //Text Input to edit step length
+ private EditText stepLengthInput;
+ //Average step length obtained from SensorFusion class
+ private float averageStepLength;
+ //User entered step length
+ private float newStepLength;
+ //OnKey is called twice so ensure only the second run updates the previous value for the scaling
+ private int secondPass = 0;
+ //Raw text entered by user
+ private CharSequence changedText;
+ //Scaling ratio based on size of trajectory
+ private static float scalingRatio = 0f;
+ //Initial location of PDR
+ private static LatLng start;
+ //Path view on screen
+ private PathView pathView;
+
+ /**
+ * Public Constructor for the class.
+ * Left empty as not required
+ */
+ public CorrectionFragment() {
+ // Required empty public constructor
+ }
+
+ /**
+ * {@inheritDoc}
+ * Loads the starting position set in {@link StartLocationFragment}, and displays a map fragment.
+ */
+ @Override
+ public View onCreateView(LayoutInflater inflater, ViewGroup container,
+ Bundle savedInstanceState) {
+ // Inflate the layout for this fragment
+ View rootView = inflater.inflate(R.layout.fragment_correction, container, false);
+
+ // Inflate the layout for this fragment
+ ((AppCompatActivity)getActivity()).getSupportActionBar().hide();
+
+ //Send trajectory data to the cloud
+ sensorFusion.sendTrajectoryToCloud();
+
+ //Obtain start position set in the startLocation fragment
+ float[] startPosition = sensorFusion.getGNSSLatitude(true);
+
+ // Initialize map fragment
+ SupportMapFragment supportMapFragment=(SupportMapFragment)
+ getChildFragmentManager().findFragmentById(R.id.map);
+
+ // Asynchronous map which can be configured
+ supportMapFragment.getMapAsync(new OnMapReadyCallback() {
+ /**
+ * {@inheritDoc}
+ * Controls to allow scrolling, tilting, rotating and a compass view of the
+ * map are enabled. A marker is added to the map with the start position and the PDR
+ * trajectory is scaled before being overlaid over the map fragment in
+ * CorrectionFragment.onViewCreated.
+ *
+ * @param map Google map to be configured
+ */
+ @Override
+ public void onMapReady(GoogleMap map) {
+ mMap = map;
+ mMap.setMapType(GoogleMap.MAP_TYPE_HYBRID);
+ mMap.getUiSettings().setCompassEnabled(true);
+ mMap.getUiSettings().setTiltGesturesEnabled(true);
+ mMap.getUiSettings().setRotateGesturesEnabled(true);
+ mMap.getUiSettings().setScrollGesturesEnabled(true);
+
+ // Add a marker at the start position and move the camera
+ start = new LatLng(startPosition[0], startPosition[1]);
+ mMap.addMarker(new MarkerOptions().position(start).title("Start Position"));
+ System.out.println("onMapReady scaling ratio: " + scalingRatio);
+ // Calculate zoom of google maps based on the scaling ration from PathView
+ double zoom = Math.log(156543.03392f * Math.cos(startPosition[0] * Math.PI / 180)
+ * scalingRatio) / Math.log(2);
+ System.out.println("onMapReady zoom: " + zoom);
+ //Center the camera
+ mMap.moveCamera(CameraUpdateFactory.newLatLngZoom(start, (float) zoom));
+ }
+ });
+
+ return rootView;
+ }
+
+ /**
+ * {@inheritDoc}.
+ * Button onClick listener enabled to detect when to go to next fragment and show the action bar.
+ * Load and display average step length from PDR.
+ */
+ @Override
+ public void onViewCreated(@NonNull View view, @Nullable Bundle savedInstanceState) {
+ super.onViewCreated(view, savedInstanceState);
+
+ //Instantiate text view to show average step length
+ this.averageStepLengthText = (TextView) getView().findViewById(R.id.averageStepView);
+ //Instantiate input text view to edit average step length
+ this.stepLengthInput = (EditText) getView().findViewById(R.id.inputStepLength);
+ //Instantiate path view for drawing trajectory
+ this.pathView = (PathView) getView().findViewById(R.id.pathView1);
+ //obtain average step length from SensorFusion class
+ averageStepLength = sensorFusion.passAverageStepLength();
+ //Display average step count on UI
+ averageStepLengthText.setText(getActivity().getResources().getString(R.string.averageStepLgn) + ": " + String.format("%.2f", averageStepLength));
+ //Check for enter to be pressed when user inputs new step length
+ this.stepLengthInput.setOnKeyListener(new View.OnKeyListener() {
+ @Override
+ public boolean onKey(View v, int keyCode, KeyEvent event) {
+ //Check if enter key has been pressed
+ if(keyCode == KeyEvent.KEYCODE_ENTER){
+ //Convert entered string to a float
+ newStepLength = Float.parseFloat(changedText.toString());
+ //Rescale the path and call function to redraw
+ //scalingRatio = newStepLength/averageStepLength;
+ sensorFusion.redrawPath(newStepLength/averageStepLength);
+ //Show user new average step value
+ averageStepLengthText.setText(getActivity().getResources().
+ getString(R.string.averageStepLgn) + ": " + String.format("%.2f", newStepLength));
+ //redraw the path
+ pathView.invalidate();
+ //OnKew is called twice (once on press and release of button so the previous
+ // step count is updated only the second time)
+ secondPass++;
+ if(secondPass == 2) {
+ averageStepLength = newStepLength;
+ secondPass = 0;
+ }
+ }
+
+ return false;
+ }
+ });
+
+ //Detect changes in the text editor. Call all default methods and store final string
+ this.stepLengthInput.addTextChangedListener(new TextWatcher() {
+ @Override
+ public void beforeTextChanged(CharSequence s, int start, int count, int after) {
+
+ }
+
+ @Override
+ public void onTextChanged(CharSequence s, int start, int before, int count) {
+
+ }
+
+ @Override
+ public void afterTextChanged(Editable s) {
+ //store string when user has finished changing the text
+ changedText = s;
+ }
+ });
+
+ // Add button to navigate back to home screen.
+ this.button = (Button) getView().findViewById(R.id.correction_done);
+ this.button.setOnClickListener(new View.OnClickListener() {
+ /**
+ * {@inheritDoc}
+ * When button clicked the {@link HomeFragment} is loaded and the action bar is
+ * returned.
+ */
+ @Override
+ public void onClick(View view) {
+ NavDirections action = CorrectionFragmentDirections.actionCorrectionFragmentToHomeFragment();
+ Navigation.findNavController(view).navigate(action);
+ //Show action bar
+ ((AppCompatActivity)getActivity()).getSupportActionBar().show();
+ }
+ });
+ }
+
+ /**
+ * Set the scaling ration for the map fragments.
+ *
+ * @param scalingRatio float ratio for scaling zoom on Maps.
+ */
+ public void setScalingRatio(float scalingRatio) {
+ this.scalingRatio = scalingRatio;
+ }
+}
\ No newline at end of file
diff --git a/app/src/main/java/com/openpositioning/PositionMe/fragments/FilesFragment.java b/app/src/main/java/com/openpositioning/PositionMe/fragments/FilesFragment.java
new file mode 100644
index 00000000..1a472217
--- /dev/null
+++ b/app/src/main/java/com/openpositioning/PositionMe/fragments/FilesFragment.java
@@ -0,0 +1,212 @@
+package com.openpositioning.PositionMe.fragments;
+
+import android.app.AlertDialog;
+import android.app.DownloadManager;
+import android.content.DialogInterface;
+import android.content.Intent;
+import android.os.Bundle;
+import android.os.Handler;
+import android.os.Looper;
+import android.view.LayoutInflater;
+import android.view.View;
+import android.view.ViewGroup;
+import android.widget.Toast;
+
+import androidx.annotation.NonNull;
+import androidx.annotation.Nullable;
+import androidx.cardview.widget.CardView;
+import androidx.fragment.app.Fragment;
+import androidx.navigation.NavDirections;
+import androidx.navigation.Navigation;
+import androidx.recyclerview.widget.LinearLayoutManager;
+import androidx.recyclerview.widget.RecyclerView;
+
+import com.openpositioning.PositionMe.R;
+import com.openpositioning.PositionMe.TrajectoryFileCallback;
+import com.openpositioning.PositionMe.ServerCommunications;
+import com.openpositioning.PositionMe.sensors.Observer;
+import com.openpositioning.PositionMe.viewitems.TrajDownloadListAdapter;
+import com.openpositioning.PositionMe.viewitems.DownloadClickListener;
+import org.json.JSONArray;
+import org.json.JSONException;
+import org.json.JSONObject;
+
+import java.util.ArrayList;
+import java.util.Comparator;
+import java.util.HashMap;
+import java.util.List;
+import java.util.Map;
+import java.io.File;
+
+/**
+ * A simple {@link Fragment} subclass. The files fragment displays a list of trajectories already
+ * uploaded with some metadata, and enables re-downloading them to the device's local storage.
+ *
+ * @see HomeFragment the connected fragment in the nav graph.
+ * @see UploadFragment sub-menu for uploading recordings that failed during recording.
+ * @see com.openpositioning.PositionMe.Traj the data structure sent and received.
+ * @see com.openpositioning.PositionMe.ServerCommunications the class handling communication with the server.
+ */
+public class FilesFragment extends Fragment implements Observer {
+
+ // UI elements
+ private RecyclerView filesList;
+ private TrajDownloadListAdapter listAdapter;
+ private CardView uploadCard;
+
+ // Class handling HTTP communication
+ private ServerCommunications serverCommunications;
+
+ /**
+ * Default public constructor, empty.
+ */
+ public FilesFragment() {
+ // Required empty public constructor
+ }
+
+ /**
+ * {@inheritDoc}
+ * Initialise the server communication class and register the FilesFragment as an Observer to
+ * receive the async http responses.
+ */
+ @Override
+ public void onCreate(Bundle savedInstanceState) {
+ super.onCreate(savedInstanceState);
+ serverCommunications = new ServerCommunications(getActivity()); // Create ServerCommunications instance for server communication
+ serverCommunications.registerObserver(this); // Register FilesFragment as an observer (does not immediately trigger a request)
+ }
+
+ /**
+ * {@inheritDoc}
+ * Sets the title in the action bar.
+ */
+ @Override
+ public View onCreateView(LayoutInflater inflater, ViewGroup container,
+ Bundle savedInstanceState) {
+ // Inflate the layout for this fragment
+ View rootView = inflater.inflate(R.layout.fragment_files, container, false); // Inflate fragment_files.xml
+ getActivity().setTitle("Trajectory recordings"); // Set the activity title
+ return rootView;
+ }
+
+ /**
+ * {@inheritDoc}
+ * Initialises UI elements, including a navigation card to the {@link UploadFragment} and a
+ * RecyclerView displaying online trajectories.
+ */
+ @Override
+ public void onViewCreated(@NonNull View view, @Nullable Bundle savedInstanceState) {
+ super.onViewCreated(view, savedInstanceState);
+ // Get recyclerview
+ filesList = view.findViewById(R.id.filesList);
+ // Get clickable card view
+ uploadCard = view.findViewById(R.id.uploadCard);
+ uploadCard.setOnClickListener(new View.OnClickListener() {
+ /**
+ * {@inheritDoc}
+ * Navigates to {@link UploadFragment}.
+ */
+ @Override
+ public void onClick(View view) {
+ NavDirections action = FilesFragmentDirections.actionFilesFragmentToUploadFragment();
+ Navigation.findNavController(view).navigate(action);
+ }
+ });
+ // Request list of uploaded trajectories from the server.
+ serverCommunications.sendInfoRequest(); // This line actually triggers the request to the server.
+ }
+
+ /**
+ * {@inheritDoc}
+ * Called by {@link ServerCommunications} when the response to the HTTP info request is received.
+ *
+ * @param singletonStringList a single string wrapped in an object array containing the http
+ * response from the server.
+ */
+ @Override
+ public void update(Object[] singletonStringList) {
+ // Cast input as a string
+ String infoString = (String) singletonStringList[0];
+ if(infoString != null && !infoString.isEmpty()) {
+ List