DPilot

Research-Grade Flight Telemetry & Visual Odometry System
Research & Development

Advanced flight telemetry system with 50Hz unified state communication, real-time web interface, and visual odometry capabilities using custom ESP32 PCB integration and Raspberry Pi AI Camera processing for autonomous flight research.

System Requirements & Development Status

๐Ÿ›ก๏ธ Regulatory Compliance

  • Drone Operations: Designed for compliance with local UAV/drone regulations (e.g., FAA Part 107 in the US, EASA in the EU). Operators are responsible for adhering to all applicable laws regarding flight altitude, airspace, and registration.
  • RF Transmission: LoRa modules operate in the 915MHz ISM band (US) or 868MHz (EU). Ensure operation within legal frequency and power limits as specified by the FCC (US) or local authorities. Maximum transmission power is set to comply with regional requirements.
  • Encryption: AES-128 encryption is used for secure communication, following best practices for data privacy and security.
  • Camera Use: Visual recording and AI camera features must comply with privacy and data protection laws. Obtain necessary permissions for video capture in
  • PCB & Electronics: Custom PCB design follows RoHS and CE guidelines for electronic safety and environmental compliance.

Note: Always check and follow your local regulations for drone operation, RF transmission, and data collection. The DPilot system is intended for research and educational use.

๐ŸŽฏ Mission Requirements

  • Range: >15 km mission coverage
  • Flight Time: >30 minutes endurance
  • Communication: >5 km line of sight
  • Update Rate: 50Hz unified state feedback
  • Flying speed: >120 km/h capability
  • Visual navigation and SLAM

๐Ÿค– Development Status

  • โœ… 50Hz unified state estimation
  • โœ… AES-128 encrypted LoRa communication
  • โœ… Frame-synchronized video/data logging
  • โœ… Web-based ground control interface
  • โœ… Custom PCB design (JLCPCB ready)
  • ๐Ÿ”„ Visual odometry implementation
  • ๐Ÿ“ AI camera integration (Planned)
  • ๐Ÿ“ Full autonomous flight (Future)

โš™๏ธ System Architecture

  • Total cost: <$300 (including aircraft)
  • Modular & expandable design
  • Cross-platform compatibility
  • Always-on WiFi hotspot access
  • PCB fabrication

The System in some videos

System Architecture & Interface

System Architecture
Complete System Architecture

Ground control, telemetry and drone system overview

Web Interface
Web Interface Dashboard

Live telemetry dashboard with smartphone-accessible controls and artificial horizon

Aircraft Integration
Aircraft Integration

VolantexRC Ranger with 3D printed components and visual odometry camera

System Features

๐Ÿ”„ Unified State Architecture

  • 50Hz synchronized telemetry transmission
  • 60-byte complete state packets
  • Perfect data alignment and timing
  • Zero correlation issues
  • Mission command integration

๐Ÿ“ก Advanced Communication

  • 915MHz LoRa with 2-5km range
  • AES-128 encryption security
  • Anti-aliasing data processing
  • Automatic role detection
  • Binary protocol optimization

๐ŸŒ Professional Web Interface

  • Always-on WiFi hotspot mode
  • Live telemetry dashboard (1Hz update)
  • Smartphone-accessible control
  • Real-time artificial horizon
  • G-G acceleration diagrams
  • Remote recording management

๐ŸŽฌ Synchronized Video Recording

  • Raw and overlay recording modes
  • Perfect frame-CSV synchronization
  • H.264 encoding with telemetry overlay
  • 30fps video with flight instruments
  • Automatic file management

๐Ÿง  Visual Navigation System

  • Raspberry Pi AI Camera support
  • Sony IMX500 12MP sensor
  • Visual odometry processing
  • Real-time feature detection
  • Position estimation and SLAM
  • Autonomous navigation capability

๐Ÿ”ง Custom PCB Integration

  • Professional 2-layer PCB design
  • JLCPCB manufacturing ready
  • Integrated MPU6050, SD, LoRa
  • 3D printed environmental protection
  • Optimized for aircraft installation

Technical Specifications

50Hz
Unified State Rate
10Hz
GPS Update Rate
5km
LoRa Range
AES-128
Encryption
60 bytes
State Packet
<100ms
Command Latency
60 FPS
AI Camera Rate
12MP
Camera Resolution

๐Ÿง  Kalman Filter Attitude Estimation

DPilot employs a sophisticated 5-state Kalman filter for high-precision attitude estimation, fusing accelerometer and gyroscope data to deliver robust roll and pitch measurements even during dynamic flight conditions.

