Initial Commit
This commit is contained in:
parent
f00ea6624f
commit
d133abefec
5
.gitignore
vendored
Normal file
5
.gitignore
vendored
Normal file
@ -0,0 +1,5 @@
|
||||
.pio
|
||||
.vscode/.browse.c_cpp.db*
|
||||
.vscode/c_cpp_properties.json
|
||||
.vscode/launch.json
|
||||
.vscode/ipch
|
10
.vscode/extensions.json
vendored
Normal file
10
.vscode/extensions.json
vendored
Normal file
@ -0,0 +1,10 @@
|
||||
{
|
||||
// See http://go.microsoft.com/fwlink/?LinkId=827846
|
||||
// for the documentation about the extensions.json format
|
||||
"recommendations": [
|
||||
"platformio.platformio-ide"
|
||||
],
|
||||
"unwantedRecommendations": [
|
||||
"ms-vscode.cpptools-extension-pack"
|
||||
]
|
||||
}
|
247
include/astm.h
Normal file
247
include/astm.h
Normal file
@ -0,0 +1,247 @@
|
||||
/*
|
||||
___ _ ___ _
|
||||
| _ \ ( )_ | _ \ (_ )
|
||||
| (_) ) _ | _) _ _ __ | (_) ) __ _ _ | | ___ ___
|
||||
| / / _ \| | / _ \( __) | / / __ \/ _ )| |/ _ _ \
|
||||
| |\ \( (_) ) |_( (_) ) | | |\ \( ___/ (_| || || ( ) ( ) |
|
||||
(_) (_)\___/ \__)\___/(_) (_) (_)\____)\__ _)___)_) (_) (_)
|
||||
|
||||
* This file is part of Rotor Realm RemoteID
|
||||
*
|
||||
* Copyright (c) 2024 Rotor Realm
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*/
|
||||
// Definitions and structures required by ASTM F3411-22a standard
|
||||
#ifndef ASTM_F3411_22A_H
|
||||
#define ASTM_F3411_22A_H
|
||||
|
||||
// Enumeration for message types in ASTM F3411-22a standard
|
||||
typedef enum Messages {
|
||||
msBasicID = 0x0, // Basic ID message type (0x0)
|
||||
msLocation = 0x1, // Location/Vector message type (0x1)
|
||||
msAuthentication = 0x2, // Authentication message type (0x2)
|
||||
msSelfID = 0x3, // Self ID message type (0x3)
|
||||
msSystem = 0x4, // System message type (0x4)
|
||||
msOperatorID = 0x5, // Operator ID message type (0x5)
|
||||
msMessagePack = 0xF // Message Pack message type (0xF)
|
||||
} msType;
|
||||
|
||||
// Enumeration for different types of IDs in ASTM F3411-22a standard
|
||||
typedef enum ID {
|
||||
idNone = 0, // No ID type (0)
|
||||
idSerial = 1, // Serial number ID type (1)
|
||||
idCAA = 2, // CAA (Civil Aviation Authority) compliant ID type (2)
|
||||
idUTM = 3, // UTM (Unmanned Traffic Management) compliant ID type (3)
|
||||
idSession = 4 // Session ID type (4)
|
||||
} idTypes;
|
||||
|
||||
// Enumeration for different types of Unmanned Aircraft (UA) in ASTM F3411-22a standard
|
||||
typedef enum UA {
|
||||
uaUndefined = 0, // Undefined UA type (0)
|
||||
uaAeroplane = 1, // Aeroplane UA type (1)
|
||||
uaMultirotor = 2, // Multirotor UA type (2)
|
||||
uaGyroplane = 3, // Gyroplane UA type (3)
|
||||
uaFixedWing = 4, // Fixed-wing UA type (4)
|
||||
uaOrnithopter = 5, // Ornithopter UA type (5)
|
||||
uaGlider = 6, // Glider UA type (6)
|
||||
uaKite = 7, // Kite UA type (7)
|
||||
uaFreeBalloon = 8, // Free balloon UA type (8)
|
||||
uaCaptiveBalloon = 9, // Captive balloon UA type (9)
|
||||
uaAirship = 10, // Airship UA type (10)
|
||||
uaFreeFall = 11, // Free-fall UA type (11)
|
||||
uaRocket = 12, // Rocket UA type (12)
|
||||
uaTethered = 13, // Tethered UA type (13)
|
||||
uaGround = 14, // Ground UA type (14)
|
||||
uaOther = 15 // Other UA type (15)
|
||||
} uaTypes;
|
||||
|
||||
// Enumeration for different types of Operational Status in ASTM F3411-22a standard
|
||||
typedef enum OperationalStatus {
|
||||
osUndeclared = 0, // Undeclared operational status (0)
|
||||
osGround = 1, // Ground operational status (1)
|
||||
osAirborne = 2, // Airborne operational status (2)
|
||||
osEmergency = 3, // Emergency operational status (3)
|
||||
osSystemFailure = 4 // System failure operational status (4)
|
||||
} osTypes;
|
||||
|
||||
// Enumeration for different types of Operator Location in ASTM F3411-22a standard
|
||||
typedef enum OperatorLocation {
|
||||
olTakeoff = 0, // Operator location at the takeoff point (0)
|
||||
olDynamic = 1, // Dynamic operator location (moving) (1)
|
||||
olFixed = 2 // Fixed operator location (stationary) (2)
|
||||
} olTypes;
|
||||
|
||||
// Enumeration for different classification types in ASTM F3411-22a standard
|
||||
// Enumeration for different types of Classification in ASTM F3411-22a standard
|
||||
typedef enum Classification {
|
||||
cfUndeclared = 0, // Undeclared classification (0)
|
||||
cfEuropeanUnion = 1, // European Union classification (1)
|
||||
// 2 - 7 Reserved for future use
|
||||
} cfTypes;
|
||||
|
||||
// Enumeration for different types of Categories in ASTM F3411-22a standard
|
||||
typedef enum Categories {
|
||||
euUndefined = 0, // Undefined category (0)
|
||||
euOpen = 1, // Open category (1)
|
||||
euSpecific = 2, // Specific category (2)
|
||||
euCertified = 3 // Certified category (3)
|
||||
// 4 - 15 Reserved for future use
|
||||
} euTypes;
|
||||
|
||||
// Enumeration for different types of Classes in ASTM F3411-22a standard
|
||||
typedef enum Classes {
|
||||
clUndefined = 0, // Undefined class (0)
|
||||
clClass0 = 1, // Class 0 (1)
|
||||
clClass1 = 2, // Class 1 (2)
|
||||
clClass2 = 3, // Class 2 (3)
|
||||
clClass3 = 4, // Class 3 (4)
|
||||
clClass4 = 5, // Class 4 (5)
|
||||
clClass5 = 6 // Class 5 (6)
|
||||
// 7 - 15 Reserved for future use
|
||||
} clTypes;
|
||||
|
||||
|
||||
// Structure for Message Header as defined in ASTM F3411-22a standard
|
||||
typedef struct MessageHeader {
|
||||
uint8_t messageType_protocolVersion; // Bits 7..4: Message Type, Bits 3..0: Protocol Version
|
||||
} MessageHeader;
|
||||
|
||||
// Structure for Basic ID Message as defined in ASTM F3411-22a standard
|
||||
typedef struct BasicIDMessage {
|
||||
MessageHeader header; // 1 byte
|
||||
uint8_t idType_uaType; // ID Type (upper 4 bits) and UA Type (lower 4 bits) - 1 byte
|
||||
uint8_t uasID[20]; // UAS ID (20 bytes)
|
||||
uint8_t reserved[3]; // Reserved bytes (3 bytes)
|
||||
} BasicIDMessage;
|
||||
|
||||
|
||||
// Structure for Location/Vector Message as defined in ASTM F3411-22a standard
|
||||
typedef struct LocationMessage {
|
||||
MessageHeader header; // 1 byte
|
||||
uint8_t status; // 1 byte
|
||||
uint8_t trackDirection; // 1 byte
|
||||
uint8_t speed; // 1 byte
|
||||
int8_t verticalSpeed; // 1 byte
|
||||
int32_t latitude; // 4 bytes
|
||||
int32_t longitude; // 4 bytes
|
||||
int16_t pressureAltitude; // 2 bytes
|
||||
int16_t geodeticAltitude; // 2 bytes
|
||||
int16_t height; // 2 bytes
|
||||
uint8_t horVertAccuracy; // 1 byte (Combined Horizontal and Vertical Accuracy)
|
||||
uint8_t baroSpeedAccuracy; // 1 byte (Combined Baro Altitude Accuracy and Speed Accuracy)
|
||||
uint16_t timestamp; // 2 bytes
|
||||
uint8_t reservedTimestampAccuracy; // 1 byte (Combined Reserved and Timestamp Accuracy)
|
||||
uint8_t reserved; // 1 byte
|
||||
} __attribute__((packed)) LocationMessage;
|
||||
|
||||
|
||||
// Structure for Authentication Message as defined in ASTM F3411-22a standard
|
||||
typedef struct AuthenticationMessage {
|
||||
MessageHeader header; // Message header
|
||||
uint8_t authType; // Authentication Type
|
||||
uint8_t authData[23]; // Authentication Data
|
||||
} AuthenticationMessage;
|
||||
|
||||
// Structure for Self-ID Message as defined in ASTM F3411-22a standard
|
||||
typedef struct SelfIDMessage {
|
||||
MessageHeader header; // Message header
|
||||
uint8_t descriptionType; // Description Type
|
||||
char description[23]; // ASCII Text Description (padded with nulls)
|
||||
} SelfIDMessage;
|
||||
|
||||
// Structure for System Message as defined in ASTM F3411-22a standard
|
||||
typedef struct SystemMessage {
|
||||
MessageHeader header; // Message header
|
||||
uint8_t flags; // Flags (1 byte)
|
||||
int32_t operatorLatitude; // Latitude of Remote Pilot (4 bytes)
|
||||
int32_t operatorLongitude; // Longitude of Remote Pilot (4 bytes)
|
||||
uint16_t areaCount; // Number of aircraft in Area (2 bytes)
|
||||
uint16_t areaRadius; // Radius of area (2 bytes)
|
||||
int16_t areaCeiling; // Area ceiling (2 bytes)
|
||||
int16_t areaFloor; // Area floor (2 bytes)
|
||||
uint8_t classification; // Classification (1 byte)
|
||||
int16_t operatorAltitude; // Altitude of Remote Pilot (2 bytes)
|
||||
uint32_t timestamp; // Timestamp (4 bytes)
|
||||
uint8_t reserved; // Reserved (1 byte)
|
||||
} __attribute__((packed)) SystemMessage;
|
||||
|
||||
// Structure for Operator-ID Message as defined in ASTM F3411-22a standard
|
||||
typedef struct OperatorIDMessage {
|
||||
MessageHeader header; // Message header
|
||||
uint8_t operatorIDType; // Operator ID Type (0: Operator ID, 1-200: Reserved, 201-255: Available for private use)
|
||||
char operatorID[20]; // ASCII Text for Operator ID (padded with nulls)
|
||||
uint8_t reserved[3]; // Reserved bytes
|
||||
} OperatorIDMessage;
|
||||
|
||||
// Horizontal Accuracy Enumeration
|
||||
typedef enum HorizontalAccuracy {
|
||||
H_ACC_UNKNOWN = 0,
|
||||
H_ACC_10_NM = 1,
|
||||
H_ACC_4_NM = 2,
|
||||
H_ACC_2_NM = 3,
|
||||
H_ACC_1_NM = 4,
|
||||
H_ACC_0_5_NM = 5,
|
||||
H_ACC_0_3_NM = 6,
|
||||
H_ACC_0_1_NM = 7,
|
||||
H_ACC_0_05_NM = 8,
|
||||
H_ACC_30_M = 9,
|
||||
H_ACC_10_M = 10,
|
||||
H_ACC_3_M = 11,
|
||||
H_ACC_1_M = 12,
|
||||
H_ACC_RESERVED = 13
|
||||
} HorizontalAccuracy;
|
||||
|
||||
// Vertical Accuracy Enumeration
|
||||
typedef enum VerticalAccuracy {
|
||||
V_ACC_UNKNOWN = 0,
|
||||
V_ACC_150_M = 1,
|
||||
V_ACC_45_M = 2,
|
||||
V_ACC_25_M = 3,
|
||||
V_ACC_10_M = 4,
|
||||
V_ACC_3_M = 5,
|
||||
V_ACC_1_M = 6
|
||||
} VerticalAccuracy;
|
||||
|
||||
// Speed Accuracy Enumeration
|
||||
typedef enum SpeedAccuracy {
|
||||
S_ACC_UNKNOWN = 0,
|
||||
S_ACC_10_M_S = 1,
|
||||
S_ACC_3_M_S = 2,
|
||||
S_ACC_1_M_S = 3,
|
||||
S_ACC_0_3_M_S = 4
|
||||
} SpeedAccuracy;
|
||||
|
||||
// Define VendorSpecificTag structure
|
||||
typedef struct VendorSpecificTag {
|
||||
uint8_t length;
|
||||
uint8_t oui[3];
|
||||
uint8_t vendType;
|
||||
uint8_t msgCounter;
|
||||
uint8_t advData[256]; // Example size, should be adjusted according to the actual requirement
|
||||
} VendorSpecificTag;
|
||||
|
||||
typedef struct MessagePack {
|
||||
MessageHeader header; // Message header
|
||||
uint8_t messageSize; // Message Size (25 Bytes)
|
||||
uint8_t numMessages; // Number of messages in the pack (up to 9)
|
||||
uint8_t messages[9][25]; // Array of messages, up to 9 messages, each 25 bytes long
|
||||
} MessagePack;
|
||||
|
||||
#endif // ASTM_F3411_22A_H
|
38
include/display.h
Normal file
38
include/display.h
Normal file
@ -0,0 +1,38 @@
|
||||
/*
|
||||
___ _ ___ _
|
||||
| _ \ ( )_ | _ \ (_ )
|
||||
| (_) ) _ | _) _ _ __ | (_) ) __ _ _ | | ___ ___
|
||||
| / / _ \| | / _ \( __) | / / __ \/ _ )| |/ _ _ \
|
||||
| |\ \( (_) ) |_( (_) ) | | |\ \( ___/ (_| || || ( ) ( ) |
|
||||
(_) (_)\___/ \__)\___/(_) (_) (_)\____)\__ _)___)_) (_) (_)
|
||||
|
||||
* This file is part of Rotor Realm RemoteID
|
||||
*
|
||||
* Copyright (c) 2024 Rotor Realm
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*/
|
||||
#ifndef DISPLAY_H
|
||||
#define DISPLAY_H
|
||||
#include <Arduino.h>
|
||||
|
||||
void displaySetup(const char* ssid);
|
||||
void displayTask(void * parameters);
|
||||
|
||||
#endif
|
246
include/enc.h
Normal file
246
include/enc.h
Normal file
@ -0,0 +1,246 @@
|
||||
/*
|
||||
___ _ ___ _
|
||||
| _ \ ( )_ | _ \ (_ )
|
||||
| (_) ) _ | _) _ _ __ | (_) ) __ _ _ | | ___ ___
|
||||
| / / _ \| | / _ \( __) | / / __ \/ _ )| |/ _ _ \
|
||||
| |\ \( (_) ) |_( (_) ) | | |\ \( ___/ (_| || || ( ) ( ) |
|
||||
(_) (_)\___/ \__)\___/(_) (_) (_)\____)\__ _)___)_) (_) (_)
|
||||
|
||||
* This file is part of Rotor Realm RemoteID
|
||||
*
|
||||
* Copyright (c) 2024 Rotor Realm
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*/
|
||||
#ifndef ENCODERS_H
|
||||
#define ENCODERS_H
|
||||
|
||||
#include <astm.h>
|
||||
|
||||
// Function declarations for encoding messages
|
||||
inline void encodeMessageHeader(MessageHeader *header, uint8_t messageType, uint8_t protocolVersion);
|
||||
inline void encodeBasicIDMessage(BasicIDMessage *msg, idTypes idType, uaTypes uaType, const char *uasID);
|
||||
inline void encodeLocationMessage(LocationMessage *msg, uint8_t status, uint8_t trackDirection, uint8_t speed, int8_t verticalSpeed, float latitude, float longitude, float pressureAltitude, float geodeticAltitude, int16_t height, uint32_t horAccuracy, uint32_t vertAccuracy, uint32_t speedAccuracy, uint16_t timestamp);
|
||||
inline void encodeAuthenticationMessage(AuthenticationMessage *msg, uint8_t authType, const uint8_t *authData);
|
||||
inline void encodeSelfIDMessage(SelfIDMessage *msg, uint8_t descriptionType, const char *description);
|
||||
inline void encodeSystemMessage(SystemMessage *msg, uint8_t operatorLocationType, int32_t operatorLatitude, int32_t operatorLongitude, uint16_t areaCount, uint16_t areaRadius, int16_t areaCeiling, int16_t areaFloor, uint8_t classificationType, uint8_t uaCategory, uint8_t uaClass, int16_t operatorAltitude, uint32_t timestamp);
|
||||
inline void encodeOperatorIDMessage(OperatorIDMessage *msg, uint8_t operatorIDType, const char *operatorID);
|
||||
inline void encodeVendorSpecificTag(VendorSpecificTag *vendorTag, MessagePack *messagePack);
|
||||
inline uint8_t encodeDirection(uint16_t direction, uint8_t *directionSegment);
|
||||
inline uint8_t encodeSpeed(float speed, uint8_t *speedMultiplier);
|
||||
inline int32_t convertLatLonFormat(float value);
|
||||
inline int8_t encodeVerticalSpeed(float verticalSpeed);
|
||||
inline uint16_t encodeAltitude(float altitude);
|
||||
inline uint16_t encodeTimestamp(float timestamp);
|
||||
|
||||
inline uint8_t convertHorizontalAccuracy(uint32_t accuracy) {
|
||||
if (accuracy >= 18520000) return 0;
|
||||
if (accuracy >= 7408000) return 1;
|
||||
if (accuracy >= 3704000) return 2;
|
||||
if (accuracy >= 1852000) return 3;
|
||||
if (accuracy >= 926000) return 4;
|
||||
if (accuracy >= 555600) return 5;
|
||||
if (accuracy >= 185200) return 6;
|
||||
if (accuracy >= 92600) return 7;
|
||||
if (accuracy >= 30000) return 8;
|
||||
if (accuracy >= 10000) return 9;
|
||||
if (accuracy >= 3000) return 10;
|
||||
if (accuracy >= 1000) return 11;
|
||||
if (accuracy >= 100) return 12;
|
||||
return 13;
|
||||
}
|
||||
|
||||
inline uint8_t convertVerticalAccuracy(uint32_t accuracy) {
|
||||
if (accuracy >= 15000) return 0;
|
||||
if (accuracy >= 4500) return 1;
|
||||
if (accuracy >= 2500) return 2;
|
||||
if (accuracy >= 1000) return 3;
|
||||
if (accuracy >= 300) return 4;
|
||||
if (accuracy >= 100) return 5;
|
||||
return 6;
|
||||
}
|
||||
|
||||
inline uint8_t convertSpeedAccuracy(uint32_t accuracy) {
|
||||
if (accuracy >= 10000) return 0;
|
||||
if (accuracy >= 3000) return 1;
|
||||
if (accuracy >= 1000) return 2;
|
||||
if (accuracy >= 300) return 3;
|
||||
return 4;
|
||||
}
|
||||
|
||||
inline uint8_t encodeTrackDirection(float course) {
|
||||
if (course < 0 || course > 359) {
|
||||
return 0; // Default value if the course is out of range
|
||||
}
|
||||
uint8_t direction = static_cast<uint8_t>(course);
|
||||
if (direction > 179) {
|
||||
direction -= 180;
|
||||
}
|
||||
return direction;
|
||||
}
|
||||
|
||||
|
||||
// Function definitions
|
||||
inline void encodeMessageHeader(MessageHeader *header, uint8_t messageType, uint8_t protocolVersion) {
|
||||
header->messageType_protocolVersion = (messageType << 4) | (protocolVersion & 0x0F);
|
||||
}
|
||||
|
||||
inline void encodeBasicIDMessage(BasicIDMessage *msg, idTypes idType, uaTypes uaType, const char *uasID) {
|
||||
encodeMessageHeader(&msg->header, msBasicID, 0x01);
|
||||
msg->idType_uaType = (idType << 4) | (uaType & 0x0F);
|
||||
memset(msg->uasID, 0, sizeof(msg->uasID));
|
||||
strncpy((char *)msg->uasID, uasID, sizeof(msg->uasID) - 1);
|
||||
msg->uasID[sizeof(msg->uasID) - 1] = '\0';
|
||||
memset(msg->reserved, 0, sizeof(msg->reserved));
|
||||
}
|
||||
|
||||
inline void encodeLocationMessage(LocationMessage *msg, uint8_t status, uint8_t trackDirection, uint8_t speed, int8_t verticalSpeed, float latitude, float longitude, float pressureAltitude, float geodeticAltitude, int16_t height, uint32_t horAccuracy, uint32_t vertAccuracy, uint32_t speedAccuracy, uint16_t timestamp) {
|
||||
encodeMessageHeader(&msg->header, msLocation, 0x01);
|
||||
msg->status = (status << 4);
|
||||
msg->trackDirection = encodeTrackDirection(trackDirection);
|
||||
msg->speed = speed;
|
||||
msg->verticalSpeed = verticalSpeed;
|
||||
msg->latitude = static_cast<int32_t>(latitude * 1e7); // Convert degrees to degrees * 10^7
|
||||
msg->longitude = static_cast<int32_t>(longitude * 1e7); // Convert degrees to degrees * 10^7
|
||||
msg->pressureAltitude = encodeAltitude(pressureAltitude);
|
||||
msg->geodeticAltitude = encodeAltitude(geodeticAltitude);
|
||||
msg->height = height;
|
||||
msg->horVertAccuracy = (convertVerticalAccuracy(vertAccuracy) << 4) | (convertHorizontalAccuracy(horAccuracy) & 0x0F);
|
||||
msg->baroSpeedAccuracy = (convertSpeedAccuracy(speedAccuracy) << 4) | (convertSpeedAccuracy(speedAccuracy) & 0x0F);
|
||||
msg->timestamp = timestamp;
|
||||
msg->reservedTimestampAccuracy = 0x00;
|
||||
msg->reserved = 0x00;
|
||||
}
|
||||
|
||||
inline void encodeAuthenticationMessage(AuthenticationMessage *msg, uint8_t authType, const uint8_t *authData) {
|
||||
encodeMessageHeader(&msg->header, msAuthentication, 0x1);
|
||||
msg->authType = authType;
|
||||
memcpy(msg->authData, authData, sizeof(msg->authData));
|
||||
}
|
||||
|
||||
inline void encodeSelfIDMessage(SelfIDMessage *msg, uint8_t descriptionType, const char *description) {
|
||||
encodeMessageHeader(&msg->header, msSelfID, 0x1);
|
||||
msg->descriptionType = descriptionType;
|
||||
strncpy(msg->description, description, sizeof(msg->description));
|
||||
if (strlen(description) < sizeof(msg->description)) {
|
||||
memset(msg->description + strlen(description), 0, sizeof(msg->description) - strlen(description));
|
||||
}
|
||||
}
|
||||
|
||||
inline void encodeSystemMessage(SystemMessage *msg, uint8_t operatorLocationType, int32_t operatorLatitude, int32_t operatorLongitude, uint16_t areaCount, uint16_t areaRadius, int16_t areaCeiling, int16_t areaFloor, uint8_t classificationType, uint8_t uaCategory, uint8_t uaClass, int16_t operatorAltitude, uint32_t timestamp) {
|
||||
encodeMessageHeader(&msg->header, msSystem, 0x1);
|
||||
msg->flags = (classificationType << 4) | operatorLocationType;
|
||||
msg->operatorLatitude = operatorLatitude;
|
||||
msg->operatorLongitude = operatorLongitude;
|
||||
msg->areaCount = areaCount;
|
||||
msg->areaRadius = areaRadius;
|
||||
msg->areaCeiling = areaCeiling;
|
||||
msg->areaFloor = areaFloor;
|
||||
msg->classification = (uaCategory << 4) | uaClass;
|
||||
msg->operatorAltitude = operatorAltitude;
|
||||
msg->timestamp = timestamp;
|
||||
msg->reserved = 0;
|
||||
}
|
||||
|
||||
inline void encodeOperatorIDMessage(OperatorIDMessage *msg, uint8_t operatorIDType, const char *operatorID) {
|
||||
encodeMessageHeader(&msg->header, msOperatorID, 0x1);
|
||||
msg->operatorIDType = operatorIDType;
|
||||
strncpy(msg->operatorID, operatorID, sizeof(msg->operatorID));
|
||||
if (strlen(operatorID) < sizeof(msg->operatorID)) {
|
||||
memset(msg->operatorID + strlen(operatorID), 0, sizeof(msg->operatorID) - strlen(operatorID));
|
||||
}
|
||||
memset(msg->reserved, 0, sizeof(msg->reserved));
|
||||
}
|
||||
|
||||
inline void encodeVendorSpecificTag(VendorSpecificTag *vendorTag, MessagePack *messagePack) {
|
||||
vendorTag->length = 3 + 1 + 1 + (messagePack->numMessages * messagePack->messageSize);
|
||||
vendorTag->oui[0] = 0xFA;
|
||||
vendorTag->oui[1] = 0x0B;
|
||||
vendorTag->oui[2] = 0xBC;
|
||||
vendorTag->vendType = 0x0D;
|
||||
memcpy(vendorTag->advData, messagePack, sizeof(MessageHeader) + 1 + 1 + (messagePack->numMessages * messagePack->messageSize));
|
||||
}
|
||||
|
||||
inline uint8_t encodeDirection(uint16_t direction, uint8_t *directionSegment) {
|
||||
uint8_t encodedValue;
|
||||
if (direction < 180) {
|
||||
encodedValue = direction;
|
||||
*directionSegment = 0;
|
||||
} else {
|
||||
encodedValue = direction - 180;
|
||||
*directionSegment = 1;
|
||||
}
|
||||
return encodedValue;
|
||||
}
|
||||
|
||||
inline uint8_t encodeSpeed(float speed, uint8_t *speedMultiplier) {
|
||||
uint8_t encodedValue;
|
||||
if (speed <= 255 * 0.25) {
|
||||
encodedValue = speed / 0.25;
|
||||
*speedMultiplier = 0;
|
||||
} else if (speed > 255 * 0.25 && speed < 254.25) {
|
||||
encodedValue = (speed - (255 * 0.25)) / 0.75;
|
||||
*speedMultiplier = 1;
|
||||
} else {
|
||||
encodedValue = 254;
|
||||
*speedMultiplier = 1;
|
||||
}
|
||||
return encodedValue;
|
||||
}
|
||||
|
||||
inline int32_t convertLatLonFormat(float value) {
|
||||
// Check if the value is already in the format of degrees * 10^7
|
||||
if (value > 1000000.0 || value < -1000000.0) {
|
||||
return static_cast<int32_t>(value);
|
||||
} else if (value > 360.0 || value < -360.0) {
|
||||
// If value is in decimal format (e.g., 12345.6789), convert it to degrees first
|
||||
int degrees = static_cast<int>(value / 100);
|
||||
float minutes = value - (degrees * 100);
|
||||
float decimalDegrees = degrees + (minutes / 60.0);
|
||||
return static_cast<int32_t>(decimalDegrees * 1e7);
|
||||
} else {
|
||||
// Convert degrees to degrees * 10^7
|
||||
return static_cast<int32_t>(value * 1e7);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
inline int8_t encodeVerticalSpeed(float verticalSpeed) {
|
||||
if (verticalSpeed > 62.0) {
|
||||
verticalSpeed = 62.0;
|
||||
} else if (verticalSpeed < -62.0) {
|
||||
verticalSpeed = -62.0;
|
||||
}
|
||||
float dividedValue = verticalSpeed / 0.5;
|
||||
int8_t encodedValue = static_cast<int8_t>(dividedValue);
|
||||
return encodedValue;
|
||||
}
|
||||
|
||||
inline uint16_t encodeAltitude(float altitude) {
|
||||
if (altitude == -1000) {
|
||||
return 0;
|
||||
}
|
||||
return (altitude + 1000) / 0.5;
|
||||
}
|
||||
|
||||
inline uint16_t encodeTimestamp(float timestamp) {
|
||||
return timestamp * 10;
|
||||
}
|
||||
|
||||
#endif // ENCODERS_H
|
42
include/gps.h
Normal file
42
include/gps.h
Normal file
@ -0,0 +1,42 @@
|
||||
/*
|
||||
___ _ ___ _
|
||||
| _ \ ( )_ | _ \ (_ )
|
||||
| (_) ) _ | _) _ _ __ | (_) ) __ _ _ | | ___ ___
|
||||
| / / _ \| | / _ \( __) | / / __ \/ _ )| |/ _ _ \
|
||||
| |\ \( (_) ) |_( (_) ) | | |\ \( ___/ (_| || || ( ) ( ) |
|
||||
(_) (_)\___/ \__)\___/(_) (_) (_)\____)\__ _)___)_) (_) (_)
|
||||
|
||||
* This file is part of Rotor Realm RemoteID
|
||||
*
|
||||
* Copyright (c) 2024 Rotor Realm
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*/
|
||||
#ifndef GPS_H
|
||||
#define GPS_H
|
||||
#include <Arduino.h>
|
||||
#include "nema.h" // Include the header file where GGAData is defined
|
||||
|
||||
// External declaration of ggaData
|
||||
extern GGAData ggaData;
|
||||
|
||||
extern HardwareSerial GPSSerial;
|
||||
void gpsSetup();
|
||||
void gpsTask(void * parameters);
|
||||
#endif
|
54
include/init.h
Normal file
54
include/init.h
Normal file
@ -0,0 +1,54 @@
|
||||
/*
|
||||
___ _ ___ _
|
||||
| _ \ ( )_ | _ \ (_ )
|
||||
| (_) ) _ | _) _ _ __ | (_) ) __ _ _ | | ___ ___
|
||||
| / / _ \| | / _ \( __) | / / __ \/ _ )| |/ _ _ \
|
||||
| |\ \( (_) ) |_( (_) ) | | |\ \( ___/ (_| || || ( ) ( ) |
|
||||
(_) (_)\___/ \__)\___/(_) (_) (_)\____)\__ _)___)_) (_) (_)
|
||||
|
||||
* This file is part of Rotor Realm RemoteID
|
||||
*
|
||||
* Copyright (c) 2024 Rotor Realm
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*/
|
||||
#ifndef INIT_H
|
||||
#define INIT_H
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <ArduinoJson.h>
|
||||
|
||||
struct OperatorInfo {
|
||||
String OperatorID;
|
||||
int32_t OperatorLatitude;
|
||||
int32_t OperatorLongitude;
|
||||
String OperatorTimezone;
|
||||
};
|
||||
|
||||
struct Config {
|
||||
int enableBT;
|
||||
int enableWiFi;
|
||||
OperatorInfo operatorInfo;
|
||||
};
|
||||
|
||||
extern Config config;
|
||||
|
||||
void loadConfig();
|
||||
|
||||
#endif // INIT_H
|
108
include/nema.h
Normal file
108
include/nema.h
Normal file
@ -0,0 +1,108 @@
|
||||
/*
|
||||
___ _ ___ _
|
||||
| _ \ ( )_ | _ \ (_ )
|
||||
| (_) ) _ | _) _ _ __ | (_) ) __ _ _ | | ___ ___
|
||||
| / / _ \| | / _ \( __) | / / __ \/ _ )| |/ _ _ \
|
||||
| |\ \( (_) ) |_( (_) ) | | |\ \( ___/ (_| || || ( ) ( ) |
|
||||
(_) (_)\___/ \__)\___/(_) (_) (_)\____)\__ _)___)_) (_) (_)
|
||||
|
||||
* This file is part of Rotor Realm RemoteID
|
||||
*
|
||||
* Copyright (c) 2024 Rotor Realm
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*/
|
||||
#ifndef NEMA_H
|
||||
#define NEMA_H
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
struct GGAData {
|
||||
String time;
|
||||
double latitude;
|
||||
char latDir;
|
||||
double longitude;
|
||||
char lonDir;
|
||||
int fixQuality;
|
||||
int numSatellites;
|
||||
double hdop;
|
||||
double altitude;
|
||||
char altUnit;
|
||||
double geoidHeight;
|
||||
char geoUnit;
|
||||
double dgpsAge;
|
||||
int dgpsStationId;
|
||||
};
|
||||
|
||||
struct RMCData {
|
||||
String time;
|
||||
char status;
|
||||
double latitude;
|
||||
char latDir;
|
||||
double longitude;
|
||||
char lonDir;
|
||||
double speed;
|
||||
double course;
|
||||
String date;
|
||||
double magVar;
|
||||
char magVarDir;
|
||||
char mode;
|
||||
};
|
||||
|
||||
struct GSAData {
|
||||
char mode1;
|
||||
int mode2;
|
||||
int sv[12];
|
||||
double pdop;
|
||||
double hdop;
|
||||
double vdop;
|
||||
};
|
||||
|
||||
struct GSVData {
|
||||
int numMessages;
|
||||
int messageNum;
|
||||
int numSVs;
|
||||
struct {
|
||||
int svID;
|
||||
int elevation;
|
||||
int azimuth;
|
||||
int snr;
|
||||
} svInfo[4];
|
||||
};
|
||||
|
||||
struct NAVACCData {
|
||||
String time;
|
||||
char status;
|
||||
uint32_t pAcc; // Horizontal Accuracy
|
||||
uint32_t vAcc; // Vertical Accuracy
|
||||
uint32_t cAcc; // Speed Accuracy
|
||||
};
|
||||
|
||||
void parseGGA(String nmea, GGAData &ggaData);
|
||||
void parseRMC(String nmea, RMCData &rmcData);
|
||||
void parseGSA(String nmea, GSAData &gsaData);
|
||||
void parseGSV(String nmea, GSVData &gsvData);
|
||||
void parseNAVACC(String nmea, NAVACCData &navaccData);
|
||||
void parseNMEA(String nmea, GGAData &ggaData, RMCData &rmcData, GSAData &gsaData, GSVData &gsvData, NAVACCData &navaccData);
|
||||
|
||||
double convertToDecimalDegrees(double coordinate, char direction);
|
||||
double parseDouble(String value);
|
||||
int parseInt(String value);
|
||||
|
||||
#endif // NEMA_H
|
71
include/wifiBeacon.h
Normal file
71
include/wifiBeacon.h
Normal file
@ -0,0 +1,71 @@
|
||||
/*
|
||||
___ _ ___ _
|
||||
| _ \ ( )_ | _ \ (_ )
|
||||
| (_) ) _ | _) _ _ __ | (_) ) __ _ _ | | ___ ___
|
||||
| / / _ \| | / _ \( __) | / / __ \/ _ )| |/ _ _ \
|
||||
| |\ \( (_) ) |_( (_) ) | | |\ \( ___/ (_| || || ( ) ( ) |
|
||||
(_) (_)\___/ \__)\___/(_) (_) (_)\____)\__ _)___)_) (_) (_)
|
||||
|
||||
* This file is part of Rotor Realm RemoteID
|
||||
*
|
||||
* Copyright (c) 2024 Rotor Realm
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*/
|
||||
#ifndef WIFI_H
|
||||
#define WIFI_H
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <enc.h>
|
||||
#include <astm.h>
|
||||
|
||||
// Define the WiFi channel and output power
|
||||
extern const int wifiChannel;
|
||||
extern const int wifiOutputPower;
|
||||
extern const int ledPin;
|
||||
|
||||
// Define UA Information
|
||||
#define uasIDType 1 // Serial
|
||||
#define uasType 2 // Multirotor
|
||||
|
||||
// Define Location Information
|
||||
// #define uasStatus 2
|
||||
// #define uasLatitude 336970783 // UAS Latitude
|
||||
// #define uasLongitude -1171853531 // UAS Longitude
|
||||
// #define uasAltitude 0 // UAS Altitude in meters
|
||||
// #define uasHorizontalSpeed 60 // Horizontal Speed in cm/s
|
||||
// #define uasVerticalSpeed 30 // Vertical Speed in cm/s
|
||||
// #define uasTrack 180 // Track direction in degrees
|
||||
|
||||
// Define Operator Information
|
||||
// #define operatorID "FC:WorldDrknss"
|
||||
// #define operatorLatitude 336970783
|
||||
// #define operatorLongitude -1171853531
|
||||
|
||||
// Define Self ID Information
|
||||
#define selfIdType 0
|
||||
#define selfIdDescription "Recreational"
|
||||
|
||||
void wifiBeaconSetup(const char* ssid);
|
||||
void wifiBeaconTask(void* parameters);
|
||||
void printRawBytes(uint8_t* data, size_t length);
|
||||
void constructBeaconFrame(const char* ssid, int channel, int beaconInterval);
|
||||
void encodeVendorSpecificElement(const char* ssid);
|
||||
|
||||
#endif // WIFI_H
|
46
lib/README
Normal file
46
lib/README
Normal file
@ -0,0 +1,46 @@
|
||||
|
||||
This directory is intended for project specific (private) libraries.
|
||||
PlatformIO will compile them to static libraries and link into executable file.
|
||||
|
||||
The source code of each library should be placed in an own separate directory
|
||||
("lib/your_library_name/[here are source files]").
|
||||
|
||||
For example, see a structure of the following two libraries `Foo` and `Bar`:
|
||||
|
||||
|--lib
|
||||
| |
|
||||
| |--Bar
|
||||
| | |--docs
|
||||
| | |--examples
|
||||
| | |--src
|
||||
| | |- Bar.c
|
||||
| | |- Bar.h
|
||||
| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
|
||||
| |
|
||||
| |--Foo
|
||||
| | |- Foo.c
|
||||
| | |- Foo.h
|
||||
| |
|
||||
| |- README --> THIS FILE
|
||||
|
|
||||
|- platformio.ini
|
||||
|--src
|
||||
|- main.c
|
||||
|
||||
and a contents of `src/main.c`:
|
||||
```
|
||||
#include <Foo.h>
|
||||
#include <Bar.h>
|
||||
|
||||
int main (void)
|
||||
{
|
||||
...
|
||||
}
|
||||
|
||||
```
|
||||
|
||||
PlatformIO Library Dependency Finder will find automatically dependent
|
||||
libraries scanning project source files.
|
||||
|
||||
More information about PlatformIO Library Dependency Finder
|
||||
- https://docs.platformio.org/page/librarymanager/ldf.html
|
18
platformio.ini
Normal file
18
platformio.ini
Normal file
@ -0,0 +1,18 @@
|
||||
; PlatformIO Project Configuration File
|
||||
;
|
||||
; Build options: build flags, source filter
|
||||
; Upload options: custom upload port, speed and extra flags
|
||||
; Library options: dependencies, extra library storages
|
||||
; Advanced options: extra scripting
|
||||
;
|
||||
; Please visit documentation for the other options and examples
|
||||
; https://docs.platformio.org/page/projectconf.html
|
||||
|
||||
[env:heltec_wireless_stick]
|
||||
platform = espressif32
|
||||
board = heltec_wireless_stick
|
||||
framework = arduino
|
||||
lib_deps =
|
||||
heltecautomation/Heltec ESP32 Dev-Boards@^2.0.2
|
||||
bblanchon/ArduinoJson@^7.1.0
|
||||
paulstoffregen/Time@^1.6.1
|
210
src/display.cpp
Normal file
210
src/display.cpp
Normal file
@ -0,0 +1,210 @@
|
||||
/*
|
||||
___ _ ___ _
|
||||
| _ \ ( )_ | _ \ (_ )
|
||||
| (_) ) _ | _) _ _ __ | (_) ) __ _ _ | | ___ ___
|
||||
| / / _ \| | / _ \( __) | / / __ \/ _ )| |/ _ _ \
|
||||
| |\ \( (_) ) |_( (_) ) | | |\ \( ___/ (_| || || ( ) ( ) |
|
||||
(_) (_)\___/ \__)\___/(_) (_) (_)\____)\__ _)___)_) (_) (_)
|
||||
|
||||
* This file is part of Rotor Realm RemoteID
|
||||
*
|
||||
* Copyright (c) 2024 Rotor Realm
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*/
|
||||
//display.cpp
|
||||
#include "HT_st7735.h"
|
||||
#include "init.h"
|
||||
#include "gps.h" // Include the header file where ggaData is declared
|
||||
#include <string.h> // Include string.h for strlen and strcmp functions
|
||||
#include <time.h>
|
||||
|
||||
extern TaskHandle_t wifiBeaconTaskHandle; // Declare the task handle as external
|
||||
|
||||
HT_st7735 tft;
|
||||
extern Config config;
|
||||
|
||||
// Variables to store previous values
|
||||
int prevNumSatellites = -1;
|
||||
int prevNumSatellitesLength = strlen("PNDNG");
|
||||
double prevLatitude = -1;
|
||||
int prevLatitudeLength = strlen("PNDNG");
|
||||
double prevLongitude = -1;
|
||||
int prevLongitudeLength = strlen("PNDNG");
|
||||
char prevTime[20] = "PNDNG";
|
||||
int prevTimeLength = strlen(prevTime);
|
||||
|
||||
// Variables to store previous WiFi status
|
||||
char prevWifiStatus[10] = "PNDNG";
|
||||
int prevWifiStatusLength = strlen(prevWifiStatus);
|
||||
|
||||
#define ST7735_PURPLE 0x780F // This is an example for purple
|
||||
|
||||
int timezoneStringToOffset(const String& timezone) {
|
||||
if (timezone == "PST") return -8;
|
||||
if (timezone == "PDT") return -7;
|
||||
if (timezone == "EST") return -5;
|
||||
if (timezone == "EDT") return -4;
|
||||
if (timezone == "CST") return -6;
|
||||
if (timezone == "CDT") return -5;
|
||||
// Add other timezones as needed
|
||||
return 0; // Default to UTC if the timezone is not recognized
|
||||
}
|
||||
|
||||
void displaySetup(const char* ssid) {
|
||||
int col1 = 0;
|
||||
int col2 = 30;
|
||||
|
||||
// Initialize Screen and Fill Black
|
||||
tft.st7735_init();
|
||||
tft.st7735_fill_screen(ST7735_BLACK);
|
||||
|
||||
// Beacon and FC Status
|
||||
tft.st7735_write_str(col1, 0, "BTX:", Font_7x10, ST7735_PURPLE, ST7735_BLACK);
|
||||
tft.st7735_write_str(col2, 0, "PNDNG", Font_7x10, ST7735_RED, ST7735_BLACK);
|
||||
tft.st7735_write_str(85, 0, "FC:", Font_7x10, ST7735_PURPLE, ST7735_BLACK);
|
||||
tft.st7735_write_str(110, 0, "PNDNG", Font_7x10, ST7735_RED, ST7735_BLACK);
|
||||
|
||||
// Satellites
|
||||
tft.st7735_write_str(col1, 13, "SAT:", Font_7x10, ST7735_PURPLE, ST7735_BLACK);
|
||||
tft.st7735_write_str(col2, 13, "PNDNG", Font_7x10, ST7735_RED, ST7735_BLACK);
|
||||
tft.st7735_write_str(85, 13, "TM:", Font_7x10, ST7735_PURPLE, ST7735_BLACK);
|
||||
tft.st7735_write_str(110, 13, "PNDNG", Font_7x10, ST7735_RED, ST7735_BLACK);
|
||||
|
||||
// Lat
|
||||
tft.st7735_write_str(col1, 26, "LAT:", Font_7x10, ST7735_PURPLE, ST7735_BLACK);
|
||||
tft.st7735_write_str(col2, 26, "PNDNG", Font_7x10, ST7735_RED, ST7735_BLACK);
|
||||
|
||||
// Lon
|
||||
tft.st7735_write_str(col1, 39, "LNG:", Font_7x10, ST7735_PURPLE, ST7735_BLACK);
|
||||
tft.st7735_write_str(col2, 39, "PNDNG", Font_7x10, ST7735_RED, ST7735_BLACK);
|
||||
|
||||
// Aircraft Serial
|
||||
tft.st7735_write_str(col1, 52, "MFR:", Font_7x10, ST7735_PURPLE, ST7735_BLACK);
|
||||
tft.st7735_write_str(col2, 52, "RRDI", Font_7x10, ST7735_RED, ST7735_BLACK); // Show RRDI
|
||||
|
||||
tft.st7735_write_str(col1, 65, "S/N:", Font_7x10, ST7735_PURPLE, ST7735_BLACK);
|
||||
tft.st7735_write_str(col2, 65, ssid + 4, Font_7x10, ST7735_RED, ST7735_BLACK); // Show the remaining of SSID
|
||||
}
|
||||
|
||||
String formatTime(int value) {
|
||||
if (value < 10) return "0" + String(value);
|
||||
return String(value);
|
||||
}
|
||||
|
||||
void displayTask(void* parameters) {
|
||||
Serial.println("Display Task started");
|
||||
|
||||
for (;;) {
|
||||
// Update the display with ggaData only if values have changed
|
||||
char buffer[20];
|
||||
|
||||
// Update number of satellites if it has changed
|
||||
if (ggaData.numSatellites > 0 && ggaData.numSatellites != prevNumSatellites) {
|
||||
snprintf(buffer, sizeof(buffer), "%d", ggaData.numSatellites);
|
||||
int newLength = strlen(buffer);
|
||||
tft.st7735_write_str(30, 13, buffer, Font_7x10, ST7735_RED, ST7735_BLACK);
|
||||
// Clear any extra characters
|
||||
for (int i = newLength; i < prevNumSatellitesLength; i++) {
|
||||
tft.st7735_write_str(30 + i * 7, 13, " ", Font_7x10, ST7735_BLACK, ST7735_BLACK);
|
||||
}
|
||||
prevNumSatellites = ggaData.numSatellites;
|
||||
prevNumSatellitesLength = newLength;
|
||||
} else if (ggaData.numSatellites == 0 && prevNumSatellites != 0) {
|
||||
tft.st7735_write_str(30, 13, "PNDNG", Font_7x10, ST7735_RED, ST7735_BLACK);
|
||||
prevNumSatellites = 0;
|
||||
prevNumSatellitesLength = strlen("PNDNG");
|
||||
}
|
||||
|
||||
// Update latitude if it has changed
|
||||
if (ggaData.latitude != prevLatitude) {
|
||||
snprintf(buffer, sizeof(buffer), "%.5f", ggaData.latitude);
|
||||
int newLength = strlen(buffer);
|
||||
tft.st7735_write_str(30, 26, buffer, Font_7x10, ST7735_RED, ST7735_BLACK);
|
||||
// Clear any extra characters
|
||||
for (int i = newLength; i < prevLatitudeLength; i++) {
|
||||
tft.st7735_write_str(30 + i * 7, 26, " ", Font_7x10, ST7735_BLACK, ST7735_BLACK);
|
||||
}
|
||||
prevLatitude = ggaData.latitude;
|
||||
prevLatitudeLength = newLength;
|
||||
} else if (ggaData.latitude == 0.0 && prevLatitude != 0.0) {
|
||||
tft.st7735_write_str(30, 26, "PNDNG", Font_7x10, ST7735_RED, ST7735_BLACK);
|
||||
prevLatitude = 0.0;
|
||||
prevLatitudeLength = strlen("PNDNG");
|
||||
}
|
||||
|
||||
// Update longitude if it has changed
|
||||
if (ggaData.longitude != prevLongitude) {
|
||||
snprintf(buffer, sizeof(buffer), "%.5f", ggaData.longitude);
|
||||
int newLength = strlen(buffer);
|
||||
tft.st7735_write_str(30, 39, buffer, Font_7x10, ST7735_RED, ST7735_BLACK);
|
||||
// Clear any extra characters
|
||||
for (int i = newLength; i < prevLongitudeLength; i++) {
|
||||
tft.st7735_write_str(30 + i * 7, 39, " ", Font_7x10, ST7735_BLACK, ST7735_BLACK);
|
||||
}
|
||||
prevLongitude = ggaData.longitude;
|
||||
prevLongitudeLength = newLength;
|
||||
} else if (ggaData.longitude == 0.0 && prevLongitude != 0.0) {
|
||||
tft.st7735_write_str(30, 39, "PNDNG", Font_7x10, ST7735_RED, ST7735_BLACK);
|
||||
prevLongitude = 0.0;
|
||||
prevLongitudeLength = strlen("PNDNG");
|
||||
}
|
||||
|
||||
// Get the timezone offset from config
|
||||
int timezoneOffset = timezoneStringToOffset(config.operatorInfo.OperatorTimezone);
|
||||
|
||||
// Convert GPS time to int
|
||||
int hours = ggaData.time.substring(0, 2).toInt();
|
||||
int minutes = ggaData.time.substring(2, 4).toInt();
|
||||
|
||||
// Apply the timezone offset
|
||||
hours = (hours + timezoneOffset + 24) % 24; // Ensure the hours wrap around correctly
|
||||
|
||||
// Format the adjusted time back to a string
|
||||
String formattedTime = formatTime(hours) + ":" + formatTime(minutes);
|
||||
|
||||
// Update GPS time if it has changed
|
||||
if (strcmp(formattedTime.c_str(), prevTime) != 0) {
|
||||
snprintf(buffer, sizeof(buffer), "%s", formattedTime.c_str());
|
||||
int newLength = strlen(buffer);
|
||||
tft.st7735_write_str(110, 13, buffer, Font_7x10, ST7735_RED, ST7735_BLACK);
|
||||
// Clear any extra characters
|
||||
for (int i = newLength; i < prevTimeLength; i++) {
|
||||
tft.st7735_write_str(110 + i * 7, 13, " ", Font_7x10, ST7735_BLACK, ST7735_BLACK);
|
||||
}
|
||||
strcpy(prevTime, formattedTime.c_str());
|
||||
prevTimeLength = newLength;
|
||||
}
|
||||
|
||||
// Update WiFi Beacon Task status if it has changed
|
||||
const char* wifiStatus = (eTaskGetState(wifiBeaconTaskHandle) != eSuspended) ? "TRSMTNG" : "PNDNG";
|
||||
if (strcmp(wifiStatus, prevWifiStatus) != 0) {
|
||||
int newLength = strlen(wifiStatus);
|
||||
tft.st7735_write_str(30, 0, wifiStatus, Font_7x10, ST7735_RED, ST7735_BLACK);
|
||||
// Clear any extra characters
|
||||
for (int i = newLength; i < prevWifiStatusLength; i++) {
|
||||
tft.st7735_write_str(30 + i * 7, 0, " ", Font_7x10, ST7735_BLACK, ST7735_BLACK);
|
||||
}
|
||||
strcpy(prevWifiStatus, wifiStatus);
|
||||
prevWifiStatusLength = newLength;
|
||||
}
|
||||
|
||||
vTaskDelay(1000 / portTICK_PERIOD_MS); // Delay to yield control
|
||||
}
|
||||
}
|
127
src/gps.cpp
Normal file
127
src/gps.cpp
Normal file
@ -0,0 +1,127 @@
|
||||
/*
|
||||
___ _ ___ _
|
||||
| _ \ ( )_ | _ \ (_ )
|
||||
| (_) ) _ | _) _ _ __ | (_) ) __ _ _ | | ___ ___
|
||||
| / / _ \| | / _ \( __) | / / __ \/ _ )| |/ _ _ \
|
||||
| |\ \( (_) ) |_( (_) ) | | |\ \( ___/ (_| || || ( ) ( ) |
|
||||
(_) (_)\___/ \__)\___/(_) (_) (_)\____)\__ _)___)_) (_) (_)
|
||||
|
||||
* This file is part of Rotor Realm RemoteID
|
||||
*
|
||||
* Copyright (c) 2024 Rotor Realm
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*/
|
||||
#include "gps.h"
|
||||
#include "nema.h"
|
||||
|
||||
HardwareSerial GPSSerial(1);
|
||||
|
||||
GGAData ggaData;
|
||||
RMCData rmcData;
|
||||
GSAData gsaData;
|
||||
GSVData gsvData;
|
||||
NAVACCData navaccData;
|
||||
|
||||
#define VGNSS_CTRL 3
|
||||
|
||||
void gpsSetup() {
|
||||
pinMode(VGNSS_CTRL, OUTPUT);
|
||||
digitalWrite(VGNSS_CTRL, HIGH);
|
||||
GPSSerial.begin(115200, SERIAL_8N1, 33, 34); // RX, TX
|
||||
Serial.println("GPS setup complete");
|
||||
|
||||
// Enable NAVACC and VTG
|
||||
GPSSerial.print("$CFGMSG,0,5,1\r\n"); // Enable VTG
|
||||
delay(1000); // Wait for the GPS to respond
|
||||
GPSSerial.print("$CFGMSG,1,3,1\r\n"); // Enable NAVACC
|
||||
delay(1000); // Wait for the GPS to respond
|
||||
}
|
||||
|
||||
void gpsTask(void* parameters) {
|
||||
Serial.println("GPS Task started");
|
||||
for (;;) {
|
||||
while (GPSSerial.available()) {
|
||||
String nmea = GPSSerial.readStringUntil('\n');
|
||||
parseNMEA(nmea, ggaData, rmcData, gsaData, gsvData, navaccData);
|
||||
|
||||
// Print all NMEA messages for debugging
|
||||
// Serial.println(nmea);
|
||||
|
||||
if (nmea.startsWith("$GPGGA") || nmea.startsWith("$GBGGA") || nmea.startsWith("$GAGGA") || nmea.startsWith("$GLGGA") || nmea.startsWith("$GNGGA")) {
|
||||
// Serial.print("Time: ");
|
||||
// Serial.println(ggaData.time);
|
||||
// Serial.print("GGA Latitude: ");
|
||||
// Serial.println(ggaData.latitude);
|
||||
// Serial.print("GGA Longitude: ");
|
||||
// Serial.println(ggaData.longitude);
|
||||
// Serial.println(ggaData.numSatellites);
|
||||
} else if (nmea.startsWith("$GPRMC") || nmea.startsWith("$GBRMC") || nmea.startsWith("$GARMC") || nmea.startsWith("$GLRMC") || nmea.startsWith("$GNRMC")) {
|
||||
// Serial.print("Time: ");
|
||||
// Serial.println(rmcData.time);
|
||||
// Serial.print("Status: ");
|
||||
// Serial.println(rmcData.status);
|
||||
// Serial.print("RMC Latitude: ");
|
||||
// Serial.println(rmcData.latitude);
|
||||
// Serial.print("RMC Longitude: ");
|
||||
// Serial.println(rmcData.longitude);
|
||||
} else if (nmea.startsWith("$GPGSA") || nmea.startsWith("$GBGSA") || nmea.startsWith("$GAGSA") || nmea.startsWith("$GLGSA") || nmea.startsWith("$GNGSA")) {
|
||||
// Serial.print("Mode1: ");
|
||||
// Serial.println(gsaData.mode1);
|
||||
// Serial.print("Mode2: ");
|
||||
// Serial.println(gsaData.mode2);
|
||||
// Serial.print("PDOP: ");
|
||||
// Serial.println(gsaData.pdop);
|
||||
// Serial.print("HDOP: ");
|
||||
// Serial.println(gsaData.hdop);
|
||||
// Serial.print("VDOP: ");
|
||||
// Serial.println(gsaData.vdop);
|
||||
} else if (nmea.startsWith("$GPGSV") || nmea.startsWith("$GBGSV") || nmea.startsWith("$GAGSV") || nmea.startsWith("$GLGSV") || nmea.startsWith("$GNGSV")) {
|
||||
// Serial.print("Number of Messages: ");
|
||||
// Serial.println(gsvData.numMessages);
|
||||
// Serial.print("Message Number: ");
|
||||
// Serial.println(gsvData.messageNum);
|
||||
// Serial.print("Number of SVs: ");
|
||||
// Serial.println(gsvData.numSVs);
|
||||
// for (int i = 0; i < 4; i++) {
|
||||
// Serial.print("SV ID: ");
|
||||
// Serial.println(gsvData.svInfo[i].svID);
|
||||
// Serial.print("Elevation: ");
|
||||
// Serial.println(gsvData.svInfo[i].elevation);
|
||||
// Serial.print("Azimuth: ");
|
||||
// Serial.println(gsvData.svInfo[i].azimuth);
|
||||
// Serial.print("SNR: ");
|
||||
// Serial.println(gsvData.svInfo[i].snr);
|
||||
// }
|
||||
} else if (nmea.startsWith("$NAVACC")) {
|
||||
// Serial.print("NAVACC Time: ");
|
||||
// Serial.println(navaccData.time);
|
||||
// Serial.print("NAVACC Status: ");
|
||||
// Serial.println(navaccData.status);
|
||||
// Serial.print("Horizontal Accuracy: ");
|
||||
// Serial.println(navaccData.pAcc);
|
||||
// Serial.print("Vertical Accuracy: ");
|
||||
// Serial.println(navaccData.vAcc);
|
||||
// Serial.print("Ground Course Accuracy: ");
|
||||
// Serial.println(navaccData.cAcc);
|
||||
}
|
||||
}
|
||||
vTaskDelay(1000 / portTICK_PERIOD_MS); // Delay to yield control
|
||||
}
|
||||
}
|
81
src/init.cpp
Normal file
81
src/init.cpp
Normal file
@ -0,0 +1,81 @@
|
||||
/*
|
||||
___ _ ___ _
|
||||
| _ \ ( )_ | _ \ (_ )
|
||||
| (_) ) _ | _) _ _ __ | (_) ) __ _ _ | | ___ ___
|
||||
| / / _ \| | / _ \( __) | / / __ \/ _ )| |/ _ _ \
|
||||
| |\ \( (_) ) |_( (_) ) | | |\ \( ___/ (_| || || ( ) ( ) |
|
||||
(_) (_)\___/ \__)\___/(_) (_) (_)\____)\__ _)___)_) (_) (_)
|
||||
|
||||
* This file is part of Rotor Realm RemoteID
|
||||
*
|
||||
* Copyright (c) 2024 Rotor Realm
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*/
|
||||
#include <FS.h>
|
||||
#include <SPIFFS.h>
|
||||
#include <ArduinoJson.h>
|
||||
#include "init.h"
|
||||
|
||||
Config config;
|
||||
|
||||
void loadConfig() {
|
||||
if (!SPIFFS.begin(true)) {
|
||||
Serial.println("An error has occurred while mounting SPIFFS");
|
||||
return;
|
||||
}
|
||||
|
||||
File configFile = SPIFFS.open("/config.json", "r");
|
||||
if (!configFile) {
|
||||
Serial.println("Failed to open config file");
|
||||
return;
|
||||
}
|
||||
|
||||
size_t size = configFile.size();
|
||||
if (size > 1024) {
|
||||
Serial.println("Config file size is too large");
|
||||
return;
|
||||
}
|
||||
|
||||
std::unique_ptr<char[]> buf(new char[size]);
|
||||
configFile.readBytes(buf.get(), size);
|
||||
|
||||
DynamicJsonDocument doc(1024);
|
||||
auto error = deserializeJson(doc, buf.get());
|
||||
if (error) {
|
||||
Serial.print(F("Failed to parse config file: "));
|
||||
Serial.println(error.c_str());
|
||||
return;
|
||||
}
|
||||
|
||||
config.enableBT = doc["config"]["enableBT"];
|
||||
config.enableWiFi = doc["config"]["enableWiFi"];
|
||||
config.operatorInfo.OperatorID = doc["operator"]["OperatorID"].as<String>();
|
||||
config.operatorInfo.OperatorLatitude = doc["operator"]["OperatorLatitude"];
|
||||
config.operatorInfo.OperatorLongitude = doc["operator"]["OperatorLongitude"];
|
||||
config.operatorInfo.OperatorTimezone = doc["operator"]["OperatorTimezone"].as<String>();
|
||||
|
||||
Serial.println("Config loaded successfully");
|
||||
Serial.println("enableBT: " + String(config.enableBT));
|
||||
Serial.println("enableWiFi: " + String(config.enableWiFi));
|
||||
Serial.println("OperatorID: " + config.operatorInfo.OperatorID);
|
||||
Serial.println("OperatorLatitude: " + String(config.operatorInfo.OperatorLatitude));
|
||||
Serial.println("OperatorLongitude: " + String(config.operatorInfo.OperatorLongitude));
|
||||
Serial.println("OperatorTimezone: " + config.operatorInfo.OperatorTimezone);
|
||||
}
|
131
src/main.cpp
Normal file
131
src/main.cpp
Normal file
@ -0,0 +1,131 @@
|
||||
/*
|
||||
___ _ ___ _
|
||||
| _ \ ( )_ | _ \ (_ )
|
||||
| (_) ) _ | _) _ _ __ | (_) ) __ _ _ | | ___ ___
|
||||
| / / _ \| | / _ \( __) | / / __ \/ _ )| |/ _ _ \
|
||||
| |\ \( (_) ) |_( (_) ) | | |\ \( ___/ (_| || || ( ) ( ) |
|
||||
(_) (_)\___/ \__)\___/(_) (_) (_)\____)\__ _)___)_) (_) (_)
|
||||
|
||||
* This file is part of Rotor Realm RemoteID
|
||||
*
|
||||
* Copyright (c) 2024 Rotor Realm
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*/
|
||||
#include "Arduino.h"
|
||||
#include "gps.h"
|
||||
#include "display.h"
|
||||
#include "wifiBeacon.h"
|
||||
#include "init.h"
|
||||
#include <freertos/FreeRTOS.h>
|
||||
#include <freertos/task.h>
|
||||
|
||||
#define VGNSS_CTRL 3
|
||||
|
||||
String ssidString;
|
||||
const char* ssid;
|
||||
TaskHandle_t wifiBeaconTaskHandle = NULL; // Declare the task handle globally
|
||||
|
||||
void setup() {
|
||||
ssidString = generateUASID();
|
||||
ssid = ssidString.c_str();
|
||||
|
||||
pinMode(VGNSS_CTRL, OUTPUT);
|
||||
digitalWrite(VGNSS_CTRL, HIGH);
|
||||
Serial.begin(115200);
|
||||
|
||||
// Order of Operations
|
||||
loadConfig();
|
||||
gpsSetup();
|
||||
displaySetup(ssid);
|
||||
wifiBeaconSetup(ssid);
|
||||
|
||||
|
||||
Serial.println("Creating GPS Task...");
|
||||
if (xTaskCreate(
|
||||
gpsTask, // Function to be called
|
||||
"GPS Task", // Name of the task
|
||||
8192, // Stack size (increased size)
|
||||
NULL, // Task input parameter
|
||||
1, // Priority of the task
|
||||
NULL // Task handle
|
||||
)
|
||||
!= pdPASS) {
|
||||
Serial.println("Failed to create GPS Task");
|
||||
} else {
|
||||
Serial.println("GPS Task created successfully");
|
||||
}
|
||||
|
||||
Serial.println("Creating WiFi Beacon Task...");
|
||||
if (xTaskCreatePinnedToCore(
|
||||
wifiBeaconTask, // Function to be called
|
||||
"WiFi Beacon Task", // Name of the task
|
||||
8192, // Stack size (increased size)
|
||||
(void*)ssid, // Task input parameter
|
||||
2, // Priority of the task
|
||||
&wifiBeaconTaskHandle, // Task handle
|
||||
0 // Core number (0 or 1 for ESP32)
|
||||
)
|
||||
!= pdPASS) {
|
||||
Serial.println("Failed to create WiFi Beacon Task");
|
||||
} else {
|
||||
Serial.println("WiFi Beacon Task created successfully");
|
||||
vTaskSuspend(wifiBeaconTaskHandle); // Suspend the task immediately
|
||||
}
|
||||
|
||||
Serial.println("Creating Display Task...");
|
||||
if (xTaskCreate(
|
||||
displayTask, // Function to be called
|
||||
"Display Task", // Name of the task
|
||||
8192, // Stack size (increased size)
|
||||
NULL, // Task input parameter
|
||||
3, // Priority of the task
|
||||
NULL // Task handle
|
||||
)
|
||||
!= pdPASS) {
|
||||
Serial.println("Failed to create Display Task");
|
||||
} else {
|
||||
Serial.println("Display Task created successfully");
|
||||
}
|
||||
}
|
||||
|
||||
void loop() {
|
||||
if (ggaData.numSatellites > 1) {
|
||||
vTaskResume(wifiBeaconTaskHandle); // Resume the task if the condition is met
|
||||
} else {
|
||||
vTaskSuspend(wifiBeaconTaskHandle); // Suspend the task if the condition is not met
|
||||
}
|
||||
|
||||
vTaskDelay(1000 / portTICK_PERIOD_MS); // Delay to prevent rapid suspend/resume calls
|
||||
}
|
||||
|
||||
String generateUASID() {
|
||||
String prefix = "RRDIF";
|
||||
uint64_t chipId = ESP.getEfuseMac();
|
||||
String serialNumber = String(chipId, HEX);
|
||||
serialNumber.toUpperCase();
|
||||
while (serialNumber.length() < 7) {
|
||||
serialNumber = "0" + serialNumber;
|
||||
}
|
||||
String uasID = prefix + serialNumber;
|
||||
while (uasID.length() < 19) {
|
||||
uasID += "0";
|
||||
}
|
||||
return uasID;
|
||||
}
|
264
src/nema.cpp
Normal file
264
src/nema.cpp
Normal file
@ -0,0 +1,264 @@
|
||||
/*
|
||||
___ _ ___ _
|
||||
| _ \ ( )_ | _ \ (_ )
|
||||
| (_) ) _ | _) _ _ __ | (_) ) __ _ _ | | ___ ___
|
||||
| / / _ \| | / _ \( __) | / / __ \/ _ )| |/ _ _ \
|
||||
| |\ \( (_) ) |_( (_) ) | | |\ \( ___/ (_| || || ( ) ( ) |
|
||||
(_) (_)\___/ \__)\___/(_) (_) (_)\____)\__ _)___)_) (_) (_)
|
||||
|
||||
* This file is part of Rotor Realm RemoteID
|
||||
*
|
||||
* Copyright (c) 2024 Rotor Realm
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*/
|
||||
#include "nema.h"
|
||||
|
||||
double convertToDecimalDegrees(double coordinate, char direction) {
|
||||
int degrees = int(coordinate / 100);
|
||||
double minutes = coordinate - (degrees * 100);
|
||||
double decimalDegrees = degrees + (minutes / 60.0);
|
||||
|
||||
if (direction == 'S' || direction == 'W') {
|
||||
decimalDegrees = -decimalDegrees;
|
||||
}
|
||||
|
||||
return decimalDegrees;
|
||||
}
|
||||
|
||||
double parseDouble(String value) {
|
||||
return value.toFloat();
|
||||
}
|
||||
|
||||
int parseInt(String value) {
|
||||
return value.toInt();
|
||||
}
|
||||
|
||||
void parseGGA(String gga, GGAData &ggaData) {
|
||||
int idx = 0;
|
||||
int fieldIndex = 0;
|
||||
String field;
|
||||
|
||||
while (idx < gga.length()) {
|
||||
int endIdx = gga.indexOf(',', idx);
|
||||
if (endIdx == -1) endIdx = gga.length();
|
||||
|
||||
field = gga.substring(idx, endIdx);
|
||||
|
||||
switch (fieldIndex) {
|
||||
case 1: // UTC Time
|
||||
ggaData.time = field;
|
||||
break;
|
||||
case 2: // Latitude
|
||||
ggaData.latitude = parseDouble(field);
|
||||
break;
|
||||
case 3: // Latitude Direction
|
||||
ggaData.latDir = field.charAt(0);
|
||||
break;
|
||||
case 4: // Longitude
|
||||
ggaData.longitude = parseDouble(field);
|
||||
break;
|
||||
case 5: // Longitude Direction
|
||||
ggaData.lonDir = field.charAt(0);
|
||||
break;
|
||||
case 6: // Fix Quality
|
||||
ggaData.fixQuality = parseInt(field);
|
||||
break;
|
||||
case 7: // Number of Satellites
|
||||
ggaData.numSatellites = parseInt(field);
|
||||
break;
|
||||
case 8: // HDOP
|
||||
ggaData.hdop = parseDouble(field);
|
||||
break;
|
||||
case 9: // Altitude
|
||||
ggaData.altitude = parseDouble(field);
|
||||
break;
|
||||
case 10: // Altitude Unit
|
||||
ggaData.altUnit = field.charAt(0);
|
||||
break;
|
||||
case 11: // Geoid Height
|
||||
ggaData.geoidHeight = parseDouble(field);
|
||||
break;
|
||||
case 12: // Geoid Unit
|
||||
ggaData.geoUnit = field.charAt(0);
|
||||
break;
|
||||
case 13: // DGPS Age
|
||||
ggaData.dgpsAge = parseDouble(field);
|
||||
break;
|
||||
case 14: // DGPS Station ID
|
||||
ggaData.dgpsStationId = parseInt(field);
|
||||
break;
|
||||
}
|
||||
|
||||
idx = endIdx + 1;
|
||||
fieldIndex++;
|
||||
}
|
||||
|
||||
// Convert latitude and longitude to proper format
|
||||
ggaData.latitude = convertToDecimalDegrees(ggaData.latitude, ggaData.latDir);
|
||||
ggaData.longitude = convertToDecimalDegrees(ggaData.longitude, ggaData.lonDir);
|
||||
}
|
||||
|
||||
void parseRMC(String rmc, RMCData &rmcData) {
|
||||
int idx = 0;
|
||||
int fieldIndex = 0;
|
||||
String field;
|
||||
|
||||
while (idx < rmc.length()) {
|
||||
int endIdx = rmc.indexOf(',', idx);
|
||||
if (endIdx == -1) endIdx = rmc.length();
|
||||
|
||||
field = rmc.substring(idx, endIdx);
|
||||
|
||||
switch (fieldIndex) {
|
||||
case 1: // UTC Time
|
||||
rmcData.time = field;
|
||||
break;
|
||||
case 2: // Status
|
||||
rmcData.status = field.charAt(0);
|
||||
break;
|
||||
case 3: // Latitude
|
||||
rmcData.latitude = parseDouble(field);
|
||||
break;
|
||||
case 4: // Latitude Direction
|
||||
rmcData.latDir = field.charAt(0);
|
||||
break;
|
||||
case 5: // Longitude
|
||||
rmcData.longitude = parseDouble(field);
|
||||
break;
|
||||
case 6: // Longitude Direction
|
||||
rmcData.lonDir = field.charAt(0);
|
||||
break;
|
||||
case 7: // Speed
|
||||
rmcData.speed = parseDouble(field);
|
||||
break;
|
||||
case 8: // Course
|
||||
rmcData.course = parseDouble(field);
|
||||
break;
|
||||
case 9: // Date
|
||||
rmcData.date = field;
|
||||
break;
|
||||
case 10: // Magnetic Variation
|
||||
rmcData.magVar = parseDouble(field);
|
||||
break;
|
||||
case 11: // Magnetic Variation Direction
|
||||
rmcData.magVarDir = field.charAt(0);
|
||||
break;
|
||||
case 12: // Mode
|
||||
rmcData.mode = field.charAt(0);
|
||||
break;
|
||||
}
|
||||
|
||||
idx = endIdx + 1;
|
||||
fieldIndex++;
|
||||
}
|
||||
|
||||
// Convert latitude and longitude to proper format
|
||||
rmcData.latitude = convertToDecimalDegrees(rmcData.latitude, rmcData.latDir);
|
||||
rmcData.longitude = convertToDecimalDegrees(rmcData.longitude, rmcData.lonDir);
|
||||
}
|
||||
|
||||
|
||||
void parseGSA(String gsa, GSAData &gsaData) {
|
||||
int idx = 0;
|
||||
int endIdx = gsa.indexOf(',', idx);
|
||||
gsaData.mode1 = gsa.charAt(idx);
|
||||
|
||||
idx = endIdx + 1;
|
||||
endIdx = gsa.indexOf(',', idx);
|
||||
gsaData.mode2 = parseInt(gsa.substring(idx, endIdx));
|
||||
|
||||
for (int i = 0; i < 12; i++) {
|
||||
idx = endIdx + 1;
|
||||
endIdx = gsa.indexOf(',', idx);
|
||||
gsaData.sv[i] = parseInt(gsa.substring(idx, endIdx));
|
||||
}
|
||||
|
||||
idx = endIdx + 1;
|
||||
endIdx = gsa.indexOf(',', idx);
|
||||
gsaData.pdop = parseDouble(gsa.substring(idx, endIdx));
|
||||
|
||||
idx = endIdx + 1;
|
||||
endIdx = gsa.indexOf(',', idx);
|
||||
gsaData.hdop = parseDouble(gsa.substring(idx, endIdx));
|
||||
|
||||
idx = endIdx + 1;
|
||||
gsaData.vdop = parseDouble(gsa.substring(idx));
|
||||
}
|
||||
|
||||
void parseGSV(String gsv, GSVData &gsvData) {
|
||||
int idx = 0;
|
||||
int endIdx = gsv.indexOf(',', idx);
|
||||
gsvData.numMessages = parseInt(gsv.substring(idx, endIdx));
|
||||
|
||||
idx = endIdx + 1;
|
||||
endIdx = gsv.indexOf(',', idx);
|
||||
gsvData.messageNum = parseInt(gsv.substring(idx, endIdx));
|
||||
|
||||
idx = endIdx + 1;
|
||||
endIdx = gsv.indexOf(',', idx);
|
||||
gsvData.numSVs = parseInt(gsv.substring(idx, endIdx));
|
||||
|
||||
for (int i = 0; i < 4; i++) {
|
||||
idx = endIdx + 1;
|
||||
endIdx = gsv.indexOf(',', idx);
|
||||
gsvData.svInfo[i].svID = parseInt(gsv.substring(idx, endIdx));
|
||||
|
||||
idx = endIdx + 1;
|
||||
endIdx = gsv.indexOf(',', idx);
|
||||
gsvData.svInfo[i].elevation = parseInt(gsv.substring(idx, endIdx));
|
||||
|
||||
idx = endIdx + 1;
|
||||
endIdx = gsv.indexOf(',', idx);
|
||||
gsvData.svInfo[i].azimuth = parseInt(gsv.substring(idx, endIdx));
|
||||
|
||||
idx = endIdx + 1;
|
||||
endIdx = gsv.indexOf(',', idx);
|
||||
gsvData.svInfo[i].snr = parseInt(gsv.substring(idx, endIdx));
|
||||
}
|
||||
}
|
||||
|
||||
void parseNAVACC(String nmea, NAVACCData &navaccData) {
|
||||
int idx = nmea.indexOf(',');
|
||||
int endIdx = nmea.indexOf(',', idx + 1);
|
||||
navaccData.pAcc = nmea.substring(idx + 1, endIdx).toInt();
|
||||
|
||||
idx = endIdx;
|
||||
endIdx = nmea.indexOf(',', idx + 1);
|
||||
navaccData.vAcc = nmea.substring(idx + 1, endIdx).toInt();
|
||||
|
||||
idx = endIdx;
|
||||
endIdx = nmea.indexOf(',', idx + 1);
|
||||
navaccData.cAcc = nmea.substring(idx + 1, endIdx).toInt();
|
||||
}
|
||||
|
||||
|
||||
void parseNMEA(String nmea, GGAData &ggaData, RMCData &rmcData, GSAData &gsaData, GSVData &gsvData, NAVACCData &navaccData) {
|
||||
if (nmea.startsWith("$GPGGA") || nmea.startsWith("$GBGGA") || nmea.startsWith("$GAGGA") || nmea.startsWith("$GLGGA") || nmea.startsWith("$GNGGA")) {
|
||||
parseGGA(nmea, ggaData);
|
||||
} else if (nmea.startsWith("$GPRMC") || nmea.startsWith("$GBRMC") || nmea.startsWith("$GARMC") || nmea.startsWith("$GLRMC") || nmea.startsWith("$GNRMC")) {
|
||||
parseRMC(nmea, rmcData);
|
||||
} else if (nmea.startsWith("$GPGSA") || nmea.startsWith("$GBGSA") || nmea.startsWith("$GAGSA") || nmea.startsWith("$GLGSA") || nmea.startsWith("$GNGSA")) {
|
||||
parseGSA(nmea, gsaData);
|
||||
} else if (nmea.startsWith("$GPGSV") || nmea.startsWith("$GBGSV") || nmea.startsWith("$GAGSV") || nmea.startsWith("$GLGSV") || nmea.startsWith("$GNGSV")) {
|
||||
parseGSV(nmea, gsvData);
|
||||
} else if (nmea.startsWith("$NAVACC")) {
|
||||
parseNAVACC(nmea, navaccData);
|
||||
}
|
||||
}
|
203
src/wifiBeacon.cpp
Normal file
203
src/wifiBeacon.cpp
Normal file
@ -0,0 +1,203 @@
|
||||
/*
|
||||
___ _ ___ _
|
||||
| _ \ ( )_ | _ \ (_ )
|
||||
| (_) ) _ | _) _ _ __ | (_) ) __ _ _ | | ___ ___
|
||||
| / / _ \| | / _ \( __) | / / __ \/ _ )| |/ _ _ \
|
||||
| |\ \( (_) ) |_( (_) ) | | |\ \( ___/ (_| || || ( ) ( ) |
|
||||
(_) (_)\___/ \__)\___/(_) (_) (_)\____)\__ _)___)_) (_) (_)
|
||||
|
||||
* This file is part of Rotor Realm RemoteID
|
||||
*
|
||||
* Copyright (c) 2024 Rotor Realm
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*/
|
||||
#include "wifiBeacon.h"
|
||||
#include "init.h" // Include init.h to access the config variable
|
||||
#include "gps.h" // Include gps.h to access the GPS data
|
||||
#include <WiFi.h>
|
||||
#include <esp_wifi.h>
|
||||
|
||||
// Define the WiFi channel and output power
|
||||
const int wifiChannel = 6; // Set WiFi Channel
|
||||
const int wifiOutputPower = 20; // dBm
|
||||
// const int ledPin = LED_BUILTIN;
|
||||
|
||||
// WiFi packet buffer
|
||||
uint8_t beaconPacket[256];
|
||||
uint8_t packetIndex = 0;
|
||||
static uint8_t beaconCounter = 0; // Static variable to keep track of how many times the beacon has been sent
|
||||
|
||||
extern Config config; // Access the global config variable
|
||||
extern GGAData ggaData; // Access the GPS GGA data
|
||||
extern RMCData rmcData;
|
||||
extern NAVACCData navaccData; // Access the GPS NAVACC data
|
||||
|
||||
void wifiBeaconSetup(const char* ssid) {
|
||||
pinMode(LED, OUTPUT);
|
||||
Serial.begin(115200);
|
||||
WiFi.mode(WIFI_MODE_STA);
|
||||
esp_wifi_set_promiscuous(true);
|
||||
esp_wifi_set_channel(wifiChannel, WIFI_SECOND_CHAN_NONE);
|
||||
int channel = wifiChannel;
|
||||
int beaconInterval = 100;
|
||||
constructBeaconFrame(ssid, channel, beaconInterval);
|
||||
}
|
||||
|
||||
void wifiBeaconTask(void* parameters) {
|
||||
for (;;) {
|
||||
esp_wifi_80211_tx(WIFI_IF_STA, beaconPacket, packetIndex, false);
|
||||
beaconCounter++;
|
||||
// digitalWrite(LED, HIGH);
|
||||
analogWrite(LED, 96);
|
||||
constructBeaconFrame((const char*)parameters, wifiChannel, 100);
|
||||
// digitalWrite(LED, LOW);
|
||||
analogWrite(LED, 0);
|
||||
vTaskDelay(1000 / portTICK_PERIOD_MS);
|
||||
}
|
||||
}
|
||||
|
||||
void constructBeaconFrame(const char* ssid, int channel, int beaconInterval) {
|
||||
packetIndex = 0;
|
||||
beaconPacket[packetIndex++] = 0x80;
|
||||
beaconPacket[packetIndex++] = 0x00;
|
||||
beaconPacket[packetIndex++] = 0x00;
|
||||
beaconPacket[packetIndex++] = 0x00;
|
||||
memset(&beaconPacket[packetIndex], 0xFF, 6);
|
||||
packetIndex += 6;
|
||||
uint8_t sourceAddress[] = { 0xDE, 0xAD, 0xBE, 0xEF, 0xDE, 0xAD };
|
||||
memcpy(&beaconPacket[packetIndex], sourceAddress, 6);
|
||||
packetIndex += 6;
|
||||
memcpy(&beaconPacket[packetIndex], sourceAddress, 6);
|
||||
packetIndex += 6;
|
||||
beaconPacket[packetIndex++] = 0x00;
|
||||
beaconPacket[packetIndex++] = 0x00;
|
||||
memset(&beaconPacket[packetIndex], 0x00, 8);
|
||||
packetIndex += 8;
|
||||
beaconPacket[packetIndex++] = beaconInterval & 0xFF;
|
||||
beaconPacket[packetIndex++] = (beaconInterval >> 8) & 0xFF;
|
||||
beaconPacket[packetIndex++] = 0x01;
|
||||
beaconPacket[packetIndex++] = 0x00;
|
||||
beaconPacket[packetIndex++] = 0x00;
|
||||
uint8_t ssidLength = strlen(ssid);
|
||||
beaconPacket[packetIndex++] = ssidLength;
|
||||
memcpy(&beaconPacket[packetIndex], ssid, ssidLength);
|
||||
packetIndex += ssidLength;
|
||||
beaconPacket[packetIndex++] = 0x01;
|
||||
beaconPacket[packetIndex++] = 0x08;
|
||||
beaconPacket[packetIndex++] = 0x82;
|
||||
beaconPacket[packetIndex++] = 0x84;
|
||||
beaconPacket[packetIndex++] = 0x8B;
|
||||
beaconPacket[packetIndex++] = 0x96;
|
||||
beaconPacket[packetIndex++] = 0x0C;
|
||||
beaconPacket[packetIndex++] = 0x12;
|
||||
beaconPacket[packetIndex++] = 0x18;
|
||||
beaconPacket[packetIndex++] = 0x24;
|
||||
beaconPacket[packetIndex++] = 0x03;
|
||||
beaconPacket[packetIndex++] = 0x01;
|
||||
beaconPacket[packetIndex++] = channel;
|
||||
encodeVendorSpecificElement(ssid);
|
||||
}
|
||||
|
||||
void encodeVendorSpecificElement(const char* ssid) {
|
||||
VendorSpecificTag vendorTag;
|
||||
MessagePack messagePack;
|
||||
messagePack.messageSize = 25;
|
||||
messagePack.numMessages = 5;
|
||||
|
||||
// Basic ID Message
|
||||
BasicIDMessage basicIDMessage;
|
||||
encodeBasicIDMessage(
|
||||
&basicIDMessage, // Basic ID message struct
|
||||
idSerial, // UAS ID Type
|
||||
uaMultirotor, // UAS Type
|
||||
ssid // UAS ID (SSID)
|
||||
);
|
||||
memcpy(messagePack.messages[0], &basicIDMessage, sizeof(BasicIDMessage));
|
||||
|
||||
// Location Message
|
||||
LocationMessage locationMessage;
|
||||
encodeLocationMessage(&locationMessage,
|
||||
osAirborne, // Status
|
||||
static_cast<uint8_t>(rmcData.course), // Track Direction
|
||||
static_cast<uint8_t>(rmcData.speed), // Speed
|
||||
0, // Vertical Speed (can be replaced with actual value if available)
|
||||
ggaData.latitude, // Latitude
|
||||
ggaData.longitude, // Longitude
|
||||
ggaData.altitude, // Pressure Altitude (float)
|
||||
ggaData.geoidHeight, // Geodetic Altitude (float)
|
||||
static_cast<int16_t>(ggaData.altitude), // Height
|
||||
navaccData.pAcc, // Horizontal Accuracy
|
||||
navaccData.vAcc, // Vertical Accuracy
|
||||
navaccData.cAcc, // Speed/Baro Accuracy
|
||||
ggaData.time.toInt() // Timestamp
|
||||
); // Timestamp
|
||||
memcpy(messagePack.messages[1], &locationMessage, sizeof(LocationMessage));
|
||||
|
||||
// Self ID Message
|
||||
SelfIDMessage selfIDMessage;
|
||||
encodeSelfIDMessage(
|
||||
&selfIDMessage, // Self ID message struct
|
||||
selfIdType, // Self ID Type
|
||||
selfIdDescription // Self ID Description
|
||||
);
|
||||
memcpy(messagePack.messages[2], &selfIDMessage, sizeof(SelfIDMessage));
|
||||
|
||||
// System Message
|
||||
SystemMessage systemMessage;
|
||||
uint8_t uaClass = 0;
|
||||
encodeSystemMessage(
|
||||
&systemMessage, // System message struct
|
||||
0, // Operator Location Type
|
||||
config.operatorInfo.OperatorLatitude, // Operator Latitude
|
||||
config.operatorInfo.OperatorLongitude, // Operator Longitude
|
||||
1, // Area Count
|
||||
0, // Area Radius
|
||||
0, // Area Ceiling
|
||||
0, // Area Floor
|
||||
cfUndeclared, // Classification Type
|
||||
uaMultirotor, // UA Category
|
||||
uaClass, // UA Class
|
||||
0, // Operator Altitude
|
||||
0 // Timestamp
|
||||
);
|
||||
memcpy(messagePack.messages[3], &systemMessage, sizeof(SystemMessage));
|
||||
|
||||
// Operator ID Message
|
||||
OperatorIDMessage operatorIDMessage;
|
||||
encodeOperatorIDMessage(
|
||||
&operatorIDMessage, // Operator ID message struct
|
||||
0, // Operator ID Type
|
||||
config.operatorInfo.OperatorID.c_str() // Operator ID
|
||||
);
|
||||
memcpy(messagePack.messages[4], &operatorIDMessage, sizeof(OperatorIDMessage));
|
||||
|
||||
encodeMessageHeader(&messagePack.header, msMessagePack, 0x01);
|
||||
|
||||
encodeVendorSpecificTag(&vendorTag, &messagePack);
|
||||
|
||||
beaconPacket[packetIndex++] = 0xDD;
|
||||
beaconPacket[packetIndex++] = vendorTag.length;
|
||||
memcpy(&beaconPacket[packetIndex], vendorTag.oui, 3);
|
||||
packetIndex += 3;
|
||||
beaconPacket[packetIndex++] = vendorTag.vendType;
|
||||
beaconPacket[packetIndex++] = vendorTag.msgCounter;
|
||||
memcpy(&beaconPacket[packetIndex], vendorTag.advData, vendorTag.length - 5);
|
||||
packetIndex += vendorTag.length - 5;
|
||||
}
|
11
test/README
Normal file
11
test/README
Normal file
@ -0,0 +1,11 @@
|
||||
|
||||
This directory is intended for PlatformIO Test Runner and project tests.
|
||||
|
||||
Unit Testing is a software testing method by which individual units of
|
||||
source code, sets of one or more MCU program modules together with associated
|
||||
control data, usage procedures, and operating procedures, are tested to
|
||||
determine whether they are fit for use. Unit testing finds problems early
|
||||
in the development cycle.
|
||||
|
||||
More information about PlatformIO Unit Testing:
|
||||
- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html
|
Loading…
Reference in New Issue
Block a user