Merge branch 'master' into fix-plugin-return-type

This commit is contained in:
Kevin Hester 2021-10-12 09:15:34 +08:00 committed by GitHub
commit 3d197d732c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
16 changed files with 717 additions and 924 deletions

View File

@ -58,6 +58,19 @@ jobs:
run: |
pio upgrade
- name: Pull web ui
uses: dsaltares/fetch-gh-release-asset@master
with:
repo: "meshtastic/meshtastic-web"
file: "build.tar"
target: "build.tar"
token: ${{ secrets.GITHUB_TOKEN }}
- name: Unpack web ui
run: |
tar -xf build.tar -C data/static
rm build.tar
# We now run integration test before other build steps (to quickly see runtime failures)
- name: Build for native
run: platformio run -e native

View File

@ -47,6 +47,19 @@ jobs:
run: |
pio upgrade
- name: Pull web ui
uses: dsaltares/fetch-gh-release-asset@master
with:
repo: "meshtastic/meshtastic-web"
file: "build.tar"
target: "build.tar"
token: ${{ secrets.GITHUB_TOKEN }}
- name: Unpack web ui
run: |
tar -xf build.tar -C data/static
rm build.tar
# Will be available in steps.version.outputs.version
- name: Get version string
run: echo "::set-output name=version::$(./bin/buildinfo.py long)"

0
data/static/.gitkeep Normal file
View File

View File

@ -1 +0,0 @@
not yet supported - soon will be included in build

450
src/gps/GeoCoord.cpp Normal file
View File

@ -0,0 +1,450 @@
#include "GeoCoord.h"
GeoCoord::GeoCoord() {
_dirty = true;
}
GeoCoord::GeoCoord (int32_t lat, int32_t lon, int32_t alt) : _latitude(lat), _longitude(lon), _altitude(alt) {
GeoCoord::setCoords();
}
GeoCoord::GeoCoord (float lat, float lon, int32_t alt) : _altitude(alt) {
// Change decimial reprsentation to int32_t. I.e., 12.345 becomes 123450000
_latitude = int32_t(lat * 1e+7);
_longitude = int32_t(lon * 1e+7);
GeoCoord::setCoords();
}
GeoCoord::GeoCoord(double lat, double lon, int32_t alt): _altitude(alt) {
// Change decimial reprsentation to int32_t. I.e., 12.345 becomes 123450000
_latitude = int32_t(lat * 1e+7);
_longitude = int32_t(lon * 1e+7);
GeoCoord::setCoords();
}
// Initialize all the coordinate systems
void GeoCoord::setCoords() {
double lat = _latitude * 1e-7;
double lon = _longitude * 1e-7;
GeoCoord::latLongToDMS(lat, lon, _dms);
GeoCoord::latLongToUTM(lat, lon, _utm);
GeoCoord::latLongToMGRS(lat, lon, _mgrs);
GeoCoord::latLongToOSGR(lat, lon, _osgr);
GeoCoord::latLongToOLC(lat, lon, _olc);
_dirty = false;
}
void GeoCoord::updateCoords(int32_t lat, int32_t lon, int32_t alt) {
// If marked dirty or new coordiantes
if(_dirty || _latitude != lat || _longitude != lon || _altitude != alt) {
_dirty = true;
_latitude = lat;
_longitude = lon;
_altitude = alt;
setCoords();
}
}
void GeoCoord::updateCoords(const double lat, const double lon, const int32_t alt) {
int32_t iLat = lat * 1e+7;
int32_t iLon = lon * 1e+7;
// If marked dirty or new coordiantes
if(_dirty || _latitude != iLat || _longitude != iLon || _altitude != alt) {
_dirty = true;
_latitude = iLat;
_longitude = iLon;
_altitude = alt;
setCoords();
}
}
void GeoCoord::updateCoords(const float lat, const float lon, const int32_t alt) {
int32_t iLat = lat * 1e+7;
int32_t iLon = lon * 1e+7;
// If marked dirty or new coordiantes
if(_dirty || _latitude != iLat || _longitude != iLon || _altitude != alt) {
_dirty = true;
_latitude = iLat;
_longitude = iLon;
_altitude = alt;
setCoords();
}
}
/**
* Converts lat long coordinates from decimal degrees to degrees minutes seconds format.
* DD°MM'SS"C DDD°MM'SS"C
*/
void GeoCoord::latLongToDMS(const double lat, const double lon, DMS &dms) {
if (lat < 0) dms.latCP = 'S';
else dms.latCP = 'N';
double latDeg = lat;
if (lat < 0)
latDeg = latDeg * -1;
dms.latDeg = floor(latDeg);
double latMin = (latDeg - dms.latDeg) * 60;
dms.latMin = floor(latMin);
dms.latSec = (latMin - dms.latMin) * 60;
if (lon < 0) dms.lonCP = 'W';
else dms.lonCP = 'E';
double lonDeg = lon;
if (lon < 0)
lonDeg = lonDeg * -1;
dms.lonDeg = floor(lonDeg);
double lonMin = (lonDeg - dms.lonDeg) * 60;
dms.lonMin = floor(lonMin);
dms.lonSec = (lonMin - dms.lonMin) * 60;
}
/**
* Converts lat long coordinates to UTM.
* based on this: https://github.com/walvok/LatLonToUTM/blob/master/latlon_utm.ino
*/
void GeoCoord::latLongToUTM(const double lat, const double lon, UTM &utm) {
const std::string latBands = "CDEFGHJKLMNPQRSTUVWXX";
utm.zone = int((lon + 180)/6 + 1);
utm.band = latBands[int(lat/8 + 10)];
double a = 6378137; // WGS84 - equatorial radius
double k0 = 0.9996; // UTM point scale on the central meridian
double eccSquared = 0.00669438; // eccentricity squared
double lonTemp = (lon + 180) - int((lon + 180)/360) * 360 - 180; //Make sure the longitude is between -180.00 .. 179.9
double latRad = toRadians(lat);
double lonRad = toRadians(lonTemp);
// Special Zones for Norway and Svalbard
if( lat >= 56.0 && lat < 64.0 && lonTemp >= 3.0 && lonTemp < 12.0 ) // Norway
utm.zone = 32;
if( lat >= 72.0 && lat < 84.0 ) { // Svalbard
if ( lonTemp >= 0.0 && lonTemp < 9.0 ) utm.zone = 31;
else if( lonTemp >= 9.0 && lonTemp < 21.0 ) utm.zone = 33;
else if( lonTemp >= 21.0 && lonTemp < 33.0 ) utm.zone = 35;
else if( lonTemp >= 33.0 && lonTemp < 42.0 ) utm.zone = 37;
}
double lonOrigin = (utm.zone - 1)*6 - 180 + 3; // puts origin in middle of zone
double lonOriginRad = toRadians(lonOrigin);
double eccPrimeSquared = (eccSquared)/(1 - eccSquared);
double N = a/sqrt(1 - eccSquared*sin(latRad)*sin(latRad));
double T = tan(latRad)*tan(latRad);
double C = eccPrimeSquared*cos(latRad)*cos(latRad);
double A = cos(latRad)*(lonRad - lonOriginRad);
double M = a*((1 - eccSquared/4 - 3*eccSquared*eccSquared/64 - 5*eccSquared*eccSquared*eccSquared/256)*latRad
- (3*eccSquared/8 + 3*eccSquared*eccSquared/32 + 45*eccSquared*eccSquared*eccSquared/1024)*sin(2*latRad)
+ (15*eccSquared*eccSquared/256 + 45*eccSquared*eccSquared*eccSquared/1024)*sin(4*latRad)
- (35*eccSquared*eccSquared*eccSquared/3072)*sin(6*latRad));
utm.easting = (double)(k0*N*(A+(1-T+C)*pow(A, 3)/6 + (5-18*T+T*T+72*C-58*eccPrimeSquared)*A*A*A*A*A/120)
+ 500000.0);
utm.northing = (double)(k0*(M+N*tan(latRad)*(A*A/2+(5-T+9*C+4*C*C)*A*A*A*A/24
+ (61-58*T+T*T+600*C-330*eccPrimeSquared)*A*A*A*A*A*A/720)));
if(lat < 0)
utm.northing += 10000000.0; //10000000 meter offset for southern hemisphere
}
// Converts lat long coordinates to an MGRS.
void GeoCoord::latLongToMGRS(const double lat, const double lon, MGRS &mgrs) {
const std::string e100kLetters[3] = { "ABCDEFGH", "JKLMNPQR", "STUVWXYZ" };
const std::string n100kLetters[2] = { "ABCDEFGHJKLMNPQRSTUV", "FGHJKLMNPQRSTUVABCDE" };
UTM utm;
latLongToUTM(lat, lon, utm);
mgrs.zone = utm.zone;
mgrs.band = utm.band;
double col = floor(utm.easting / 100000);
mgrs.east100k = e100kLetters[(mgrs.zone - 1) % 3][col - 1];
double row = (int32_t)floor(utm.northing / 100000.0) % 20;
mgrs.north100k = n100kLetters[(mgrs.zone-1)%2][row];
mgrs.easting = (int32_t)utm.easting % 100000;
mgrs.northing = (int32_t)utm.northing % 100000;
}
/**
* Converts lat long coordinates to Ordnance Survey Grid Reference (UK National Grid Ref).
* Based on: https://www.movable-type.co.uk/scripts/latlong-os-gridref.html
*/
void GeoCoord::latLongToOSGR(const double lat, const double lon, OSGR &osgr) {
char letter[] = "ABCDEFGHJKLMNOPQRSTUVWXYZ"; // No 'I' in OSGR
double a = 6377563.396; // Airy 1830 semi-major axis
double b = 6356256.909; // Airy 1830 semi-minor axis
double f0 = 0.9996012717; // National Grid point scale factor on the central meridian
double phi0 = toRadians(49);
double lambda0 = toRadians(-2);
double n0 = -100000;
double e0 = 400000;
double e2 = 1 - (b*b)/(a*a); // eccentricity squared
double n = (a - b)/(a + b);
double osgb_Latitude;
double osgb_Longitude;
convertWGS84ToOSGB36(lat, lon, osgb_Latitude, osgb_Longitude);
double phi = osgb_Latitude; // already in radians
double lambda = osgb_Longitude; // already in radians
double v = a * f0 / sqrt(1 - e2 * sin(phi) * sin(phi));
double rho = a * f0 * (1 - e2) / pow(1 - e2 * sin(phi) * sin(phi), 1.5);
double eta2 = v / rho - 1;
double mA = (1 + n + (5/4)*n*n + (5/4)*n*n*n) * (phi - phi0);
double mB = (3*n + 3*n*n + (21/8)*n*n*n) * sin(phi - phi0) * cos(phi + phi0);
// loss of precision in mC & mD due to floating point rounding can cause innaccuracy of northing by a few meters
double mC = (15/8*n*n + 15/8*n*n*n) * sin(2*(phi - phi0)) * cos(2*(phi + phi0));
double mD = (35/24)*n*n*n * sin(3*(phi - phi0)) * cos(3*(phi + phi0));
double m = b*f0*(mA - mB + mC - mD);
double cos3Phi = cos(phi)*cos(phi)*cos(phi);
double cos5Phi = cos3Phi*cos(phi)*cos(phi);
double tan2Phi = tan(phi)*tan(phi);
double tan4Phi = tan2Phi*tan2Phi;
double I = m + n0;
double II = (v/2)*sin(phi)*cos(phi);
double III = (v/24)*sin(phi)*cos3Phi*(5 - tan2Phi + 9*eta2);
double IIIA = (v/720)*sin(phi)*cos5Phi*(61 - 58*tan2Phi + tan4Phi);
double IV = v*cos(phi);
double V = (v/6)*cos3Phi*(v/rho - tan2Phi);
double VI = (v/120)*cos5Phi*(5 - 18*tan2Phi + tan4Phi + 14*eta2 - 58*tan2Phi*eta2);
double deltaLambda = lambda - lambda0;
double deltaLambda2 = deltaLambda*deltaLambda;
double northing = I + II*deltaLambda2 + III*deltaLambda2*deltaLambda2 + IIIA*deltaLambda2*deltaLambda2*deltaLambda2;
double easting = e0 + IV*deltaLambda + V*deltaLambda2*deltaLambda + VI*deltaLambda2*deltaLambda2*deltaLambda;
if (easting < 0 || easting > 700000 || northing < 0 || northing > 1300000) // Check if out of boundaries
osgr = { 'I', 'I', 0, 0 };
else {
uint32_t e100k = floor(easting / 100000);
uint32_t n100k = floor(northing / 100000);
int8_t l1 = (19 - n100k) - (19 - n100k) % 5 + floor((e100k + 10) / 5);
int8_t l2 = (19 - n100k) * 5 % 25 + e100k % 5;
osgr.e100k = letter[l1];
osgr.n100k = letter[l2];
osgr.easting = floor((int)easting % 100000);
osgr.northing = floor((int)northing % 100000);
}
}
/**
* Converts lat long coordinates to Open Location Code.
* Based on: https://github.com/google/open-location-code/blob/main/c/src/olc.c
*/
void GeoCoord::latLongToOLC(double lat, double lon, OLC &olc) {
char tempCode[] = "1234567890abc";
const char kAlphabet[] = "23456789CFGHJMPQRVWX";
double latitude;
double longitude = lon;
double latitude_degrees = std::min(90.0, std::max(-90.0, lat));
if (latitude_degrees < 90) // Check latitude less than lat max
latitude = latitude_degrees;
else {
double precision;
if (OLC_CODE_LEN <= 10)
precision = pow_neg(20, floor((OLC_CODE_LEN / -2) + 2));
else
precision = pow_neg(20, -3) / pow(5, OLC_CODE_LEN - 10);
latitude = latitude_degrees - precision / 2;
}
while (longitude < -180) // Normalize longitude
longitude += 360;
while (longitude >= 180)
longitude -= 360;
int64_t lat_val = 90 * 2.5e7;
int64_t lng_val = 180 * 8.192e6;
lat_val += latitude * 2.5e7;
lng_val += longitude * 8.192e6;
size_t pos = OLC_CODE_LEN;
if (OLC_CODE_LEN > 10) { // Compute grid part of code if needed
for (size_t i = 0; i < 5; i++) {
int lat_digit = lat_val % 5;
int lng_digit = lng_val % 4;
int ndx = lat_digit * 4 + lng_digit;
tempCode[pos--] = kAlphabet[ndx];
lat_val /= 5;
lng_val /= 4;
}
} else {
lat_val /= pow(5, 5);
lng_val /= pow(4, 5);
}
pos = 10;
for (size_t i = 0; i < 5; i++) { // Compute pair section of code
int lat_ndx = lat_val % 20;
int lng_ndx = lng_val % 20;
tempCode[pos--] = kAlphabet[lng_ndx];
tempCode[pos--] = kAlphabet[lat_ndx];
lat_val /= 20;
lng_val /= 20;
if (i == 0)
tempCode[pos--] = '+';
}
if (OLC_CODE_LEN < 9) { // Add padding if needed
for (size_t i = OLC_CODE_LEN; i < 9; i++)
tempCode[i] = '0';
tempCode[9] = '+';
}
size_t char_count = OLC_CODE_LEN;
if (10 > char_count) {
char_count = 10;
}
for (size_t i = 0; i < char_count; i++) {
olc.code[i] = tempCode[i];
}
olc.code[char_count] = '\0';
}
// Converts the coordinate in WGS84 datum to the OSGB36 datum.
void GeoCoord::convertWGS84ToOSGB36(const double lat, const double lon, double &osgb_Latitude, double &osgb_Longitude) {
// Convert lat long to cartesian
double phi = toRadians(lat);
double lambda = toRadians(lon);
double h = 0.0; // No OSTN height data used, some loss of accuracy (up to 5m)
double wgsA = 6378137; // WGS84 datum semi major axis
double wgsF = 1 / 298.257223563; // WGS84 datum flattening
double ecc = 2*wgsF - wgsF*wgsF;
double vee = wgsA / sqrt(1 - ecc * pow(sin(phi), 2));
double wgsX = (vee + h) * cos(phi) * cos(lambda);
double wgsY = (vee + h) * cos(phi) * sin(lambda);
double wgsZ = ((1 - ecc) * vee + h) * sin(phi);
// 7-parameter Helmert transform
double tx = -446.448; // x shift in meters
double ty = 125.157; // y shift in meters
double tz = -542.060; // z shift in meters
double s = 20.4894/1e6 + 1; // scale normalized parts per million to (s + 1)
double rx = toRadians(-0.1502/3600); // x rotation normalize arcseconds to radians
double ry = toRadians(-0.2470/3600); // y rotation normalize arcseconds to radians
double rz = toRadians(-0.8421/3600); // z rotation normalize arcseconds to radians
double osgbX = tx + wgsX*s - wgsY*rz + wgsZ*ry;
double osgbY = ty + wgsX*rz + wgsY*s - wgsZ*rx;
double osgbZ = tz - wgsX*ry + wgsY*rx + wgsZ*s;
// Convert cartesian to lat long
double airyA = 6377563.396; // Airy1830 datum semi major axis
double airyB = 6356256.909; // Airy1830 datum semi minor axis
double airyF = 1/ 299.3249646; // Airy1830 datum flattening
double airyEcc = 2*airyF - airyF*airyF;
double airyEcc2 = airyEcc / (1 - airyEcc);
double p = sqrt(osgbX*osgbX + osgbY*osgbY);
double R = sqrt(p*p + osgbZ*osgbZ);
double tanBeta = (airyB*osgbZ) / (airyA*p) * (1 + airyEcc2*airyB/R);
double sinBeta = tanBeta / sqrt(1 + tanBeta*tanBeta);
double cosBeta = sinBeta / tanBeta;
osgb_Latitude = atan2(osgbZ + airyEcc2*airyB*sinBeta*sinBeta*sinBeta, p - airyEcc*airyA*cosBeta*cosBeta*cosBeta); // leave in radians
osgb_Longitude = atan2(osgbY, osgbX); // leave in radians
//osgb height = p*cos(osgb.latitude) + osgbZ*sin(osgb.latitude) -
//(airyA*airyA/(airyA / sqrt(1 - airyEcc*sin(osgb.latitude)*sin(osgb.latitude)))); // Not used, no OSTN data
}
/// Ported from my old java code, returns distance in meters along the globe
/// surface (by magic?)
float GeoCoord::latLongToMeter(double lat_a, double lng_a, double lat_b, double lng_b)
{
double pk = (180 / 3.14169);
double a1 = lat_a / pk;
double a2 = lng_a / pk;
double b1 = lat_b / pk;
double b2 = lng_b / pk;
double cos_b1 = cos(b1);
double cos_a1 = cos(a1);
double t1 = cos_a1 * cos(a2) * cos_b1 * cos(b2);
double t2 = cos_a1 * sin(a2) * cos_b1 * sin(b2);
double t3 = sin(a1) * sin(b1);
double tt = acos(t1 + t2 + t3);
if (std::isnan(tt))
tt = 0.0; // Must have been the same point?
return (float)(6366000 * tt);
}
/**
* Computes the bearing in degrees between two points on Earth. Ported from my
* old Gaggle android app.
*
* @param lat1
* Latitude of the first point
* @param lon1
* Longitude of the first point
* @param lat2
* Latitude of the second point
* @param lon2
* Longitude of the second point
* @return Bearing between the two points in radians. A value of 0 means due
* north.
*/
float GeoCoord::bearing(double lat1, double lon1, double lat2, double lon2)
{
double lat1Rad = toRadians(lat1);
double lat2Rad = toRadians(lat2);
double deltaLonRad = toRadians(lon2 - lon1);
double y = sin(deltaLonRad) * cos(lat2Rad);
double x = cos(lat1Rad) * sin(lat2Rad) - (sin(lat1Rad) * cos(lat2Rad) * cos(deltaLonRad));
return atan2(y, x);
}
/**
* Ported from http://www.edwilliams.org/avform147.htm#Intro
* @brief Convert from meters to range in radians on a great circle
* @param range_meters
* The range in meters
* @return range in radians on a great circle
*/
float GeoCoord::rangeMetersToRadians(double range_meters) {
// 1 nm is 1852 meters
double distance_nm = range_meters * 1852;
return (PI / (180 * 60)) *distance_nm;
}
/**
* Ported from http://www.edwilliams.org/avform147.htm#Intro
* @brief Convert from radians to range in meters on a great circle
* @param range_radians
* The range in radians
* @return Range in meters on a great circle
*/
float GeoCoord::rangeRadiansToMeters(double range_radians) {
double distance_nm = ((180 * 60) / PI) * range_radians;
// 1 meter is 0.000539957 nm
return distance_nm * 0.000539957;
}
// Find distance from point to passed in point
int32_t GeoCoord::distanceTo(GeoCoord pointB) {
return latLongToMeter(this->getLatitude() * 1e-7, this->getLongitude() * 1e-7, pointB.getLatitude() * 1e-7, pointB.getLongitude() * 1e-7);
}
// Find bearing from point to passed in point
int32_t GeoCoord::bearingTo(GeoCoord pointB) {
return bearing(this->getLatitude() * 1e-7, this->getLongitude() * 1e-7, pointB.getLatitude() * 1e-7, pointB.getLongitude() * 1e-7);
}
/**
* Create a new point bassed on the passed in poin
* Ported from http://www.edwilliams.org/avform147.htm#LL
* @param bearing
* The bearing in raidans
* @param range_meters
* range in meters
* @return GeoCoord object of point at bearing and range from initial point
*/
std::shared_ptr<GeoCoord> GeoCoord::pointAtDistance(double bearing, double range_meters) {
double range_radians = rangeMetersToRadians(range_meters);
double lat1 = this->getLatitude() * 1e-7;
double lon1 = this->getLongitude() * 1e-7;
double lat = asin(sin(lat1) * cos(range_radians) + cos(lat1) * sin(range_radians) * cos(bearing));
double dlon = atan2(sin(bearing) * sin(range_radians) * cos(lat1), cos(range_radians) - sin(lat1) * sin(lat));
double lon = fmod(lon1 - dlon + PI, 2 * PI) - PI;
return std::make_shared<GeoCoord>(double(lat), double(lon), this->getAltitude());
}