Filter Architecture

  • State Vector: [roll, pitch, roll_rate, pitch_rate, yaw_rate]
  • Update Rate: 50Hz with non-uniform time handling
  • Gyro Integration: Dynamic time-step adjustment
  • Bias Correction: Calibrated yaw rate bias removal
  • Noise Models: Tuned process and measurement covariances

Innovation Analysis

  • Real-time Monitoring: Innovation factor visualization
  • Statistical Analysis: Means and standard deviations
  • Performance Target: <2ยฐ steady-state accuracy
  • Convergence: Rapid filter stabilization (<1s)
  • Robustness Target: Maintains accuracy during dynamic flying
# Kalman Filter State Prediction Step def predict(self, gx, gy, gz, timestamp): # Calculate dt since last update dt = (timestamp - self.last_update).total_seconds() # Current state: [roll, pitch, roll_rate, pitch_rate, yaw_rate] roll, pitch, roll_rate, pitch_rate, yaw_rate = self.state # Update rates directly from gyroscope (with bias correction on yaw) roll_rate_new = gx pitch_rate_new = gy yaw_rate_new = gz # Bias already corrected in data preparation # Integrate gyroscope rates to update angles roll_new = roll + math.degrees(gx) * dt pitch_new = pitch + math.degrees(gy) * dt # Update state vector self.state = np.array([roll_new, pitch_new, roll_rate_new, pitch_rate_new, yaw_rate_new]) # Update state covariance: P = FยทPยทF^T + Q F = np.eye(5) # State transition matrix F[0, 2] = dt # roll affected by roll_rate F[1, 3] = dt # pitch affected by pitch_rate self.P = F @ self.P @ F.T + self.Q return self.state # Kalman Filter Measurement Update Step def update_with_accel(self, ax, ay, az): # Calculate attitude from accelerometer roll_acc = math.degrees(math.atan2(ay, math.sqrt(ax*ax + az*az))) pitch_acc = math.degrees(math.atan2(-ax, math.sqrt(ay*ay + az*az))) # Measurement vector z = np.array([roll_acc, pitch_acc]) # Measurement model (maps states to measurements) H = np.zeros((2, 5)) H[0, 0] = 1.0 # roll_acc corresponds to roll H[1, 1] = 1.0 # pitch_acc corresponds to pitch # Innovation: difference between measurement and prediction y = z - H @ self.state # Kalman gain calculation S = H @ self.P @ H.T + self.R_accel K = self.P @ H.T @ np.linalg.inv(S) # Update state and covariance self.state = self.state + K @ y self.P = (np.eye(5) - K @ H) @ self.P return y # Return innovation values for analysis

The filter employs a two-step prediction-correction approach, first integrating gyroscope data for rapid attitude updates, then using accelerometer measurements to correct drift. The innovation factor (difference between predicted and measured values) provides real-time insight into filter performance and convergence.

This implementation handles gyroscope bias, non-uniform sampling times, and maintains high accuracy during aggressive maneuvers by carefully tuning the process and measurement noise covariance matrices.

Complete Hardware Integration

๐Ÿ›ฉ๏ธ Aircraft Platform

Main Aircraft
  • Model: VolantexRC Ranger 1600/2000
  • Wingspan: 1600mm/2000mm EPO foam
  • Configuration: Pusher, PNP ready
  • Weight: 1500-1700g with telemetry (depending on Battery)
  • ๐Ÿ”— Source Link
Propulsion System
  • Motor: D3536 Brushless 1450KV
  • Propeller: 8x6 3-blade pusher
  • ESC: 60A with 4A UBEC
  • Mount: Custom 3D printed
  • ๐Ÿ”— Motor Link
Wing Configuration
  • Standard: Ranger 1600 wings
  • Slow Flight: Ranger 2000 wings
  • Flaps: Servo-controlled (2000)
  • Sensors: Wing loading monitoring

๐Ÿ–ฅ๏ธ Computing & Vision System

Mission Computer
  • CPU: Raspberry Pi Zero 2 W
  • RAM: 512MB LPDDR2
  • Storage: 32GB+ microSD
  • Housing: Custom 3D printed bucket
  • ๐Ÿ”— Source Link
Camera System
  • Standard: OV5647 5MP Sensor
  • Resolution: 1080p @ 30fps
  • Upgrade: AI Camera with IMX500 (optional)
  • Mounting: Downward + 15ยฐ forward
  • ๐Ÿ”— Source Link
Custom PCB Module
  • Design: 2-layer JLCPCB
  • Controller: ESP32-S3 + SX1262
  • Sensors: MPU6050 IMU integrated
  • Storage: SD card module

๐Ÿ“ก Communication & Display

Heltec WiFi LoRa 32 V3 (Drone & Ground)
  • MCU: ESP32-S3 dual-core
  • LoRa: SX1262 @ 915MHz
  • Display: 0.96" OLED 128x64
  • Power: USB-C powered
  • Range: 2-5km line of sight
  • Encryption: AES-128 security
  • ๐Ÿ”— Official Documentation

โšก Power & Storage System

Power Regulation
  • Converter: LM2596 DC-DC Buck
  • Output: 5V regulated @ 3A
  • Input: ESC UBEC 5V @ 4A
  • Efficiency: >85% typical
  • ๐Ÿ”— Source Link
Data Storage
  • Module: Micro SD card breakout
  • Interface: SPI with pins
  • Capacity: 32GB+ Class 10
  • Integration: On custom PCB
  • ๐Ÿ”— Source Link
Power Budget
  • Pi Zero 2W: 4W peak with AI camera
  • Custom PCB: 2W with LoRa TX
  • Total Aircraft: ~7.5W continuous
  • Flight Time: >2 hours endurance

System Architecture & Data Flow

Complete System Integration

Aircraft Sensors โ†’ Custom PCB ESP32 โ†’ LoRa โ†’ Ground ESP32 โ†’ USB โ†’ Pi Zero 2W โ†“ โ†“ โ†“ โ”œโ”€ IMU (50Hz) โ”€โ”€โ”€โ”€โ”€โ”€โ†’ Filtered data โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ†’ Raw data โ”œโ”€ GPS (10Hz) โ”€โ”€โ”€โ”€โ”€โ”€โ†’ Position/velocity โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ†’ Navigation โ”œโ”€ ADC (50Hz) โ”€โ”€โ”€โ”€โ”€โ”€โ†’ Aircraft systems โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ†’ Health monitoring โ”œโ”€ AI Camera โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ†’ Visual features โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ†’ Odometry processing โ””โ”€ Status โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ†’ Flight status โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ”€โ†’ Safety monitoring Pi Zero 2W Processing: โ”œโ”€ H.264 video recording with AI camera (60fps) โ”œโ”€ Data logging (CSV) at 50Hz unified state โ”œโ”€ Web interface (port 5000) with live telemetry โ”œโ”€ WiFi hotspot (field access: dpilot_horizon) โ”œโ”€ Visual odometry processing and SLAM โ””โ”€ Mission command generation and planning

Custom PCB Integration (JLCPCB)

PCB Specifications

  • Manufacturer: JLCPCB Professional
  • Layers: 2-layer cost-effective
  • Size: ~50x40mm aircraft fit
  • Finish: HASL/ENIG RoHS
  • Components: ESP32-S3, SX1262, MPU6050

Integration Benefits

  • Professional manufacturing quality
  • Reduced wiring complexity
  • Optimized RF performance
  • Integrated sensor fusion
  • 3D printed environmental protection

Aircraft Mounting Strategy

VolantexRC Ranger 1600/2000 - Optimized Layout: Nose Section: โ”œโ”€ Pi (AI or conventional) Camera; inclined at from 20ยฐ downwards (looking forward) to visual odometry โ”‚ โ”œโ”€ Visual odometry capability with Sony IMX500 โ”‚ โ”œโ”€ 12MP high-resolution imaging โ”‚ โ””โ”€ AI processing for object detection/tracking โ”œโ”€ GPS Antenna (clear sky view) โ””โ”€ Custom 3D printed camera mount Center Fuselage: โ”œโ”€ Raspberry Pi Zero 2W (custom 3D printed bucket) โ”œโ”€ Custom PCB ESP32 Module (custom 3D printed bucket) โ”œโ”€ Power distribution board โ”œโ”€ LM2596 Buck converter (single unit) โ””โ”€ Battery bay (LiPo pack) Pusher Motor Section: โ”œโ”€ D3536 Motor (custom 3D printed mount) โ”œโ”€ ESC mounting (optimized airflow) โ”œโ”€ Vibration isolation (3D printed dampeners) โ””โ”€ Propeller clearance optimization

Aircraft Platform Specifications