164
src/gps/GeoCoord.h Normal file
View File

@ -0,0 +1,164 @@
#pragma once
#include <algorithm>
#include <string>
#include <cstring>
#include <cstdint>
#include <math.h>
#include <stdint.h>
#include <stdexcept>
#include <memory>
#define PI 3.1415926535897932384626433832795
#define OLC_CODE_LEN 11
// Helper functions
// Raises a number to an exponent, handling negative exponents.
static double pow_neg(double base, double exponent) {
if (exponent == 0) {
return 1;
} else if (exponent > 0) {
return pow(base, exponent);
}
return 1 / pow(base, -exponent);
}
static inline double toRadians(double deg)
{
return deg * PI / 180;
}
static inline double toDegrees(double r)
{
return r * 180 / PI;
}
// GeoCoord structs/classes
// A struct to hold the data for a DMS coordinate.
struct DMS
{
uint8_t latDeg;
uint8_t latMin;
uint32_t latSec;
char latCP;
uint8_t lonDeg;
uint8_t lonMin;
uint32_t lonSec;
char lonCP;
};
// A struct to hold the data for a UTM coordinate, this is also used when creating an MGRS coordinate.
struct UTM
{
uint8_t zone;
char band;
uint32_t easting;
uint32_t northing;
};
// A struct to hold the data for a MGRS coordinate.
struct MGRS
{
uint8_t zone;
char band;
char east100k;
char north100k;
uint32_t easting;
uint32_t northing;
};
// A struct to hold the data for a OSGR coordiante
struct OSGR {
char e100k;
char n100k;
uint32_t easting;
uint32_t northing;
};
// A struct to hold the data for a OLC coordinate
struct OLC {
char code[OLC_CODE_LEN + 1]; // +1 for null termination
};
class GeoCoord {
private:
int32_t _latitude = 0;
int32_t _longitude = 0;
int32_t _altitude = 0;
DMS _dms;
UTM _utm;
MGRS _mgrs;
OSGR _osgr;
OLC _olc;
bool _dirty = true;
void setCoords();
public:
GeoCoord();
GeoCoord(int32_t lat, int32_t lon, int32_t alt);
GeoCoord(double lat, double lon, int32_t alt);
GeoCoord(float lat, float lon, int32_t alt);
void updateCoords(const int32_t lat, const int32_t lon, const int32_t alt);
void updateCoords(const double lat, const double lon, const int32_t alt);
void updateCoords(const float lat, const float lon, const int32_t alt);
// Conversions
static void latLongToDMS(const double lat, const double lon, DMS &dms);
static void latLongToUTM(const double lat, const double lon, UTM &utm);
static void latLongToMGRS(const double lat, const double lon, MGRS &mgrs);
static void latLongToOSGR(const double lat, const double lon, OSGR &osgr);
static void latLongToOLC(const double lat, const double lon, OLC &olc);
static void convertWGS84ToOSGB36(const double lat, const double lon, double &osgb_Latitude, double &osgb_Longitude);
static float latLongToMeter(double lat_a, double lng_a, double lat_b, double lng_b);
static float bearing(double lat1, double lon1, double lat2, double lon2);
static float rangeRadiansToMeters(double range_radians);
static float rangeMetersToRadians(double range_meters);
// Point to point conversions
int32_t distanceTo(GeoCoord pointB);
int32_t bearingTo(GeoCoord pointB);
std::shared_ptr<GeoCoord> pointAtDistance(double bearing, double range);
// Lat lon alt getters
int32_t getLatitude() const { return _latitude; }
int32_t getLongitude() const { return _longitude; }
int32_t getAltitude() const { return _altitude; }
// DMS getters
uint8_t getDMSLatDeg() const { return _dms.latDeg; }
uint8_t getDMSLatMin() const { return _dms.latMin; }
uint32_t getDMSLatSec() const { return _dms.latSec; }
char getDMSLatCP() const { return _dms.latCP; }
uint8_t getDMSLonDeg() const { return _dms.lonDeg; }
uint8_t getDMSLonMin() const { return _dms.lonMin; }
uint32_t getDMSLonSec() const { return _dms.lonSec; }
char getDMSLonCP() const { return _dms.lonCP; }
// UTM getters
uint8_t getUTMZone() const { return _utm.zone; }
char getUTMBand() const { return _utm.band; }
uint32_t getUTMEasting() const { return _utm.easting; }
uint32_t getUTMNorthing() const { return _utm.northing; }
// MGRS getters
uint8_t getMGRSZone() const { return _mgrs.zone; }
char getMGRSBand() const { return _mgrs.band; }
char getMGRSEast100k() const { return _mgrs.east100k; }
char getMGRSNorth100k() const { return _mgrs.north100k; }
uint32_t getMGRSEasting() const { return _mgrs.easting; }
uint32_t getMGRSNorthing() const { return _mgrs.northing; }
// OSGR getters
char getOSGRE100k() const { return _osgr.e100k; }
char getOSGRN100k() const { return _osgr.n100k; }
uint32_t getOSGREasting() const { return _osgr.easting; }
uint32_t getOSGRNorthing() const { return _osgr.northing; }
// OLC getter
void getOLCCode(char* code) { strncpy(code, _olc.code, OLC_CODE_LEN + 1); } // +1 for null termination
};