Parameter Ranger 1600 Ranger 2000 Notes
Wingspan 1600mm 2000mm EPO foam construction
Length 1075mm 1075mm Pusher configuration
Wing Area 26.5dmยฒ 32.8dmยฒ High aspect ratio
Flying Weight 1200-1500g 1200-1500g With telemetry system
Speed Range Normal operations Slow flight capable Visual odometry optimized
Flap Control None Servo-controlled Enhanced landing approach

System Testing & Performance

Verified Performance Metrics

Communication Performance

  • Unified State Rate: 50Hz ยฑ1Hz sustained
  • LoRa Success Rate: >95% at operational range
  • Command Latency: <100ms typical
  • Range Testing: >2km line of sight verified
  • Encryption Overhead: <5ms per packet

Data Quality Metrics

  • GPS Update Rate: 10Hz after configuration
  • IMU Data Quality: <3% duplicate rate
  • Video Synchronization: Frame-perfect CSV alignment
  • Power Efficiency: >2 hour flight endurance
  • Temperature Stability: MPU6050 calibrated

Testing Progression

Ground Testing
  1. Power system verification
  2. LoRa communication range test
  3. Sensor calibration and alignment
  4. 50Hz unified state verification
  5. AI camera and visual processing
  6. Web interface functionality
  7. Command response testing
Flight Testing
  1. Taxi tests with sensor validation
  2. Range tests at operational distance
  3. Short flights with basic telemetry
  4. Extended flights for endurance
  5. Visual odometry validation
  6. Mission command following
  7. Autonomous flight capabilities
Data Analysis
  1. Telemetry data quality analysis
  2. Video-CSV synchronization check
  3. Visual odometry accuracy assessment
  4. Power consumption optimization
  5. Communication reliability metrics
  6. System performance profiling
  7. Research data validation

Ground Control Station

Desktop GCS
Desktop Ground Control

Python application with FPV video overlay

TFT Display
TFT Base Station Display

2" TFT with real-time G-G diagrams

Communication & Data Flow

๐Ÿ“ก Communication System (ToDo)

  • Set up 915MHz LoRa radio communication
  • Implement AES-128 encryption for secure data transfer
  • Test range capability in open field conditions
  • Optimize antenna placement for maximum range
  • Document interference patterns and mitigations

๐Ÿ“Š Data Flow Architecture (ToDo)

  • Implement 50Hz unified state communication
  • Optimize packet structure for minimal overhead
  • Develop robust error handling and packet recovery
  • Create bidirectional command framework
  • Set up logging and monitoring of data flow

๐Ÿ“ฆ Packet Structure (ToDo)

  • Design 60-byte optimized telemetry format
  • Include CRC validation for data integrity
  • Implement timestamping for synchronization
  • Create command integration within packet structure
  • Document protocol specifications for future reference

๐Ÿ”’ Security Implementation (ToDo)

  • Deploy AES-128 encryption across all communications
  • Develop key management system for secure operation
  • Test encryption overhead and performance impact
  • Create failsafe modes for communication loss
  • Document security protocols and best practices

System Testing & Validation

๐Ÿงช Ground Testing
Work in progress
  • Set up bench testing environment
  • Validate sensor calibration and integration
  • Test unified state communication
  • Verify SD card logging functionality
  • Benchmark power consumption
๐Ÿ“ก LoRa Range Testing
Work in progress
  • Perform field testing at varying distances
  • Measure packet success rate vs. distance
  • Test with different antenna configurations
  • Optimize transmission parameters
  • Document maximum reliable range
๐Ÿ›ฉ๏ธ Flight Testing
Work in progress
  • Complete Ranger integration with telemetry
  • Perform initial taxi tests
  • Validate in-flight data collection
  • Test visual odometry during flight
  • Verify endurance and performance
๐Ÿ“ˆ Data Analysis & Validation
Work in progress
  • Develop post-flight analysis tools
  • Validate sensor accuracy and precision
  • Compare visual odometry to GPS data
  • Create visualization dashboards
  • Document system performance metrics

Manufacturing & Assembly Process

Custom PCB
Custom PCB Design

Professional 2-layer PCB with integrated ESP32, LoRa, IMU, and SD card

3D Printing
Motor mount

Custom component printing in PETG

3D Printing
Ground Control TFTs Displays

Custom component printing in PETG

Research Applications & Future Development

๐Ÿ”ฌ Current Research Focus

  • Visual odometry algorithm development
  • AI-powered feature detection and matching
  • Real-time SLAM implementation
  • Multi-sensor fusion techniques
  • Autonomous navigation strategies

๐ŸŽฏ Future Capabilities

  • Full autonomous flight missions
  • Object detection and avoidance
  • Landing site detection and selection
  • Swarm coordination protocols
  • Advanced AI model deployment

๐Ÿ“Š Data Applications

  • Flight dynamics research
  • Aerodynamic performance analysis
  • Wing loading studies
  • Visual navigation validation
  • Autonomous systems development

Development Roadmap

Phase 1: โœ… COMPLETED โ”œโ”€ Unified state communication architecture โ”œโ”€ 50Hz telemetry with perfect synchronization โ”œโ”€ Web-based ground control interface โ”œโ”€ Custom PCB design and integration โ””โ”€ Basic visual processing pipeline Phase 2: ๐Ÿ”„ IN PROGRESS โ”œโ”€ Visual odometry implementation โ”œโ”€ AI camera integration and testing โ”œโ”€ Feature detection optimization โ”œโ”€ SLAM algorithm development โ””โ”€ Position estimation validation Phase 3: ๐Ÿ“ PLANNED โ”œโ”€ Full autonomous flight capability โ”œโ”€ Advanced AI model deployment โ”œโ”€ Object detection and avoidance โ”œโ”€ Multi-aircraft coordination โ””โ”€ Research publication and validation

Hardware Interface Documentation

๐Ÿ—๏ธ System Architecture Overview

Drone ESP32 (Heltec WiFi LoRa 32 V3)
โ”œโ”€โ”€ IยฒC Bus 1: MPU6050 IMU (SDA=47, SCL=48)
Drone ESP32 (Heltec WiFi LoRa 32 V3)
โ”œโ”€โ”€ IยฒC Bus 1: MPU6050 IMU (SDA=47, SCL=48)
โ”œโ”€โ”€ IยฒC Bus 2: OLED Display (SDA_OLED, SCL_OLED)
โ”œโ”€โ”€ SPI Bus 1: LoRa Module (Built-in)
โ”œโ”€โ”€ SPI Bus 2: SD Card (CS=26, MOSI=42, SCLK=46, MISO=45)
โ”œโ”€โ”€ Serial 1: USB Serial (115200 baud)
โ”œโ”€โ”€ Serial 2: GPS Module (RX=19, TX=20, 38400 baud)
โ””โ”€โ”€ ADC: 7-channel analog inputs (A0-A6)

Base Station ESP32 (Heltec WiFi LoRa 32 V3)
โ”œโ”€โ”€ IยฒC Bus 1: OLED Display (SDA_OLED, SCL_OLED)
โ”œโ”€โ”€ SPI Bus 1: LoRa Module (Built-in)
โ”œโ”€โ”€ SPI Bus 2: TFT Display (CS=26, DC=45, SCLK=46, MOSI=42)
โ””โ”€โ”€ Serial 1: USB Serial (115200 baud)

๐ŸŽฏ Automatic Role Detection

System automatically determines role based on MPU6050 presence:
MPU6050 Detected โ†’ Drone Mode (sensor collection, SD logging)
No MPU6050 โ†’ Base Station Mode (command relay, TFT display)

๐Ÿ“ก Complete Pin Assignment Tables

๐Ÿš Drone Configuration DRONE MODE

Component Interface ESP32 Pins Configuration
MPU6050 IMU IยฒC Bus 1 (Wire1) SDA=47, SCL=48 ยฑ8g accel, ยฑ500ยฐ/s gyro, 10Hz filter
GPS Module Serial2 RX=19, TX=20 38400 baud, 8N1
SD Card SPI Bus 2 (spi1) CS=26, MOSI=42, SCLK=46, MISO=45 Time-controlled logging, auto file management
Analog Sensors ADC A0(12), A1(13), A2(14), A3(15), A4(16), A5(17), A6(18) 7-channel 8-bit ADC, 0-255 range
Logging Button Digital Input GPIO 41 (Pull-up) Single-button start/stop logging
OLED Display IยฒC Bus 2 SDA_OLED, SCL_OLED 128x64 status display
LoRa Module SPI Bus 1 (Built-in) Integrated 915MHz, 21dBm, SF7, BW=500kHz, AES-128
USB Serial Serial (Built-in) USB Port 115200 baud, unified state packets (50Hz)

๐Ÿ“ก Base Station Configuration BASE STATION