View File

@ -35,6 +35,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#include "plugins/TextMessagePlugin.h"
#include "target_specific.h"
#include "utils.h"
#include "gps/GeoCoord.h"
#ifndef NO_ESP32
#include "mesh/http/WiFiAPClient.h"
@ -72,6 +73,9 @@ std::vector<MeshPlugin *> pluginFrames;
// Stores the last 4 of our hardware ID, to make finding the device for pairing easier
static char ourId[5];
// GeoCoord object for the screen
GeoCoord geoCoord;
#ifdef SHOW_REDRAWS
static bool heartbeat = false;
#endif
@ -379,369 +383,12 @@ static void drawGPSAltitude(OLEDDisplay *display, int16_t x, int16_t y, const GP
// displayLine = "No GPS Lock";
// display->drawString(x + (SCREEN_WIDTH - (display->getStringWidth(displayLine))) / 2, y, displayLine);
} else {
displayLine = "Altitude: " + String(gps->getAltitude()) + "m";
geoCoord.updateCoords(int32_t(gps->getLatitude()), int32_t(gps->getLongitude()), int32_t(gps->getAltitude()));
displayLine = "Altitude: " + String(geoCoord.getAltitude()) + "m";
display->drawString(x + (SCREEN_WIDTH - (display->getStringWidth(displayLine))) / 2, y, displayLine);
}
}
static inline double toRadians(double deg)
{
return deg * PI / 180;
}
static inline double toDegrees(double r)
{
return r * 180 / PI;
}
// A struct to hold the data for a DMS coordinate.
struct DMS
{
byte latDeg;
byte latMin;
double latSec;
char latCP;
byte lonDeg;
byte lonMin;
double lonSec;
char lonCP;
};
// A struct to hold the data for a UTM coordinate, this is also used when creating an MGRS coordinate.
struct UTM
{
byte zone;
char band;
double easting;
double northing;
};
// A struct to hold the data for a MGRS coordinate.
struct MGRS
{
byte zone;
char band;
char east100k;
char north100k;
uint32_t easting;
uint32_t northing;
};
/**
* Converts lat long coordinates to UTM.
* based on this: https://github.com/walvok/LatLonToUTM/blob/master/latlon_utm.ino
*/
static struct UTM latLongToUTM(const double lat, const double lon)
{
const String latBands = "CDEFGHJKLMNPQRSTUVWXX";
UTM utm;
utm.zone = int((lon + 180)/6 + 1);
utm.band = latBands.charAt(int(lat/8 + 10));
double a = 6378137; // WGS84 - equatorial radius
double k0 = 0.9996; // UTM point scale on the central meridian
double eccSquared = 0.00669438; // eccentricity squared
double lonTemp = (lon + 180) - int((lon + 180)/360) * 360 - 180; //Make sure the longitude is between -180.00 .. 179.9
double latRad = toRadians(lat);
double lonRad = toRadians(lonTemp);
// Special Zones for Norway and Svalbard
if( lat >= 56.0 && lat < 64.0 && lonTemp >= 3.0 && lonTemp < 12.0 ) // Norway
utm.zone = 32;
if( lat >= 72.0 && lat < 84.0 ) { // Svalbard
if ( lonTemp >= 0.0 && lonTemp < 9.0 ) utm.zone = 31;
else if( lonTemp >= 9.0 && lonTemp < 21.0 ) utm.zone = 33;
else if( lonTemp >= 21.0 && lonTemp < 33.0 ) utm.zone = 35;
else if( lonTemp >= 33.0 && lonTemp < 42.0 ) utm.zone = 37;
}
double lonOrigin = (utm.zone - 1)*6 - 180 + 3; // puts origin in middle of zone
double lonOriginRad = toRadians(lonOrigin);
double eccPrimeSquared = (eccSquared)/(1 - eccSquared);
double N = a/sqrt(1 - eccSquared*sin(latRad)*sin(latRad));
double T = tan(latRad)*tan(latRad);
double C = eccPrimeSquared*cos(latRad)*cos(latRad);
double A = cos(latRad)*(lonRad - lonOriginRad);
double M = a*((1 - eccSquared/4 - 3*eccSquared*eccSquared/64 - 5*eccSquared*eccSquared*eccSquared/256)*latRad
- (3*eccSquared/8 + 3*eccSquared*eccSquared/32 + 45*eccSquared*eccSquared*eccSquared/1024)*sin(2*latRad)
+ (15*eccSquared*eccSquared/256 + 45*eccSquared*eccSquared*eccSquared/1024)*sin(4*latRad)
- (35*eccSquared*eccSquared*eccSquared/3072)*sin(6*latRad));
utm.easting = (double)(k0*N*(A+(1-T+C)*pow(A, 3)/6 + (5-18*T+T*T+72*C-58*eccPrimeSquared)*A*A*A*A*A/120)
+ 500000.0);
utm.northing = (double)(k0*(M+N*tan(latRad)*(A*A/2+(5-T+9*C+4*C*C)*A*A*A*A/24
+ (61-58*T+T*T+600*C-330*eccPrimeSquared)*A*A*A*A*A*A/720)));
if(lat < 0)
utm.northing += 10000000.0; //10000000 meter offset for southern hemisphere
return utm;
}
// Converts lat long coordinates to an MGRS.
static struct MGRS latLongToMGRS(double lat, double lon)
{
const String e100kLetters[3] = { "ABCDEFGH", "JKLMNPQR", "STUVWXYZ" };
const String n100kLetters[2] = { "ABCDEFGHJKLMNPQRSTUV", "FGHJKLMNPQRSTUVABCDE" };
UTM utm = latLongToUTM(lat, lon);
MGRS mgrs;
mgrs.zone = utm.zone;
mgrs.band = utm.band;
double col = floor(utm.easting / 100000);
mgrs.east100k = e100kLetters[(mgrs.zone - 1) % 3].charAt(col - 1);
double row = (int)floor(utm.northing / 100000.0) % 20;
mgrs.north100k = n100kLetters[(mgrs.zone-1)%2].charAt(row);
mgrs.easting = (int)utm.easting % 100000;
mgrs.northing = (int)utm.northing % 100000;
return mgrs;
}
/**
* Converts lat long coordinates from decimal degrees to degrees minutes seconds format.
* DD°MM'SS"C DDD°MM'SS"C
*/
static struct DMS latLongToDMS(double lat, double lon)
{
DMS dms;
if (lat < 0) dms.latCP = 'S';
else dms.latCP = 'N';
double latDeg = lat;
if (lat < 0)
latDeg = latDeg * -1;
dms.latDeg = floor(latDeg);
double latMin = (latDeg - dms.latDeg) * 60;
dms.latMin = floor(latMin);
dms.latSec = (latMin - dms.latMin) * 60;
if (lon < 0) dms.lonCP = 'W';
else dms.lonCP = 'E';
double lonDeg = lon;
if (lon < 0)
lonDeg = lonDeg * -1;
dms.lonDeg = floor(lonDeg);
double lonMin = (lonDeg - dms.lonDeg) * 60;
dms.lonMin = floor(lonMin);
dms.lonSec = (lonMin - dms.lonMin) * 60;
return dms;
}
// Raises a number to an exponent, handling negative exponents.
static double pow_neg(double base, double exponent) {
if (exponent == 0) {
return 1;
} else if (exponent > 0) {
return pow(base, exponent);
}
return 1 / pow(base, -exponent);
}
/**
* Converts lat long coordinates to Open Location Code.
* Based on: https://github.com/google/open-location-code/blob/main/c/src/olc.c
*/
static void latLongToOLC(double lat, double lon, char* code) {
char tempCode[] = "1234567890abc";
const char kAlphabet[] = "23456789CFGHJMPQRVWX";
const byte CODE_LEN = 12;
double latitude;
double longitude = lon;
double latitude_degrees = min(90.0, max(-90.0, lat));
if (latitude_degrees < 90) // Check latitude less than lat max
latitude = latitude_degrees;
else {
double precision;
if (CODE_LEN <= 10)
precision = pow_neg(20, floor((CODE_LEN / -2) + 2));
else
precision = pow_neg(20, -3) / pow(5, CODE_LEN - 10);
latitude = latitude_degrees - precision / 2;
}
while (lon < -180) // Normalize longitude
longitude += 360;
while (lon >= 180)
longitude -= 360;
int64_t lat_val = 90 * 2.5e7;
int64_t lng_val = 180 * 8.192e6;
lat_val += latitude * 2.5e7;
lng_val += longitude * 8.192e6;
size_t pos = CODE_LEN;
if (CODE_LEN > 10) { // Compute grid part of code if needed
for (size_t i = 0; i < 5; i++) {
int lat_digit = lat_val % 5;
int lng_digit = lng_val % 4;
int ndx = lat_digit * 4 + lng_digit;
tempCode[pos--] = kAlphabet[ndx];
lat_val /= 5;
lng_val /= 4;
}
} else {
lat_val /= pow(5, 5);
lng_val /= pow(4, 5);
}
pos = 10;
for (size_t i = 0; i < 5; i++) { // Compute pair section of code
int lat_ndx = lat_val % 20;
int lng_ndx = lng_val % 20;
tempCode[pos--] = kAlphabet[lng_ndx];
tempCode[pos--] = kAlphabet[lat_ndx];
lat_val /= 20;
lng_val /= 20;
if (i == 0)
tempCode[pos--] = '+';
}
if (CODE_LEN < 9) { // Add padding if needed
for (size_t i = CODE_LEN; i < 9; i++)
tempCode[i] = '0';
tempCode[9] = '+';
}
size_t char_count = CODE_LEN + 1;
if (10 > char_count) {
char_count = 10;
}
for (size_t i = 0; i < char_count; i++) {
code[i] = tempCode[i];
}
code[char_count] = '\0';
}
struct GeoCoord {
double latitude;
double longitude;
double height;
};
struct OSGR {
char e100k;
char n100k;
uint32_t easting;
uint32_t northing;
};
// Converts the coordinate in WGS84 datum to the OSGB36 datum.
static struct GeoCoord convertWGS84ToOSGB36(double lat, double lon) {
// Convert lat long to cartesian
double phi = toRadians(lat);
double lambda = toRadians(lon);
double h = 0.0; // No OSTN height data used, some loss of accuracy (up to 5m)
double wgsA = 6378137; // WGS84 datum semi major axis
double wgsF = 1 / 298.257223563; // WGS84 datum flattening
double ecc = 2*wgsF - wgsF*wgsF;
double vee = wgsA / sqrt(1 - ecc * pow(sin(phi), 2));
double wgsX = (vee + h) * cos(phi) * cos(lambda);
double wgsY = (vee + h) * cos(phi) * sin(lambda);
double wgsZ = ((1 - ecc) * vee + h) * sin(phi);
// 7-parameter Helmert transform
double tx = -446.448; // x shift in meters
double ty = 125.157; // y shift in meters
double tz = -542.060; // z shift in meters
double s = 20.4894/1e6 + 1; // scale normalized parts per million to (s + 1)
double rx = toRadians(-0.1502/3600); // x rotation normalize arcseconds to radians
double ry = toRadians(-0.2470/3600); // y rotation normalize arcseconds to radians
double rz = toRadians(-0.8421/3600); // z rotation normalize arcseconds to radians
double osgbX = tx + wgsX*s - wgsY*rz + wgsZ*ry;
double osgbY = ty + wgsX*rz + wgsY*s - wgsZ*rx;
double osgbZ = tz - wgsX*ry + wgsY*rx + wgsZ*s;
// Convert cartesian to lat long
double airyA = 6377563.396; // Airy1830 datum semi major axis
double airyB = 6356256.909; // Airy1830 datum semi minor axis
double airyF = 1/ 299.3249646; // Airy1830 datum flattening
GeoCoord osgb;
double airyEcc = 2*airyF - airyF*airyF;
double airyEcc2 = airyEcc / (1 - airyEcc);
double p = sqrt(osgbX*osgbX + osgbY*osgbY);
double R = sqrt(p*p + osgbZ*osgbZ);
double tanBeta = (airyB*osgbZ) / (airyA*p) * (1 + airyEcc2*airyB/R);
double sinBeta = tanBeta / sqrt(1 + tanBeta*tanBeta);
double cosBeta = sinBeta / tanBeta;
osgb.latitude = atan2(osgbZ + airyEcc2*airyB*sinBeta*sinBeta*sinBeta, p - airyEcc*airyA*cosBeta*cosBeta*cosBeta); // leave in radians
osgb.longitude = atan2(osgbY, osgbX); // leave in radians
osgb.height = 0;
//osgb height = p*cos(osgb.latitude) + osgbZ*sin(osgb.latitude) -
//(airyA*airyA/(airyA / sqrt(1 - airyEcc*sin(osgb.latitude)*sin(osgb.latitude)))); // Not used, no OSTN data
return osgb;
}
/**
* Converts lat long coordinates to Ordnance Survey Grid Reference (UK National Grid Ref).
* Based on: https://www.movable-type.co.uk/scripts/latlong-os-gridref.html
*/
static struct OSGR latLongToOSGR(double lat, double lon) {
char letter[] = "ABCDEFGHJKLMNOPQRSTUVWXYZ"; // No 'I' in OSGR
double a = 6377563.396; // Airy 1830 semi-major axis
double b = 6356256.909; // Airy 1830 semi-minor axis
double f0 = 0.9996012717; // National Grid point scale factor on the central meridian
double phi0 = toRadians(49);
double lambda0 = toRadians(-2);
double n0 = -100000;
double e0 = 400000;
double e2 = 1 - (b*b)/(a*a); // eccentricity squared
double n = (a - b)/(a + b);
GeoCoord osgb = convertWGS84ToOSGB36(lat, lon);
double phi = osgb.latitude; // already in radians
double lambda = osgb.longitude; // already in radians
double v = a * f0 / sqrt(1 - e2 * sin(phi) * sin(phi));
double rho = a * f0 * (1 - e2) / pow(1 - e2 * sin(phi) * sin(phi), 1.5);
double eta2 = v / rho - 1;
double mA = (1 + n + (5/4)*n*n + (5/4)*n*n*n) * (phi - phi0);
double mB = (3*n + 3*n*n + (21/8)*n*n*n) * sin(phi - phi0) * cos(phi + phi0);
// loss of precision in mC & mD due to floating point rounding can cause innaccuracy of northing by a few meters
double mC = (15/8*n*n + 15/8*n*n*n) * sin(2*(phi - phi0)) * cos(2*(phi + phi0));
double mD = (35/24)*n*n*n * sin(3*(phi - phi0)) * cos(3*(phi + phi0));
double m = b*f0*(mA - mB + mC - mD);
double cos3Phi = cos(phi)*cos(phi)*cos(phi);
double cos5Phi = cos3Phi*cos(phi)*cos(phi);
double tan2Phi = tan(phi)*tan(phi);
double tan4Phi = tan2Phi*tan2Phi;
double I = m + n0;
double II = (v/2)*sin(phi)*cos(phi);
double III = (v/24)*sin(phi)*cos3Phi*(5 - tan2Phi + 9*eta2);
double IIIA = (v/720)*sin(phi)*cos5Phi*(61 - 58*tan2Phi + tan4Phi);
double IV = v*cos(phi);
double V = (v/6)*cos3Phi*(v/rho - tan2Phi);
double VI = (v/120)*cos5Phi*(5 - 18*tan2Phi + tan4Phi + 14*eta2 - 58*tan2Phi*eta2);
double deltaLambda = lambda - lambda0;
double deltaLambda2 = deltaLambda*deltaLambda;
double northing = I + II*deltaLambda2 + III*deltaLambda2*deltaLambda2 + IIIA*deltaLambda2*deltaLambda2*deltaLambda2;
double easting = e0 + IV*deltaLambda + V*deltaLambda2*deltaLambda + VI*deltaLambda2*deltaLambda2*deltaLambda;
OSGR osgr;
if (easting < 0 || easting > 700000 || northing < 0 || northing > 1300000) // Check if out of boundaries
osgr = { 'I', 'I', 0, 0 };
else {
uint32_t e100k = floor(easting / 100000);
uint32_t n100k = floor(northing / 100000);
byte l1 = (19 - n100k) - (19 - n100k) % 5 + floor((e100k + 10) / 5);
byte l2 = (19 - n100k) * 5 % 25 + e100k % 5;
osgr.e100k = letter[l1];
osgr.n100k = letter[l2];
osgr.easting = floor((int)easting % 100000);
osgr.northing = floor((int)northing % 100000);
}
return osgr;
}
// Draw GPS status coordinates
static void drawGPScoordinates(OLEDDisplay *display, int16_t x, int16_t y, const GPSStatus *gps)
{
@ -757,85 +404,39 @@ static void drawGPScoordinates(OLEDDisplay *display, int16_t x, int16_t y, const
} else {
if (gpsFormat != GpsCoordinateFormat_GpsFormatDMS) {
char coordinateLine[22];
geoCoord.updateCoords(int32_t(gps->getLatitude()), int32_t(gps->getLongitude()), int32_t(gps->getAltitude()));
if (gpsFormat == GpsCoordinateFormat_GpsFormatDec) { // Decimal Degrees
sprintf(coordinateLine, "%f %f", gps->getLatitude() * 1e-7, gps->getLongitude() * 1e-7);
sprintf(coordinateLine, "%f %f", geoCoord.getLatitude() * 1e-7, geoCoord.getLongitude() * 1e-7);
} else if (gpsFormat == GpsCoordinateFormat_GpsFormatUTM) { // Universal Transverse Mercator
UTM utm = latLongToUTM(gps->getLatitude() * 1e-7, gps->getLongitude() * 1e-7);
sprintf(coordinateLine, "%2i%1c %06.0f %07.0f", utm.zone, utm.band, utm.easting, utm.northing);
sprintf(coordinateLine, "%2i%1c %06i %07i", geoCoord.getUTMZone(), geoCoord.getUTMBand(),
geoCoord.getUTMEasting(), geoCoord.getUTMNorthing());
} else if (gpsFormat == GpsCoordinateFormat_GpsFormatMGRS) { // Military Grid Reference System
MGRS mgrs = latLongToMGRS(gps->getLatitude() * 1e-7, gps->getLongitude() * 1e-7);
sprintf(coordinateLine, "%2i%1c %1c%1c %05i %05i", mgrs.zone, mgrs.band, mgrs.east100k, mgrs.north100k,
mgrs.easting, mgrs.northing);
sprintf(coordinateLine, "%2i%1c %1c%1c %05i %05i", geoCoord.getMGRSZone(), geoCoord.getMGRSBand(), geoCoord.getMGRSEast100k(),
geoCoord.getMGRSNorth100k(), geoCoord.getMGRSEasting(), geoCoord.getMGRSNorthing());
} else if (gpsFormat == GpsCoordinateFormat_GpsFormatOLC) { // Open Location Code
latLongToOLC(gps->getLatitude() * 1e-7, gps->getLongitude() * 1e-7, coordinateLine);
geoCoord.getOLCCode(coordinateLine);
} else if (gpsFormat == GpsCoordinateFormat_GpsFormatOSGR) { // Ordnance Survey Grid Reference
OSGR osgr = latLongToOSGR(gps->getLatitude() * 1e-7, gps->getLongitude() * 1e-7);
if (osgr.e100k == 'I' || osgr.n100k == 'I') // OSGR is only valid around the UK region
if (geoCoord.getOSGRE100k() == 'I' || geoCoord.getOSGRN100k() == 'I') // OSGR is only valid around the UK region
sprintf(coordinateLine, "%s", "Out of Boundary");
else
sprintf(coordinateLine, "%1c%1c %05i %05i", osgr.e100k, osgr.n100k, osgr.easting, osgr.northing);
sprintf(coordinateLine, "%1c%1c %05i %05i", geoCoord.getOSGRE100k(),geoCoord.getOSGRN100k(),
geoCoord.getOSGREasting(), geoCoord.getOSGRNorthing());
}
display->drawString(x + (SCREEN_WIDTH - (display->getStringWidth(coordinateLine))) / 2, y, coordinateLine);
} else {
char latLine[22];
char lonLine[22];
DMS dms = latLongToDMS(gps->getLatitude() * 1e-7, gps->getLongitude() * 1e-7);
sprintf(latLine, "%2i° %2i' %2.4f\" %1c", dms.latDeg, dms.latMin, dms.latSec, dms.latCP);
sprintf(lonLine, "%3i° %2i' %2.4f\" %1c", dms.lonDeg, dms.lonMin, dms.lonSec, dms.lonCP);
sprintf(latLine, "%2i° %2i' %2.4f\" %1c", geoCoord.getDMSLatDeg(), geoCoord.getDMSLatMin(), geoCoord.getDMSLatSec(),
geoCoord.getDMSLatCP());
sprintf(lonLine, "%3i° %2i' %2.4f\" %1c", geoCoord.getDMSLonDeg(), geoCoord.getDMSLonMin(), geoCoord.getDMSLonSec(),
geoCoord.getDMSLonCP());
display->drawString(x + (SCREEN_WIDTH - (display->getStringWidth(latLine))) / 2, y - FONT_HEIGHT_SMALL * 1, latLine);
display->drawString(x + (SCREEN_WIDTH - (display->getStringWidth(lonLine))) / 2, y, lonLine);
}
}
}
/// Ported from my old java code, returns distance in meters along the globe
/// surface (by magic?)
static float latLongToMeter(double lat_a, double lng_a, double lat_b, double lng_b)
{
double pk = (180 / 3.14169);
double a1 = lat_a / pk;
double a2 = lng_a / pk;
double b1 = lat_b / pk;
double b2 = lng_b / pk;
double cos_b1 = cos(b1);
double cos_a1 = cos(a1);
double t1 = cos_a1 * cos(a2) * cos_b1 * cos(b2);
double t2 = cos_a1 * sin(a2) * cos_b1 * sin(b2);
double t3 = sin(a1) * sin(b1);
double tt = acos(t1 + t2 + t3);
if (isnan(tt))
tt = 0.0; // Must have been the same point?
return (float)(6366000 * tt);
}
/**
* Computes the bearing in degrees between two points on Earth. Ported from my
* old Gaggle android app.
*
* @param lat1
* Latitude of the first point
* @param lon1
* Longitude of the first point
* @param lat2
* Latitude of the second point
* @param lon2
* Longitude of the second point
* @return Bearing between the two points in radians. A value of 0 means due
* north.
*/
static float bearing(double lat1, double lon1, double lat2, double lon2)
{
double lat1Rad = toRadians(lat1);
double lat2Rad = toRadians(lat2);
double deltaLonRad = toRadians(lon2 - lon1);
double y = sin(deltaLonRad) * cos(lat2Rad);
double x = cos(lat1Rad) * sin(lat2Rad) - (sin(lat1Rad) * cos(lat2Rad) * cos(deltaLonRad));
return atan2(y, x);
}
namespace
{
@ -896,11 +497,11 @@ static float estimatedHeading(double lat, double lon)
return b;
}
float d = latLongToMeter(oldLat, oldLon, lat, lon);
float d = GeoCoord::latLongToMeter(oldLat, oldLon, lat, lon);
if (d < 10) // haven't moved enough, just keep current bearing
return b;
b = bearing(oldLat, oldLon, lat, lon);
b = GeoCoord::bearing(oldLat, oldLon, lat, lon);
oldLat = lat;
oldLon = lon;
@ -1020,7 +621,7 @@ static void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_
// display direction toward node
hasNodeHeading = true;
Position &p = node->position;
float d = latLongToMeter(DegD(p.latitude_i), DegD(p.longitude_i), DegD(op.latitude_i), DegD(op.longitude_i));
float d = GeoCoord::latLongToMeter(DegD(p.latitude_i), DegD(p.longitude_i), DegD(op.latitude_i), DegD(op.longitude_i));
if (d < 2000)
snprintf(distStr, sizeof(distStr), "%.0f m", d);
else
@ -1028,7 +629,7 @@ static void drawNodeInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_
// FIXME, also keep the guess at the operators heading and add/substract
// it. currently we don't do this and instead draw north up only.
float bearingToOther = bearing(DegD(p.latitude_i), DegD(p.longitude_i), DegD(op.latitude_i), DegD(op.longitude_i));
float bearingToOther = GeoCoord::bearing(DegD(p.latitude_i), DegD(p.longitude_i), DegD(op.latitude_i), DegD(op.longitude_i));
headingRadian = bearingToOther - myHeading;
drawNodeHeading(display, compassX, compassY, headingRadian);
}