Component Interface ESP32 Pins Configuration
TFT Display SPI Bus 2 (spiTFT) CS=26, DC=45, SCLK=46, MOSI=42 240x320 ST7789, G-G diagram, flight instruments
OLED Display IยฒC Bus 1 SDA_OLED, SCL_OLED 128x64 system status
LoRa Module SPI Bus 1 (Built-in) Integrated 915MHz, 21dBm, SF7, BW=500kHz, AES-128
USB Serial Serial (Built-in) USB Port 115200 baud, binary command interface

๐Ÿ”ง Hardware Initialization Code

๐Ÿš Drone Mode Initialization

// MPU6050 IMU Initialization (IยฒC Bus 1) static const uint8_t SCL_IMU = 48; static const uint8_t SDA_IMU = 47; Wire1.begin(SDA_IMU, SCL_IMU); while (!mpu.begin(MPU6050_I2CADDR_DEFAULT, &Wire1, 0)) { delay(100); Serial.println("Failed to find MPU6050 chip"); } // Configure MPU6050 settings mpu.setAccelerometerRange(MPU6050_RANGE_8_G); mpu.setGyroRange(MPU6050_RANGE_500_DEG); mpu.setFilterBandwidth(MPU6050_BAND_10_HZ); // GPS Module Initialization (Serial2) #define Serial2RxPin 19 #define Serial2TxPin 20 Serial2.begin(38400, SERIAL_8N1, Serial2RxPin, Serial2TxPin); // SD Card Initialization (SPI Bus 2) #define SD_CS 26 #define SD_MOSI 42 #define SD_SCLK 46 #define SD_MISO 45 SPIClass spi1; spi1.begin(SD_SCLK, SD_MISO, SD_MOSI, SD_CS); while (!SD.begin(SD_CS, spi1)) { delay(100); Serial.println("Failed to find SD card"); } // Analog Input Initialization #define analogInPin0 12 // A0 #define analogInPin1 13 // A1 #define analogInPin2 14 // A2 #define analogInPin3 15 // A3 #define analogInPin4 16 // A4 #define analogInPin5 17 // A5 #define analogInPin6 18 // A6 pinMode(A0, INPUT); pinMode(A1, INPUT); pinMode(A2, INPUT); pinMode(A3, INPUT); pinMode(A4, INPUT); pinMode(A5, INPUT); pinMode(A6, INPUT); // Logging Button Initialization #define BUTTON_LOG 41 pinMode(BUTTON_LOG, INPUT_PULLUP);

๐Ÿ“ก Base Station Mode Initialization

// TFT Display Initialization (SPI Bus 2) #define TFT_CS 26 #define TFT_DC 45 #define TFT_RST -1 // No reset pin #define TFT_SCLK 46 #define TFT_MOSI 42 SPIClass spiTFT = SPIClass(HSPI); Adafruit_ST7789 tft = Adafruit_ST7789(&spiTFT, TFT_CS, TFT_DC, TFT_RST); // Initialize SPI for TFT spiTFT.begin(TFT_SCLK, -1, TFT_MOSI, TFT_CS); // Initialize the display tft.init(240, 320); // 240x320 resolution tft.setRotation(0); tft.fillScreen(ST77XX_BLACK); // Initialize default reference command for base station initializeDefaultReferenceCommand();

๐Ÿ”„ Shared Components Initialization

// OLED Display Initialization (Both modes) static SSD1306Wire display(0x3c, 500000, SDA_OLED, SCL_OLED, GEOMETRY_128_64, RST_OLED); VextON(); // Enable Vext power delay(100); display.init(); display.setFont(ArialMT_Plain_10); display.clear(); // LoRa Module Initialization (Both modes) #define RF_FREQUENCY 915000000 // Hz #define TX_OUTPUT_POWER 21 // dBm #define LORA_BANDWIDTH 2 // 500 kHz #define LORA_SPREADING_FACTOR 7 // SF7 #define LORA_CODINGRATE 1 // 4/5 Radio.Init(&RadioEvents); Radio.SetChannel(RF_FREQUENCY); Radio.SetTxConfig(MODEM_LORA, TX_OUTPUT_POWER, 0, LORA_BANDWIDTH, LORA_SPREADING_FACTOR, LORA_CODINGRATE, 8, false, true, 0, 0, false, 3000); // AES-128 Encryption Initialization byte key[16] = { 0xAA, 0xBB, 0xCC, 0xDD, 0x11, 0x22, 0x33, 0x44, 0x55, 0x66, 0x77, 0x88, 0x99, 0x00, 0xFE, 0xED }; aes128.setKey(key, 16); // USB Serial Initialization Serial.begin(115200);