View File

@ -66,7 +66,7 @@ MeshPacket *MeshPlugin::allocErrorResponse(Routing_Error err, const MeshPacket *
return r;
}
void MeshPlugin::callPlugins(const MeshPacket &mp)
void MeshPlugin::callPlugins(const MeshPacket &mp, RxSource src)
{
// DEBUG_MSG("In call plugins\n");
bool pluginFound = false;
@ -79,6 +79,7 @@ void MeshPlugin::callPlugins(const MeshPacket &mp)
// Was this message directed to us specifically? Will be false if we are sniffing someone elses packets
auto ourNodeNum = nodeDB.getNodeNum();
bool toUs = mp.to == NODENUM_BROADCAST || mp.to == ourNodeNum;
for (auto i = plugins->begin(); i != plugins->end(); ++i) {
auto &pi = **i;
@ -87,6 +88,11 @@ void MeshPlugin::callPlugins(const MeshPacket &mp)
/// We only call plugins that are interested in the packet (and the message is destined to us or we are promiscious)
bool wantsPacket = (isDecoded || pi.encryptedOk) && (pi.isPromiscuous || toUs) && pi.wantPacket(&mp);
if ((src == RX_SRC_LOCAL) && !(pi.loopbackOk)) {
// new case, monitor separately for now, then FIXME merge above
wantsPacket = false;
}
assert(!pi.myReply); // If it is !null it means we have a bug, because it should have been sent the previous time
if (wantsPacket) {
@ -169,7 +175,9 @@ void MeshPlugin::callPlugins(const MeshPacket &mp)
}
if (!pluginFound)
DEBUG_MSG("No plugins interested in portnum=%d\n", mp.decoded.portnum);
DEBUG_MSG("No plugins interested in portnum=%d, src=%s\n",
mp.decoded.portnum,
(src == RX_SRC_LOCAL) ? "LOCAL":"REMOTE");
}
MeshPacket *MeshPlugin::allocReply()

View File

@ -45,7 +45,7 @@ class MeshPlugin
/** For use only by MeshService
*/
static void callPlugins(const MeshPacket &mp);
static void callPlugins(const MeshPacket &mp, RxSource src = RX_SRC_RADIO);
static std::vector<MeshPlugin *> GetMeshPluginsWithUIFrames();
#ifndef NO_SCREEN
@ -60,6 +60,10 @@ class MeshPlugin
*/
bool isPromiscuous = false;
/** Also receive a copy of LOCALLY GENERATED messages - most plugins should leave
* this setting disabled - see issue #877 */
bool loopbackOk = false;
/** Most plugins only understand decrypted packets. For plugins that also want to see encrypted packets, they should set this
* flag */
bool encryptedOk = false;

View File

@ -15,6 +15,14 @@ typedef uint32_t PacketId; // A packet sequence number
#define ERRNO_UNKNOWN 32 // pick something that doesn't conflict with RH_ROUTER_ERROR_UNABLE_TO_DELIVER
#define ERRNO_DISABLED 34 // the itnerface is disabled
/*
* Source of a received message
*/
enum RxSource {
RX_SRC_LOCAL, // message was generated locally
RX_SRC_RADIO // message was received from radio mesh
};
/**
* the max number of hops a message can pass through, used as the default max for hop_limit in MeshPacket.
*

View File

@ -161,7 +161,7 @@ ErrorCode Router::sendLocal(MeshPacket *p)
// If we are sending a broadcast, we also treat it as if we just received it ourself
// this allows local apps (and PCs) to see broadcasts sourced locally
if (p->to == NODENUM_BROADCAST) {
handleReceived(p);
handleReceived(p, RX_SRC_LOCAL);
}
return send(p);
@ -324,7 +324,7 @@ NodeNum Router::getNodeNum()
* Handle any packet that is received by an interface on this node.
* Note: some packets may merely being passed through this node and will be forwarded elsewhere.
*/
void Router::handleReceived(MeshPacket *p)
void Router::handleReceived(MeshPacket *p, RxSource src)
{
// Also, we should set the time from the ISR and it should have msec level resolution
p->rx_time = getValidTime(RTCQualityFromNet); // store the arrival timestamp for the phone
@ -333,13 +333,16 @@ void Router::handleReceived(MeshPacket *p)
bool decoded = perhapsDecode(p);
if (decoded) {
// parsing was successful, queue for our recipient
printPacket("handleReceived", p);
if (src == RX_SRC_LOCAL)
printPacket("handleReceived(local)", p);
else
printPacket("handleReceived(remote)", p);
} else {
printPacket("packet decoding failed (no PSK?)", p);
}
// call plugins here
MeshPlugin::callPlugins(*p);
MeshPlugin::callPlugins(*p, src);
}
void Router::perhapsHandleReceived(MeshPacket *p)

View File

@ -122,7 +122,7 @@ class Router : protected concurrency::OSThread
* Note: this packet will never be called for messages sent/generated by this node.
* Note: this method will free the provided packet.
*/
void handleReceived(MeshPacket *p);
void handleReceived(MeshPacket *p, RxSource src = RX_SRC_RADIO);
/** Frees the provided packet, and generates a NAK indicating the speicifed error while sending */
void abortSendAndNak(Routing_Error err, MeshPacket *p);

View File

@ -4,7 +4,6 @@
#include "airtime.h"
#include "main.h"
#include "mesh/http/ContentHelper.h"
#include "mesh/http/ContentStatic.h"
#include "mesh/http/WiFiAPClient.h"
#include "power.h"
#include "sleep.h"
@ -79,19 +78,17 @@ void registerHandlers(HTTPServer *insecureServer, HTTPSServer *secureServer)
ResourceNode *nodeHotspotApple = new ResourceNode("/hotspot-detect.html", "GET", &handleHotspot);
ResourceNode *nodeHotspotAndroid = new ResourceNode("/generate_204", "GET", &handleHotspot);
ResourceNode *nodeFavicon = new ResourceNode("/favicon.ico", "GET", &handleFavicon);
ResourceNode *nodeRoot = new ResourceNode("/", "GET", &handleRoot);
ResourceNode *nodeStaticBrowse = new ResourceNode("/static", "GET", &handleStaticBrowse);
ResourceNode *nodeStaticPOST = new ResourceNode("/static", "POST", &handleStaticPost);
ResourceNode *nodeStatic = new ResourceNode("/static/*", "GET", &handleStatic);
ResourceNode *nodeRestart = new ResourceNode("/restart", "POST", &handleRestart);
ResourceNode *node404 = new ResourceNode("", "GET", &handle404);
ResourceNode *nodeFormUpload = new ResourceNode("/upload", "POST", &handleFormUpload);
ResourceNode *nodeJsonScanNetworks = new ResourceNode("/json/scanNetworks", "GET", &handleScanNetworks);
ResourceNode *nodeJsonBlinkLED = new ResourceNode("/json/blink", "POST", &handleBlinkLED);
ResourceNode *nodeJsonReport = new ResourceNode("/json/report", "GET", &handleReport);
ResourceNode *nodeJsonSpiffsBrowseStatic = new ResourceNode("/json/spiffs/browse/static", "GET", &handleSpiffsBrowseStatic);
ResourceNode *nodeJsonDelete = new ResourceNode("/json/spiffs/delete/static", "DELETE", &handleSpiffsDeleteStatic);
ResourceNode *nodeRoot = new ResourceNode("/*", "GET", &handleStatic);
// Secure nodes
secureServer->registerNode(nodeAPIv1ToRadioOptions);
@ -99,11 +96,6 @@ void registerHandlers(HTTPServer *insecureServer, HTTPSServer *secureServer)
secureServer->registerNode(nodeAPIv1FromRadio);
secureServer->registerNode(nodeHotspotApple);
secureServer->registerNode(nodeHotspotAndroid);
secureServer->registerNode(nodeFavicon);
secureServer->registerNode(nodeRoot);
secureServer->registerNode(nodeStaticBrowse);
secureServer->registerNode(nodeStaticPOST);
secureServer->registerNode(nodeStatic);
secureServer->registerNode(nodeRestart);
secureServer->registerNode(nodeFormUpload);
secureServer->registerNode(nodeJsonScanNetworks);
@ -111,7 +103,7 @@ void registerHandlers(HTTPServer *insecureServer, HTTPSServer *secureServer)
secureServer->registerNode(nodeJsonSpiffsBrowseStatic);
secureServer->registerNode(nodeJsonDelete);
secureServer->registerNode(nodeJsonReport);
secureServer->setDefaultNode(node404);
secureServer->registerNode(nodeRoot);
secureServer->addMiddleware(&middlewareSpeedUp240);
@ -121,11 +113,6 @@ void registerHandlers(HTTPServer *insecureServer, HTTPSServer *secureServer)
insecureServer->registerNode(nodeAPIv1FromRadio);
insecureServer->registerNode(nodeHotspotApple);
insecureServer->registerNode(nodeHotspotAndroid);
insecureServer->registerNode(nodeFavicon);
insecureServer->registerNode(nodeRoot);
insecureServer->registerNode(nodeStaticBrowse);
insecureServer->registerNode(nodeStaticPOST);
insecureServer->registerNode(nodeStatic);
insecureServer->registerNode(nodeRestart);
insecureServer->registerNode(nodeFormUpload);
insecureServer->registerNode(nodeJsonScanNetworks);
@ -133,7 +120,7 @@ void registerHandlers(HTTPServer *insecureServer, HTTPSServer *secureServer)
insecureServer->registerNode(nodeJsonSpiffsBrowseStatic);
insecureServer->registerNode(nodeJsonDelete);
insecureServer->registerNode(nodeJsonReport);
insecureServer->setDefaultNode(node404);
insecureServer->registerNode(nodeRoot);
insecureServer->addMiddleware(&middlewareSpeedUp160);
}
@ -180,11 +167,8 @@ void handleAPIv1FromRadio(HTTPRequest *req, HTTPResponse *res)
/*
For documentation, see:
https://github.com/meshtastic/Meshtastic-device/wiki/HTTP-REST-API-discussion
https://github.com/meshtastic/Meshtastic-device/blob/master/docs/software/device-api.md
Example:
http://10.10.30.198/api/v1/fromradio
https://meshtastic.org/docs/developers/device/http-api
https://meshtastic.org/docs/developers/device/device-api
*/
// Get access to the parameters
@ -233,24 +217,20 @@ void handleAPIv1ToRadio(HTTPRequest *req, HTTPResponse *res)
/*
For documentation, see:
https://github.com/meshtastic/Meshtastic-device/wiki/HTTP-REST-API-discussion
https://github.com/meshtastic/Meshtastic-device/blob/master/docs/software/device-api.md
Example:
http://10.10.30.198/api/v1/toradio
https://meshtastic.org/docs/developers/device/http-api
https://meshtastic.org/docs/developers/device/device-api
*/
// Status code is 200 OK by default.
res->setHeader("Content-Type", "application/x-protobuf");
res->setHeader("Access-Control-Allow-Headers", "Content-Type");
res->setHeader("Access-Control-Allow-Origin", "*");
res->setHeader("Access-Control-Allow-Methods", "PUT, OPTIONS");
res->setHeader("X-Protobuf-Schema", "https://raw.githubusercontent.com/meshtastic/Meshtastic-protobufs/master/mesh.proto");
if (req->getMethod() == "OPTIONS") {
res->setStatusCode(204); // Success with no content
res->print("");
// res->print(""); @todo remove
return;
}
@ -264,86 +244,8 @@ void handleAPIv1ToRadio(HTTPRequest *req, HTTPResponse *res)
DEBUG_MSG("--------------- webAPI handleAPIv1ToRadio\n");
}
void handleFavicon(HTTPRequest *req, HTTPResponse *res)
{
// Set Content-Type
res->setHeader("Content-Type", "image/vnd.microsoft.icon");
// Write data from header file
res->write(FAVICON_DATA, FAVICON_LENGTH);
}
void handleStaticPost(HTTPRequest *req, HTTPResponse *res)
{
// Assume POST request. Contains submitted data.
res->println("<html><head><title>File Edited</title><meta http-equiv=\"refresh\" content=\"1;url=/static\" "
"/><head><body><h1>File Edited</h1>");
// The form is submitted with the x-www-form-urlencoded content type, so we need the
// HTTPURLEncodedBodyParser to read the fields.
// Note that the content of the file's content comes from a <textarea>, so we
// can use the URL encoding here, since no file upload from an <input type="file"
// is involved.
HTTPURLEncodedBodyParser parser(req);
// The bodyparser will consume the request body. That means you can iterate over the
// fields only ones. For that reason, we need to create variables for all fields that
// we expect. So when parsing is done, you can process the field values from your
// temporary variables.
std::string filename;
bool savedFile = false;
// Iterate over the fields from the request body by calling nextField(). This function
// will update the field name and value of the body parsers. If the last field has been
// reached, it will return false and the while loop stops.
while (parser.nextField()) {
// Get the field name, so that we can decide what the value is for
std::string name = parser.getFieldName();
if (name == "filename") {
// Read the filename from the field's value, add the /public prefix and store it in
// the filename variable.
char buf[512];
size_t readLength = parser.read((byte *)buf, 512);
// filename = std::string("/public/") + std::string(buf, readLength);
filename = std::string(buf, readLength);
} else if (name == "content") {
// Browsers must return the fields in the order that they are placed in
// the HTML form, so if the broweser behaves correctly, this condition will
// never be true. We include it for safety reasons.
if (filename == "") {
res->println("<p>Error: form contained content before filename.</p>");
break;
}
// With parser.read() and parser.endOfField(), we can stream the field content
// into a buffer. That allows handling arbitrarily-sized field contents. Here,
// we use it and write the file contents directly to the SPIFFS:
size_t fieldLength = 0;
File file = SPIFFS.open(filename.c_str(), "w");
savedFile = true;
while (!parser.endOfField()) {
byte buf[512];
size_t readLength = parser.read(buf, 512);
file.write(buf, readLength);
fieldLength += readLength;
}
file.close();
res->printf("<p>Saved %d bytes to %s</p>", int(fieldLength), filename.c_str());
} else {
res->printf("<p>Unexpected field %s</p>", name.c_str());
}
}
if (!savedFile) {
res->println("<p>No file to save...</p>");
}
res->println("</body></html>");
}
void handleSpiffsBrowseStatic(HTTPRequest *req, HTTPResponse *res)
{
// jm
res->setHeader("Content-Type", "application/json");
res->setHeader("Access-Control-Allow-Origin", "*");
@ -422,206 +324,6 @@ void handleSpiffsDeleteStatic(HTTPRequest *req, HTTPResponse *res)
}
}
/*
To convert text to c strings:
https://tomeko.net/online_tools/cpp_text_escape.php?lang=en
*/
void handleRoot(HTTPRequest *req, HTTPResponse *res)
{
res->setHeader("Content-Type", "text/html");
res->setHeader("Set-Cookie",
"mt_session=" + httpsserver::intToString(random(1, 9999999)) + "; Expires=Wed, 20 Apr 2049 4:20:00 PST");
std::string cookie = req->getHeader("Cookie");
// String cookieString = cookie.c_str();
// uint8_t nameIndex = cookieString.indexOf("mt_session");
// DEBUG_MSG(cookie.c_str());
std::string filename = "/static/index.html";
std::string filenameGzip = "/static/index.html.gz";
if (!SPIFFS.exists(filename.c_str()) && !SPIFFS.exists(filenameGzip.c_str())) {
// Send "404 Not Found" as response, as the file doesn't seem to exist
res->setStatusCode(404);
res->setStatusText("Not found");
res->println("404 Not Found");
res->printf("<p>File not found: %s</p>\n", filename.c_str());
res->printf("<p></p>\n");
res->printf("<p>You have gotten this error because the filesystem for the web server has not been loaded.</p>\n");
res->printf("<p>Please review the 'Common Problems' section of the <a "
"href=https://github.com/meshtastic/Meshtastic-device/wiki/"
"How-to-use-the-Meshtastic-Web-Interface-over-WiFi>web interface</a> documentation.</p>\n");
return;
}
// Try to open the file from SPIFFS
File file;
if (SPIFFS.exists(filename.c_str())) {
file = SPIFFS.open(filename.c_str());
if (!file.available()) {
DEBUG_MSG("File not available - %s\n", filename.c_str());
}
} else if (SPIFFS.exists(filenameGzip.c_str())) {
file = SPIFFS.open(filenameGzip.c_str());
res->setHeader("Content-Encoding", "gzip");
if (!file.available()) {
DEBUG_MSG("File not available\n");
}
}
// Read the file from SPIFFS and write it to the HTTP response body
size_t length = 0;
do {
char buffer[256];
length = file.read((uint8_t *)buffer, 256);
std::string bufferString(buffer, length);
res->write((uint8_t *)bufferString.c_str(), bufferString.size());
} while (length > 0);
}
void handleStaticBrowse(HTTPRequest *req, HTTPResponse *res)
{
// Get access to the parameters
ResourceParameters *params = req->getParams();
std::string paramValDelete;
std::string paramValEdit;
DEBUG_MSG("Static Browse - Disabling keep-alive\n");
res->setHeader("Connection", "close");
// Set a default content type
res->setHeader("Content-Type", "text/html");
if (params->getQueryParameter("delete", paramValDelete)) {
std::string pathDelete = "/" + paramValDelete;
if (SPIFFS.remove(pathDelete.c_str())) {
Serial.println(pathDelete.c_str());
res->println("<html><head><meta http-equiv=\"refresh\" content=\"1;url=/static\" /><title>File "
"deleted!</title></head><body><h1>File deleted!</h1>");
res->println("<meta http-equiv=\"refresh\" 1;url=/static\" />\n");
res->println("</body></html>");
return;
} else {
Serial.println(pathDelete.c_str());
res->println("<html><head><meta http-equiv=\"refresh\" content=\"1;url=/static\" /><title>Error deleteing "
"file!</title></head><body><h1>Error deleteing file!</h1>");
res->println("Error deleteing file!<br>");
return;
}
}
if (params->getQueryParameter("edit", paramValEdit)) {
std::string pathEdit = "/" + paramValEdit;
res->println("<html><head><title>Edit "
"file</title></head><body><h1>Edit file - ");
res->println(pathEdit.c_str());
res->println("</h1>");
res->println("<form method=post action=/static enctype=application/x-www-form-urlencoded>");
res->printf("<input name=\"filename\" type=\"hidden\" value=\"%s\">", pathEdit.c_str());
res->print("<textarea id=id name=content rows=20 cols=80>");
// Try to open the file from SPIFFS
File file = SPIFFS.open(pathEdit.c_str());
if (file.available()) {
// Read the file from SPIFFS and write it to the HTTP response body
size_t length = 0;
do {
char buffer[256];
length = file.read((uint8_t *)buffer, 256);
std::string bufferString(buffer, length);
// Escape gt and lt
replaceAll(bufferString, "<", "&lt;");
replaceAll(bufferString, ">", "&gt;");
res->write((uint8_t *)bufferString.c_str(), bufferString.size());
} while (length > 0);
} else {
res->println("Error: File not found");
}
res->println("</textarea><br>");
res->println("<input type=submit value=Submit>");
res->println("</form>");
res->println("</body></html>");
return;
}
res->println("<h2>Upload new file</h2>");
res->println("<p>This form allows you to upload files. Keep your filenames small and files under 200k.</p>");
res->println("<form method=\"POST\" action=\"/upload\" enctype=\"multipart/form-data\">");
res->println("file: <input type=\"file\" name=\"file\"><br>");
res->println("<input type=\"submit\" value=\"Upload\">");
res->println("</form>");
res->println("<h2>All Files</h2>");
File root = SPIFFS.open("/");
if (root.isDirectory()) {
res->println("<script type=\"text/javascript\">function confirm_delete() {return confirm('Are you sure?');}</script>");
res->println("<table>");
res->println("<tr>");
res->println("<td>File");
res->println("</td>");
res->println("<td>Size");
res->println("</td>");
res->println("<td colspan=2>Actions");
res->println("</td>");
res->println("</tr>");
File file = root.openNextFile();
while (file) {
String filePath = String(file.name());
if (filePath.indexOf("/static") == 0) {
res->println("<tr>");
res->println("<td>");
if (String(file.name()).substring(1).endsWith(".gz")) {
String modifiedFile = String(file.name()).substring(1);
modifiedFile.remove((modifiedFile.length() - 3), 3);
res->print("<a href=\"" + modifiedFile + "\">" + String(file.name()).substring(1) + "</a>");
} else {
res->print("<a href=\"" + String(file.name()).substring(1) + "\">" + String(file.name()).substring(1) +
"</a>");
}
res->println("</td>");
res->println("<td>");
res->print(String(file.size()));
res->println("</td>");
res->println("<td>");
res->print("<a href=\"/static?delete=" + String(file.name()).substring(1) +
"\" onclick=\"return confirm_delete()\">Delete</a> ");
res->println("</td>");
res->println("<td>");
if (!String(file.name()).substring(1).endsWith(".gz")) {
res->print("<a href=\"/static?edit=" + String(file.name()).substring(1) + "\">Edit</a>");
}
res->println("</td>");
res->println("</tr>");
}
file = root.openNextFile();
}
res->println("</table>");
res->print("<br>");
// res->print("Total : " + String(SPIFFS.totalBytes()) + " Bytes<br>");
res->print("Used : " + String(SPIFFS.usedBytes()) + " Bytes<br>");
res->print("Free : " + String(SPIFFS.totalBytes() - SPIFFS.usedBytes()) + " Bytes<br>");
}
}
void handleStatic(HTTPRequest *req, HTTPResponse *res)
{
// Get access to the parameters
@ -634,35 +336,33 @@ void handleStatic(HTTPRequest *req, HTTPResponse *res)
std::string filename = "/static/" + parameter1;
std::string filenameGzip = "/static/" + parameter1 + ".gz";
if (!SPIFFS.exists(filename.c_str()) && !SPIFFS.exists(filenameGzip.c_str())) {
// Send "404 Not Found" as response, as the file doesn't seem to exist
res->setStatusCode(404);
res->setStatusText("Not found");
res->println("404 Not Found");
res->printf("<p>File not found: %s</p>\n", filename.c_str());
return;
}
// Try to open the file from SPIFFS
File file;
bool has_set_content_type = false;
if (SPIFFS.exists(filename.c_str())) {
file = SPIFFS.open(filename.c_str());
if (!file.available()) {
DEBUG_MSG("File not available - %s\n", filename.c_str());
}
} else if (SPIFFS.exists(filenameGzip.c_str())) {
file = SPIFFS.open(filenameGzip.c_str());
res->setHeader("Content-Encoding", "gzip");
if (!file.available()) {
DEBUG_MSG("File not available\n");
}
} else {
has_set_content_type = true;
filenameGzip = "/static/index.html.gz";
file = SPIFFS.open(filenameGzip.c_str());
res->setHeader("Content-Encoding", "gzip");
res->setHeader("Content-Type", "text/html");
}
res->setHeader("Content-Length", httpsserver::intToString(file.size()));
bool has_set_content_type = false;
// Content-Type is guessed using the definition of the contentTypes-table defined above
int cTypeIdx = 0;
do {
@ -949,30 +649,6 @@ void handleReport(HTTPRequest *req, HTTPResponse *res)
res->println("}");
}
// --------
void handle404(HTTPRequest *req, HTTPResponse *res)
{
// Discard request body, if we received any
// We do this, as this is the default node and may also server POST/PUT requests
req->discardRequestBody();
// Set the response status
res->setStatusCode(404);
res->setStatusText("Not Found");
// Set content type of the response
res->setHeader("Content-Type", "text/html");
// Write a tiny HTTP page
res->println("<!DOCTYPE html>");
res->println("<html>");
res->println("<head><title>Not Found</title></head>");
res->println("<body><h1>404 Not Found</h1><p>The requested resource was not found on this server.</p></body>");
res->println("</html>");
}
/*
This supports the Apple Captive Network Assistant (CNA) Portal
*/

View File

@ -5,25 +5,18 @@ void registerHandlers(HTTPServer *insecureServer, HTTPSServer *secureServer);
// Declare some handler functions for the various URLs on the server
void handleAPIv1FromRadio(HTTPRequest *req, HTTPResponse *res);
void handleAPIv1ToRadio(HTTPRequest *req, HTTPResponse *res);
void handleStyleCSS(HTTPRequest *req, HTTPResponse *res);
void handleHotspot(HTTPRequest *req, HTTPResponse *res);
void handleRoot(HTTPRequest *req, HTTPResponse *res);
void handleStaticBrowse(HTTPRequest *req, HTTPResponse *res);
void handleStaticPost(HTTPRequest *req, HTTPResponse *res);
void handleStatic(HTTPRequest *req, HTTPResponse *res);
void handleRestart(HTTPRequest *req, HTTPResponse *res);
void handle404(HTTPRequest *req, HTTPResponse *res);
void handleFormUpload(HTTPRequest *req, HTTPResponse *res);
void handleScanNetworks(HTTPRequest *req, HTTPResponse *res);
void handleSpiffsBrowseStatic(HTTPRequest *req, HTTPResponse *res);
void handleSpiffsDeleteStatic(HTTPRequest *req, HTTPResponse *res);
void handleBlinkLED(HTTPRequest *req, HTTPResponse *res);
void handleReport(HTTPRequest *req, HTTPResponse *res);
void handleFavicon(HTTPRequest *req, HTTPResponse *res);
void middlewareSpeedUp240(HTTPRequest *req, HTTPResponse *res, std::function<void()> next);
void middlewareSpeedUp160(HTTPRequest *req, HTTPResponse *res, std::function<void()> next);
void middlewareSession(HTTPRequest *req, HTTPResponse *res, std::function<void()> next);
uint32_t getTimeSpeedUp();
void setTimeSpeedUp();

View File

@ -1,119 +0,0 @@
#include <Arduino.h>
#include <functional>
/*
This file contains static content.
*/
// Length of the binary data
const int FAVICON_LENGTH = 2238;
// Binary data for the favicon
const byte FAVICON_DATA[] = {
0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x20, 0x20, 0x00, 0x00, 0x01, 0x00, 0x08, 0x00, 0xA8, 0x08, 0x00, 0x00, 0x16, 0x00, 0x00,
0x00, 0x28, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x01, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x84,
0xDC, 0x3D, 0x00, 0x84, 0xDC, 0x3C, 0x00, 0x85, 0xDC, 0x3F, 0x00, 0x86, 0xDD, 0x40, 0x00, 0x83, 0xDC, 0x3C, 0x00, 0x85, 0xDC,
0x3E, 0x00, 0x82, 0xDC, 0x3A, 0x00, 0x8B, 0xDE, 0x49, 0x00, 0x84, 0xDB, 0x3E, 0x00, 0x82, 0xD9, 0x3C, 0x00, 0x89, 0xDD, 0x45,
0x00, 0x83, 0xDB, 0x3C, 0x00, 0x83, 0xD8, 0x3D, 0x00, 0x81, 0xD8, 0x3A, 0x00, 0x8D, 0xE0, 0x49, 0x00, 0x88, 0xE4, 0x3F, 0x00,
0x89, 0xE9, 0x3E, 0x00, 0x84, 0xD8, 0x40, 0x00, 0x85, 0xDF, 0x3C, 0x00, 0x8E, 0xF2, 0x40, 0x00, 0x8D, 0xF6, 0x3D, 0x00, 0x90,
0xEA, 0x49, 0x00, 0x82, 0xD5, 0x3E, 0x00, 0x78, 0xC1, 0x3A, 0x00, 0x90, 0xE9, 0x4A, 0x00, 0x8E, 0xF5, 0x3D, 0x00, 0x84, 0xDD,
0x3D, 0x00, 0x91, 0xF7, 0x43, 0x00, 0x87, 0xE5, 0x3D, 0x00, 0x6C, 0xA2, 0x38, 0x00, 0x53, 0x65, 0x31, 0x00, 0x41, 0x39, 0x2E,
0x00, 0x3A, 0x27, 0x2B, 0x00, 0x34, 0x1A, 0x2A, 0x00, 0x41, 0x38, 0x2E, 0x00, 0x82, 0xD8, 0x3D, 0x00, 0x88, 0xE7, 0x3D, 0x00,
0x8E, 0xF3, 0x41, 0x00, 0x69, 0x95, 0x39, 0x00, 0x3E, 0x33, 0x2C, 0x00, 0x31, 0x11, 0x29, 0x00, 0x2E, 0x0A, 0x29, 0x00, 0x2D,
0x0B, 0x27, 0x00, 0x30, 0x10, 0x29, 0x00, 0x34, 0x18, 0x2A, 0x00, 0x3E, 0x31, 0x2C, 0x00, 0x68, 0x95, 0x39, 0x00, 0x88, 0xE7,
0x3E, 0x00, 0x82, 0xD7, 0x3C, 0x00, 0x84, 0xDD, 0x3C, 0x00, 0x8B, 0xEE, 0x3E, 0x00, 0x85, 0xDF, 0x3D, 0x00, 0x47, 0x48, 0x2E,
0x00, 0x30, 0x0F, 0x29, 0x00, 0x31, 0x13, 0x29, 0x00, 0x48, 0x4D, 0x2E, 0x00, 0x61, 0x7F, 0x39, 0x00, 0x6A, 0x9C, 0x38, 0x00,
0x75, 0xB8, 0x39, 0x00, 0x85, 0xDE, 0x3D, 0x00, 0x8C, 0xEF, 0x3E, 0x00, 0x89, 0xDE, 0x44, 0x00, 0x80, 0xD1, 0x3C, 0x00, 0x3A,
0x28, 0x2C, 0x00, 0x32, 0x16, 0x2A, 0x00, 0x33, 0x17, 0x2A, 0x00, 0x4B, 0x50, 0x30, 0x00, 0x76, 0xBA, 0x3A, 0x00, 0x8A, 0xEF,
0x3C, 0x00, 0x9A, 0xFE, 0x4D, 0x00, 0x95, 0xFF, 0x43, 0x00, 0x93, 0xFF, 0x40, 0x00, 0x4B, 0x52, 0x30, 0x00, 0x7E, 0xCE, 0x3C,
0x00, 0x87, 0xD9, 0x44, 0x00, 0x34, 0x1B, 0x2A, 0x00, 0x65, 0x90, 0x36, 0x00, 0x8E, 0xF6, 0x3D, 0x00, 0x8F, 0xF7, 0x40, 0x00,
0x8B, 0xDD, 0x48, 0x00, 0x73, 0xB1, 0x3A, 0x00, 0x66, 0x95, 0x35, 0x00, 0x66, 0x93, 0x35, 0x00, 0x35, 0x1B, 0x2A, 0x00, 0x8D,
0xE8, 0x45, 0x00, 0x82, 0xD9, 0x3B, 0x00, 0x72, 0xAA, 0x3C, 0x00, 0x95, 0xFD, 0x46, 0x00, 0x8D, 0xF0, 0x40, 0x00, 0x57, 0x70,
0x32, 0x00, 0x3C, 0x2D, 0x2C, 0x00, 0x2F, 0x0D, 0x29, 0x00, 0x81, 0xD4, 0x3D, 0x00, 0x8D, 0xF1, 0x40, 0x00, 0x94, 0xFC, 0x46,
0x00, 0x73, 0xAE, 0x3D, 0x00, 0x45, 0x44, 0x2D, 0x00, 0x94, 0xF5, 0x49, 0x00, 0x90, 0xF0, 0x45, 0x00, 0x73, 0xAF, 0x3B, 0x00,
0x38, 0x21, 0x2C, 0x00, 0x30, 0x11, 0x29, 0x00, 0x2F, 0x0F, 0x28, 0x00, 0x72, 0xAC, 0x3B, 0x00, 0x6A, 0x93, 0x3D, 0x00, 0x2E,
0x0D, 0x27, 0x00, 0x35, 0x1C, 0x2B, 0x00, 0x36, 0x20, 0x2A, 0x00, 0x5E, 0x77, 0x39, 0x00, 0x78, 0xBE, 0x3B, 0x00, 0x36, 0x21,
0x2A, 0x00, 0x71, 0xAB, 0x3B, 0x00, 0x4C, 0x54, 0x30, 0x00, 0x3D, 0x31, 0x2B, 0x00, 0x82, 0xD6, 0x3D, 0x00, 0x79, 0xC5, 0x39,
0x00, 0x9A, 0xFF, 0x4D, 0x00, 0x8A, 0xE8, 0x40, 0x00, 0x8A, 0xE7, 0x40, 0x00, 0x7A, 0xC6, 0x39, 0x00, 0x3D, 0x2E, 0x2C, 0x00,
0x81, 0xD5, 0x3D, 0x00, 0x77, 0xBC, 0x3A, 0x00, 0x31, 0x12, 0x2A, 0x00, 0x69, 0x9B, 0x37, 0x00, 0x8E, 0xF3, 0x40, 0x00, 0x83,
0xDC, 0x3B, 0x00, 0x8C, 0xF6, 0x3B, 0x00, 0x88, 0xD9, 0x45, 0x00, 0x86, 0xE1, 0x3D, 0x00, 0x85, 0xE0, 0x3D, 0x00, 0x7B, 0xC8,
0x39, 0x00, 0x36, 0x1F, 0x29, 0x00, 0x55, 0x6B, 0x32, 0x00, 0x8A, 0xEE, 0x3C, 0x00, 0x48, 0x4B, 0x2E, 0x00, 0x51, 0x61, 0x31,
0x00, 0x8C, 0xE0, 0x48, 0x00, 0x8B, 0xDE, 0x47, 0x00, 0x98, 0xEE, 0x55, 0x00, 0x5D, 0x79, 0x36, 0x00, 0x3A, 0x2A, 0x2B, 0x00,
0x3A, 0x29, 0x2B, 0x00, 0x5C, 0x78, 0x36, 0x00, 0x60, 0x7C, 0x3A, 0x00, 0x3D, 0x30, 0x2C, 0x00, 0x99, 0xFD, 0x4C, 0x00, 0x66,
0x8A, 0x3C, 0x00, 0x2D, 0x0C, 0x27, 0x00, 0x42, 0x3C, 0x2E, 0x00, 0x84, 0xDA, 0x3E, 0x00, 0x88, 0xE5, 0x3F, 0x00, 0x37, 0x22,
0x2B, 0x00, 0x2E, 0x0B, 0x28, 0x00, 0x6A, 0x9B, 0x37, 0x00, 0x72, 0xAF, 0x3A, 0x00, 0x32, 0x15, 0x29, 0x00, 0x2A, 0x00, 0x28,
0x00, 0x5B, 0x75, 0x35, 0x00, 0x89, 0xE8, 0x3D, 0x00, 0x78, 0xBF, 0x3A, 0x00, 0x73, 0xB4, 0x38, 0x00, 0x83, 0xDA, 0x3C, 0x00,
0x84, 0xDE, 0x3C, 0x00, 0x85, 0xDD, 0x3E, 0x00, 0x86, 0xDE, 0x40, 0x00, 0x84, 0xDE, 0x3B, 0x00, 0x86, 0xE2, 0x3C, 0x00, 0x85,
0xDD, 0x3F, 0x00, 0x87, 0xE2, 0x3F, 0x00, 0x87, 0xE1, 0x3E, 0x00, 0x85, 0xDE, 0x3E, 0x00, 0x89, 0xE2, 0x41, 0x00, 0x89, 0xE2,
0x43, 0x00, 0x84, 0xDC, 0x3E, 0x00, 0x83, 0xD8, 0x3E, 0x00, 0x90, 0xF6, 0x41, 0x00, 0x2B, 0x04, 0x28, 0x00, 0x8C, 0xE3, 0x47,
0x00, 0x8B, 0xDE, 0x48, 0x00, 0x8A, 0xDC, 0x47, 0x00, 0x8A, 0xDD, 0x47, 0x00, 0x8D, 0xDD, 0x4A, 0x00, 0x8A, 0xDE, 0x47, 0x00,
0x8B, 0xDD, 0x49, 0x00, 0x8B, 0xE0, 0x46, 0x00, 0x9A, 0xF2, 0x55, 0x00, 0x59, 0x70, 0x35, 0x00, 0x8F, 0xDE, 0x4F, 0x00, 0x82,
0xDC, 0x3B, 0x00, 0x82, 0xDB, 0x39, 0x00, 0x7F, 0xD7, 0x38, 0x00, 0x92, 0xF0, 0x48, 0x00, 0x33, 0x19, 0x29, 0x00, 0x87, 0xDD,
0x42, 0x00, 0x87, 0xDD, 0x41, 0x00, 0x92, 0xEC, 0x4B, 0x00, 0x78, 0xBD, 0x3C, 0x00, 0x86, 0xDD, 0x3F, 0x00, 0x81, 0xD9, 0x39,
0x00, 0x7B, 0xC4, 0x3C, 0x00, 0x34, 0x1A, 0x29, 0x00, 0x89, 0xDD, 0x44, 0x00, 0x86, 0xDC, 0x40, 0x00, 0x88, 0xDD, 0x44, 0x00,
0x87, 0xDE, 0x41, 0x00, 0x99, 0xFA, 0x4F, 0x00, 0x7B, 0xC3, 0x3E, 0x00, 0x83, 0xD7, 0x3F, 0x00, 0x8B, 0xED, 0x3E, 0x00, 0x40,
0x33, 0x2F, 0x00, 0x39, 0x27, 0x2B, 0x00, 0x81, 0xD7, 0x3B, 0x00, 0x3B, 0x2C, 0x2A, 0x00, 0x33, 0x18, 0x29, 0x00, 0x38, 0x22,
0x2B, 0x00, 0x85, 0xDA, 0x40, 0x00, 0x89, 0xEA, 0x3D, 0x00, 0x6F, 0xA9, 0x38, 0x00, 0x70, 0xAB, 0x38, 0x00, 0x85, 0xDD, 0x3D,
0x00, 0x88, 0xE1, 0x40, 0x00, 0x36, 0x1F, 0x2B, 0x00, 0x30, 0x13, 0x28, 0x00, 0x68, 0x9A, 0x36, 0x00, 0x90, 0xFB, 0x3F, 0x00,
0x8A, 0xDD, 0x46, 0x00, 0x8D, 0xE9, 0x45, 0x00, 0x5A, 0x71, 0x36, 0x00, 0x27, 0x00, 0x24, 0x00, 0x73, 0x9F, 0x45, 0x00, 0x97,
0xFE, 0x4A, 0x00, 0x86, 0xD8, 0x43, 0x00, 0x73, 0xA1, 0x45, 0x00, 0x8E, 0xDF, 0x4C, 0x00, 0x85, 0xDB, 0x40, 0x00, 0x72, 0xB5,
0x37, 0x00, 0x95, 0xF4, 0x4B, 0x00, 0x73, 0xB6, 0x37, 0x00, 0x88, 0xE9, 0x3C, 0x00, 0x8A, 0xDB, 0x48, 0x00, 0x8C, 0xDE, 0x49,
0x00, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x01, 0x02, 0x03, 0x04, 0xAE, 0x06, 0xF1, 0x02, 0x04, 0x04, 0x02, 0xF1, 0x06, 0xAE, 0x04, 0x03, 0x02, 0x01, 0x00, 0x01,
0x0A, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0xAE, 0xC7, 0xF1, 0x02, 0x04,
0x04, 0x02, 0xF1, 0xC7, 0xAE, 0x04, 0x03, 0x02, 0x01, 0x00, 0x01, 0x0A, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x01, 0x02, 0x03, 0x0B, 0xAE, 0xEF, 0xF0, 0x02, 0x01, 0x01, 0x02, 0xB4, 0xEF, 0xAE, 0x0B, 0x03, 0x02, 0x01, 0x00,
0x01, 0x0A, 0x01, 0x00, 0x00, 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x04, 0x05, 0xEB, 0xA7, 0xD1, 0xEC, 0xED, 0x96,
0x04, 0x04, 0x96, 0xED, 0xEE, 0xD1, 0xA7, 0xEB, 0x05, 0x04, 0x01, 0x04, 0xCA, 0x04, 0x01, 0x01, 0x01, 0xCA, 0xCA, 0xCA, 0xCA,
0xCA, 0xCA, 0xCA, 0xCC, 0xE2, 0x8A, 0xE3, 0xE4, 0xE5, 0xE6, 0xE7, 0xE8, 0xE8, 0xE7, 0xE9, 0xE5, 0xBB, 0xE3, 0x8A, 0xE2, 0xCC,
0xCA, 0xCC, 0xEA, 0xCC, 0xCA, 0xCA, 0xCA, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x04, 0x08, 0xDD, 0x55, 0xDE, 0x2C, 0xDF,
0xE0, 0xE1, 0xE1, 0xE0, 0xDF, 0x2C, 0xDE, 0x55, 0xDD, 0x08, 0x04, 0x01, 0x04, 0xCA, 0x04, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x01, 0xC6, 0xD8, 0xD9, 0xAB, 0x78, 0x6A, 0x28, 0xDA, 0xDB, 0x28, 0x6A, 0x5A, 0xDC, 0xD9, 0xD8, 0xC6,
0x01, 0x00, 0x01, 0x0A, 0x01, 0x00, 0x00, 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x04, 0x05, 0x03, 0xD4, 0xD1, 0x31,
0xD5, 0xD6, 0x98, 0xD7, 0xD6, 0xD5, 0x0B, 0x32, 0xD4, 0x03, 0x05, 0x04, 0x01, 0x04, 0xCA, 0x04, 0x01, 0x01, 0x01, 0x02, 0x02,
0x02, 0x02, 0x02, 0x02, 0x02, 0x05, 0xC3, 0xC2, 0xA4, 0xD0, 0xD1, 0xB3, 0xD2, 0xD3, 0xD3, 0xD2, 0x4F, 0x32, 0xD0, 0xA4, 0xC2,
0xC3, 0x05, 0x02, 0x05, 0xB7, 0x05, 0x02, 0x02, 0x02, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0xCB, 0xC2, 0xCC, 0x02, 0xCD,
0x79, 0xCE, 0xCF, 0xC1, 0xC1, 0xCF, 0xCE, 0x79, 0xCD, 0x02, 0xCC, 0xC2, 0xCB, 0x03, 0xCB, 0xB3, 0xCB, 0x03, 0x03, 0x03, 0x04,
0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x7E, 0x05, 0xC6, 0x7E, 0x00, 0xC7, 0x15, 0xC8, 0xC9, 0xC9, 0xC8, 0x15, 0xC7, 0x00, 0x7E,
0xC6, 0x05, 0x7E, 0x04, 0x7E, 0xCA, 0x7E, 0x04, 0x04, 0x04, 0xAE, 0xAE, 0xAE, 0xAE, 0xAE, 0xAE, 0xAE, 0x00, 0x03, 0xC3, 0x00,
0x05, 0x55, 0xC4, 0xC5, 0xC1, 0xC1, 0xC5, 0xC4, 0x55, 0x05, 0x00, 0xC3, 0x03, 0x00, 0xAE, 0x00, 0x3D, 0x00, 0xAE, 0xAE, 0xAE,
0xBD, 0xBD, 0xBD, 0xBD, 0xBD, 0xBD, 0x7E, 0xBE, 0x00, 0x05, 0xBE, 0x7E, 0xBF, 0xC0, 0x5C, 0xC1, 0xC1, 0x5C, 0xC0, 0xBF, 0x7E,
0xBE, 0x05, 0x00, 0xBE, 0x7E, 0xBE, 0xC2, 0x06, 0xBD, 0xBD, 0xBD, 0xB3, 0xB3, 0xB3, 0xB4, 0xB5, 0xB3, 0xB3, 0xB5, 0xB6, 0xB6,
0xB7, 0xB8, 0xB9, 0xBA, 0xBB, 0x6B, 0x6B, 0xBB, 0xBA, 0xB9, 0xB8, 0xB7, 0xB6, 0xB6, 0xB5, 0xB3, 0xB5, 0xBC, 0xB4, 0xB3, 0xB3,
0xB3, 0x02, 0x02, 0xA8, 0xA9, 0xAA, 0xA8, 0x02, 0xAB, 0xAC, 0xAD, 0xAE, 0xAF, 0xB0, 0x8F, 0xB1, 0x71, 0x2D, 0xB1, 0x9E, 0xB0,
0xAF, 0xAE, 0xAD, 0xAC, 0xAB, 0x02, 0xA4, 0xB2, 0xAA, 0xA8, 0x02, 0x02, 0x04, 0x31, 0xA3, 0x04, 0x31, 0x82, 0x3B, 0xA3, 0xA4,
0xA5, 0xA6, 0x82, 0xA7, 0x8E, 0x20, 0x78, 0x78, 0x20, 0x8E, 0xA7, 0x82, 0xA6, 0xA5, 0xA4, 0xA3, 0x3B, 0x82, 0x3D, 0x04, 0xA3,
0x31, 0x04, 0x09, 0x9F, 0xA0, 0x21, 0x2C, 0xA1, 0x47, 0x52, 0x5B, 0x5A, 0xA2, 0x1C, 0x81, 0x8D, 0x8E, 0x91, 0x91, 0x8E, 0x8D,
0x81, 0x1C, 0xA2, 0x5A, 0x5B, 0x52, 0x47, 0xA1, 0x2C, 0x21, 0xA0, 0x9F, 0x09, 0x96, 0x97, 0x16, 0x98, 0x99, 0x9A, 0x46, 0x9B,
0x28, 0x9C, 0x6D, 0x76, 0x7D, 0x8C, 0x9D, 0x8E, 0x8E, 0x9D, 0x9E, 0x7D, 0x75, 0x6D, 0x9C, 0x65, 0x9B, 0x46, 0x39, 0x99, 0x98,
0x16, 0x97, 0x96, 0x4F, 0x89, 0x15, 0x1F, 0x69, 0x38, 0x45, 0x8A, 0x78, 0x66, 0x6C, 0x74, 0x4A, 0x8B, 0x8C, 0x8D, 0x8E, 0x8F,
0x8B, 0x80, 0x45, 0x90, 0x66, 0x91, 0x8A, 0x92, 0x93, 0x94, 0x95, 0x15, 0x89, 0x4F, 0x7E, 0x0D, 0x14, 0x1E, 0x29, 0x37, 0x44,
0x14, 0x59, 0x65, 0x6B, 0x73, 0x7F, 0x80, 0x25, 0x81, 0x82, 0x25, 0x80, 0x7F, 0x83, 0x84, 0x65, 0x85, 0x4D, 0x86, 0x87, 0x29,
0x88, 0x14, 0x0D, 0x7E, 0x05, 0x0C, 0x13, 0x1D, 0x28, 0x2C, 0x43, 0x4E, 0x72, 0x64, 0x53, 0x5A, 0x73, 0x74, 0x75, 0x1C, 0x1C,
0x76, 0x74, 0x77, 0x78, 0x6A, 0x64, 0x79, 0x4E, 0x7A, 0x2C, 0x7B, 0x7C, 0x7D, 0x0C, 0x05, 0x04, 0x0B, 0x12, 0x1C, 0x27, 0x36,
0x42, 0x4D, 0x5D, 0x63, 0x69, 0x6A, 0x6B, 0x6C, 0x6D, 0x1A, 0x1A, 0x6D, 0x6C, 0x6E, 0x53, 0x69, 0x6F, 0x5D, 0x19, 0x70, 0x36,
0x71, 0x24, 0x12, 0x0B, 0x04, 0x03, 0x03, 0x11, 0x1B, 0x2E, 0x35, 0x41, 0x4C, 0x5E, 0x62, 0x63, 0x64, 0x65, 0x66, 0x2C, 0x5A,
0x5A, 0x2C, 0x66, 0x65, 0x64, 0x67, 0x62, 0x5E, 0x52, 0x40, 0x65, 0x68, 0x1B, 0x11, 0x03, 0x03, 0x02, 0x02, 0x02, 0x02, 0x25,
0x34, 0x40, 0x4B, 0x56, 0x57, 0x58, 0x16, 0x59, 0x5A, 0x41, 0x5B, 0x5B, 0x41, 0x5A, 0x59, 0x5C, 0x5D, 0x5E, 0x5F, 0x21, 0x41,
0x60, 0x61, 0x05, 0x02, 0x02, 0x02, 0x01, 0x01, 0x01, 0x09, 0x24, 0x33, 0x3F, 0x2C, 0x4B, 0x4C, 0x4D, 0x4E, 0x14, 0x4F, 0x50,
0x51, 0x51, 0x50, 0x4F, 0x14, 0x4E, 0x4D, 0x52, 0x53, 0x2C, 0x3F, 0x01, 0x54, 0x55, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x1A,
0x23, 0x32, 0x3E, 0x3F, 0x40, 0x41, 0x42, 0x43, 0x44, 0x45, 0x46, 0x47, 0x47, 0x46, 0x45, 0x44, 0x43, 0x48, 0x41, 0x40, 0x3F,
0x49, 0x3C, 0x4A, 0x1A, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1A, 0x30, 0x32, 0x33, 0x34, 0x35, 0x36, 0x2C, 0x37, 0x38,
0x39, 0x3A, 0x3A, 0x39, 0x38, 0x37, 0x2C, 0x36, 0x35, 0x34, 0x3B, 0x3C, 0x30, 0x3D, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x1A, 0x23, 0x24, 0x25, 0x26, 0x27, 0x28, 0x29, 0x2A, 0x2B, 0x2C, 0x2C, 0x2B, 0x2A, 0x29, 0x28, 0x2D, 0x2E, 0x13,
0x2F, 0x30, 0x31, 0x0A, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1A, 0x09, 0x02, 0x1B, 0x1C, 0x1D, 0x1E,
0x1F, 0x20, 0x21, 0x21, 0x20, 0x22, 0x1E, 0x1D, 0x1C, 0x1B, 0x02, 0x09, 0x1A, 0x01, 0x0A, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x11, 0x12, 0x13, 0x14, 0x15, 0x16, 0x17, 0x17, 0x16, 0x18, 0x19, 0x13, 0x12, 0x11,
0x02, 0x01, 0x00, 0x01, 0x0A, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x0B, 0x0C,
0x0D, 0x0E, 0x0F, 0x10, 0x10, 0x0F, 0x0E, 0x0D, 0x0C, 0x0B, 0x03, 0x02, 0x01, 0x00, 0x01, 0x0A, 0x01, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09, 0x09, 0x08, 0x07, 0x06, 0x05, 0x04,
0x03, 0x02, 0x01, 0x00, 0x01, 0x0A, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00};

View File

@ -5,6 +5,7 @@
#include "RTC.h"
#include "Router.h"
#include "configuration.h"
#include "gps/GeoCoord.h"
#include <Arduino.h>
#include <SPIFFS.h>
//#include <assert.h>
@ -184,27 +185,6 @@ ProcessMessage RangeTestPluginRadio::handleReceived(const MeshPacket &mp)
return ProcessMessage::CONTINUE; // Let others look at this message also if they want
}
/// Ported from my old java code, returns distance in meters along the globe
/// surface (by magic?)
float RangeTestPluginRadio::latLongToMeter(double lat_a, double lng_a, double lat_b, double lng_b)
{
double pk = (180 / 3.14169);
double a1 = lat_a / pk;
double a2 = lng_a / pk;
double b1 = lat_b / pk;
double b2 = lng_b / pk;
double cos_b1 = cos(b1);
double cos_a1 = cos(a1);
double t1 = cos_a1 * cos(a2) * cos_b1 * cos(b2);
double t2 = cos_a1 * sin(a2) * cos_b1 * sin(b2);
double t3 = sin(a1) * sin(b1);
double tt = acos(t1 + t2 + t3);
if (isnan(tt))
tt = 0.0; // Must have been the same point?
return (float)(6366000 * tt);
}
bool RangeTestPluginRadio::appendFile(const MeshPacket &mp)
{
auto &p = mp.decoded;
@ -303,7 +283,7 @@ bool RangeTestPluginRadio::appendFile(const MeshPacket &mp)
fileToAppend.printf("%f,", mp.rx_snr); // RX SNR
if (n->position.latitude_i && n->position.longitude_i && gpsStatus->getLatitude() && gpsStatus->getLongitude()) {
float distance = latLongToMeter(n->position.latitude_i * 1e-7, n->position.longitude_i * 1e-7,
float distance = GeoCoord::latLongToMeter(n->position.latitude_i * 1e-7, n->position.longitude_i * 1e-7,
gpsStatus->getLatitude() * 1e-7, gpsStatus->getLongitude() * 1e-7);
fileToAppend.printf("%f,", distance); // Distance in meters
} else {