kopia lustrzana https://github.com/pjalocha/esp32-ogn-tracker
Initial code, basic functionality: transmit, receive, relay, display position
rodzic
545b4ae5b1
commit
79f8e58659
|
@ -0,0 +1,9 @@
|
|||
#
|
||||
# This is a project Makefile. It is assumed the directory this Makefile resides in is a
|
||||
# project subdirectory.
|
||||
#
|
||||
|
||||
PROJECT_NAME := app-template
|
||||
|
||||
include $(IDF_PATH)/make/project.mk
|
||||
|
22
README.md
22
README.md
|
@ -1,2 +1,24 @@
|
|||
# esp32-ogn-tracker
|
||||
OGN Tracker implementation on ESP32 devices
|
||||
|
||||
The initial code is written for and tested on HALTEC LoRa 32 module with sx1276 and 128x64 OLED display.
|
||||
Most likely it can be easily ported to other ESP32 devices, as these are very flexible for the I/O assignement.
|
||||
If you need to change the pins assigned to various periferials, see the top of the hal.cpp file.
|
||||
|
||||
To compile and upload use the standard ESP32 toolchain and esp-idf
|
||||
|
||||
To wire the UART GPS follow the pins defined in the hal.cpp
|
||||
|
||||
// wire colours for VK2828U GPS
|
||||
#define PIN_GPS_TXD GPIO_NUM_12 // green
|
||||
#define PIN_GPS_RXD GPIO_NUM_35 // blue
|
||||
#define PIN_GPS_PPS GPIO_NUM_34 // white
|
||||
#define PIN_GPS_ENA GPIO_NUM_13 // yellow -> well, I had a problem here, thus I tied the enable wire to 3.3V for the time being.
|
||||
|
||||
Note the yellow wire: put it to 3.3V to start with.
|
||||
An attempt to control it from the CPU did not work, to be followed.
|
||||
|
||||
Note: I have seen GPSes where red was ground and black was power thus be carefull !
|
||||
|
||||
Note: If you use MTK GPS check the definitions in the hal.h accordingly if you want higher baud rates on the GPS UART
|
||||
|
||||
|
|
|
@ -0,0 +1,33 @@
|
|||
#include "bitcount.h"
|
||||
|
||||
#ifndef BITCOUNT_USE_BUILTIN
|
||||
#ifdef BITCOUNT_SAVE_FLASH
|
||||
const uint8_t ByteCount1s[ 16] = { 0, 1, 1, 2, 1, 2, 2, 3, 1, 2, 2, 3, 2, 3, 3, 4 } ;
|
||||
#else
|
||||
const uint8_t ByteCount1s[256] = {
|
||||
0, 1, 1, 2, 1, 2, 2, 3, 1, 2, 2, 3, 2, 3, 3, 4,
|
||||
1, 2, 2, 3, 2, 3, 3, 4, 2, 3, 3, 4, 3, 4, 4, 5,
|
||||
1, 2, 2, 3, 2, 3, 3, 4, 2, 3, 3, 4, 3, 4, 4, 5,
|
||||
2, 3, 3, 4, 3, 4, 4, 5, 3, 4, 4, 5, 4, 5, 5, 6,
|
||||
1, 2, 2, 3, 2, 3, 3, 4, 2, 3, 3, 4, 3, 4, 4, 5,
|
||||
2, 3, 3, 4, 3, 4, 4, 5, 3, 4, 4, 5, 4, 5, 5, 6,
|
||||
2, 3, 3, 4, 3, 4, 4, 5, 3, 4, 4, 5, 4, 5, 5, 6,
|
||||
3, 4, 4, 5, 4, 5, 5, 6, 4, 5, 5, 6, 5, 6, 6, 7,
|
||||
1, 2, 2, 3, 2, 3, 3, 4, 2, 3, 3, 4, 3, 4, 4, 5,
|
||||
2, 3, 3, 4, 3, 4, 4, 5, 3, 4, 4, 5, 4, 5, 5, 6,
|
||||
2, 3, 3, 4, 3, 4, 4, 5, 3, 4, 4, 5, 4, 5, 5, 6,
|
||||
3, 4, 4, 5, 4, 5, 5, 6, 4, 5, 5, 6, 5, 6, 6, 7,
|
||||
2, 3, 3, 4, 3, 4, 4, 5, 3, 4, 4, 5, 4, 5, 5, 6,
|
||||
3, 4, 4, 5, 4, 5, 5, 6, 4, 5, 5, 6, 5, 6, 6, 7,
|
||||
3, 4, 4, 5, 4, 5, 5, 6, 4, 5, 5, 6, 5, 6, 6, 7,
|
||||
4, 5, 5, 6, 5, 6, 6, 7, 5, 6, 6, 7, 6, 7, 7, 8
|
||||
} ;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
int Count1s(const uint8_t *Byte, int Bytes)
|
||||
{ int Count=0;
|
||||
for( ; Bytes>0; Bytes--)
|
||||
{ Count += Count1s(*Byte++); }
|
||||
return Count; }
|
||||
|
|
@ -0,0 +1,71 @@
|
|||
// Fast bit counting for (forward) error correction codes
|
||||
// (c) 2003, Pawel Jalocha, Pawel.Jalocha@cern.ch
|
||||
|
||||
#ifndef __BITCOUNT_H__
|
||||
#define __BITCOUNT_H__
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
// #define BITCOUNT_USE_BUILTIN
|
||||
#define BITCOUNT_SAVE_FLASH
|
||||
|
||||
// ==========================================================================
|
||||
// a table for fast bit counting
|
||||
|
||||
#ifdef BITCOUNT_SAVE_FLASH
|
||||
extern const uint8_t ByteCount1s[16];
|
||||
#else
|
||||
extern const uint8_t ByteCount1s[256];
|
||||
#endif
|
||||
|
||||
// ==========================================================================
|
||||
|
||||
#ifdef BITCOUNT_USE_BUILTIN
|
||||
inline uint8_t Count1s(uint8_t Byte) { return __builtin_popcount(Byte); }
|
||||
#else
|
||||
#ifdef BITCOUNT_SAVE_FLASH
|
||||
inline uint8_t Count1s(uint8_t Byte) { return ByteCount1s[Byte&0x0F] + ByteCount1s[Byte>>4]; }
|
||||
#else
|
||||
inline uint8_t Count1s(uint8_t Byte) { return ByteCount1s[Byte]; }
|
||||
#endif
|
||||
#endif
|
||||
|
||||
inline uint8_t Count1s(int8_t Byte) { return Count1s((uint8_t)Byte); }
|
||||
|
||||
#ifdef BITCOUNT_USE_BUILTIN
|
||||
inline uint8_t Count1s(uint16_t Word) { return __builtin_popcount(Word); }
|
||||
#else
|
||||
inline uint8_t Count1s(uint16_t Word)
|
||||
{ return Count1s((uint8_t)Word)
|
||||
+Count1s((uint8_t)(Word>>8)); }
|
||||
#endif
|
||||
|
||||
inline uint8_t Count1s(int16_t Word) { return Count1s((uint16_t)Word); }
|
||||
|
||||
#ifdef BITCOUNT_USE_BUILTIN
|
||||
inline uint8_t Count1s(uint32_t LongWord) { return __builtin_popcountl(LongWord); }
|
||||
#else
|
||||
inline uint8_t Count1s(uint32_t LongWord)
|
||||
{ return Count1s((uint16_t)LongWord)
|
||||
+Count1s((uint16_t)(LongWord>>16)); }
|
||||
#endif
|
||||
|
||||
inline uint8_t Count1s(int32_t LongWord) { return Count1s((uint32_t)LongWord); }
|
||||
|
||||
#ifdef BITCOUNT_USE_BUILTIN
|
||||
inline uint8_t Count1s(uint64_t LongWord) { return __builtin_popcountll(LongWord); }
|
||||
#else
|
||||
inline uint8_t Count1s(uint64_t LongWord)
|
||||
{ return Count1s((uint32_t)LongWord)
|
||||
+Count1s((uint32_t)(LongWord>>32)); }
|
||||
#endif
|
||||
|
||||
inline uint8_t Count1s(int64_t LongWord) { return Count1s((uint64_t)LongWord); }
|
||||
|
||||
int Count1s(const uint8_t *Byte, int Bytes);
|
||||
|
||||
// ==========================================================================
|
||||
|
||||
// use __builtin_popcount(unsigned int) ? http://stackoverflow.com/questions/109023/how-to-count-the-number-of-set-bits-in-a-32-bit-integer
|
||||
|
||||
#endif // of __BITCOUNT_H__
|
|
@ -0,0 +1,8 @@
|
|||
#
|
||||
# Main component makefile.
|
||||
#
|
||||
# This Makefile can be left empty. By default, it will take the sources in the
|
||||
# src/ directory, compile them and link them into lib(subdirectory_name).a
|
||||
# in the build directory. This behaviour is entirely configurable,
|
||||
# please read the ESP-IDF documents if you need to do this.
|
||||
#
|
|
@ -0,0 +1,189 @@
|
|||
#include <stdio.h>
|
||||
|
||||
#include "hal.h"
|
||||
|
||||
#include "ctrl.h"
|
||||
|
||||
#include "gps.h"
|
||||
#include "timesync.h"
|
||||
#include "format.h"
|
||||
|
||||
// ========================================================================================================================
|
||||
|
||||
void PrintTasks(void (*CONS_UART_Write)(char))
|
||||
{ char Line[32];
|
||||
|
||||
size_t FreeHeap = xPortGetFreeHeapSize();
|
||||
Format_String(CONS_UART_Write, "Task Pr. Stack, ");
|
||||
Format_UnsDec(CONS_UART_Write, (uint32_t)FreeHeap, 4, 3);
|
||||
Format_String(CONS_UART_Write, "kB free\n");
|
||||
|
||||
UBaseType_t uxArraySize = uxTaskGetNumberOfTasks();
|
||||
TaskStatus_t *pxTaskStatusArray = (TaskStatus_t *)pvPortMalloc( uxArraySize * sizeof( TaskStatus_t ) );
|
||||
if(pxTaskStatusArray==0) return;
|
||||
uxArraySize = uxTaskGetSystemState( pxTaskStatusArray, uxArraySize, NULL );
|
||||
for(UBaseType_t T=0; T<uxArraySize; T++)
|
||||
{ TaskStatus_t *Task = pxTaskStatusArray+T;
|
||||
uint8_t Len=Format_String(Line, Task->pcTaskName);
|
||||
for( ; Len<=configMAX_TASK_NAME_LEN; )
|
||||
Line[Len++]=' ';
|
||||
Len+=Format_UnsDec(Line+Len, Task->uxCurrentPriority, 2); Line[Len++]=' ';
|
||||
// Line[Len++]='0'+Task->uxCurrentPriority; Line[Len++]=' ';
|
||||
Len+=Format_UnsDec(Line+Len, Task->usStackHighWaterMark, 3);
|
||||
Line[Len++]='\n'; Line[Len++]=0;
|
||||
Format_String(CONS_UART_Write, Line);
|
||||
}
|
||||
vPortFree( pxTaskStatusArray );
|
||||
}
|
||||
|
||||
// ========================================================================================================================
|
||||
|
||||
#ifdef WITH_OLED
|
||||
int OLED_DisplayStatus(uint32_t Time, GPS_Position *GPS=0)
|
||||
{ char Line[20];
|
||||
Format_String(Line , "OGN Tx/Rx ");
|
||||
Format_HHMMSS(Line+10, Time);
|
||||
OLED_PutLine(0, Line);
|
||||
Parameters.Print(Line);
|
||||
OLED_PutLine(1, Line);
|
||||
if(GPS && GPS->isValid())
|
||||
{ Line[0]=' ';
|
||||
Format_SignDec(Line+1, GPS->Latitude /60, 6, 4); Line[9]=' ';
|
||||
Format_UnsDec (Line+10, GPS->Altitude /10, 5, 0); Line[15]='m';
|
||||
OLED_PutLine(2, Line);
|
||||
Format_SignDec(Line, GPS->Longitude/60, 7, 4);
|
||||
Format_SignDec(Line+10, GPS->ClimbRate, 4, 1);
|
||||
OLED_PutLine(3, Line);
|
||||
Format_UnsDec (Line , GPS->Speed, 4, 1); Format_String(Line+5, "m/s ");
|
||||
Format_UnsDec (Line+10, GPS->Heading, 4, 1); Line[15]='^';
|
||||
OLED_PutLine(4, Line);
|
||||
Format_String(Line, "0D/00sat DOP00.0");
|
||||
Line[0]+=GPS->FixMode; Format_UnsDec(Line+3, GPS->Satellites, 2);
|
||||
Format_UnsDec(Line+12, (uint16_t)GPS->HDOP, 3, 1);
|
||||
OLED_PutLine(5, Line);
|
||||
}
|
||||
else { OLED_PutLine(2, 0); OLED_PutLine(3, 0); OLED_PutLine(4, 0); }
|
||||
if(GPS && GPS->isDateValid())
|
||||
{ Format_UnsDec (Line , (uint16_t)GPS->Day, 2, 0); Line[2]='.';
|
||||
Format_UnsDec (Line+ 3, (uint16_t)GPS->Month, 2, 0); Line[5]='.';
|
||||
Format_UnsDec (Line+ 6, (uint16_t)GPS->Year , 2, 0); Line[8]=' '; Line[9]=' '; }
|
||||
else Format_String(Line, " ");
|
||||
if(GPS && GPS->isTimeValid())
|
||||
{ Format_UnsDec (Line+10, (uint16_t)GPS->Hour, 2, 0);
|
||||
Format_UnsDec (Line+12, (uint16_t)GPS->Min, 2, 0);
|
||||
Format_UnsDec (Line+14, (uint16_t)GPS->Sec, 2, 0);
|
||||
} else Line[10]=0;
|
||||
OLED_PutLine(6, Line);
|
||||
Line[0]=0;
|
||||
if(GPS && GPS->Baro)
|
||||
{ Format_String(Line , "0000.0hPa 00000m");
|
||||
Format_UnsDec(Line , GPS->Pressure/4, 5, 1);
|
||||
Format_UnsDec(Line+10, GPS->StdAltitude/10, 5, 0); }
|
||||
OLED_PutLine(7, Line);
|
||||
return 0; }
|
||||
#endif
|
||||
|
||||
// ========================================================================================================================
|
||||
|
||||
static NMEA_RxMsg NMEA;
|
||||
|
||||
static char Line[80];
|
||||
|
||||
static void PrintParameters(void) // print parameters stored in Flash
|
||||
{ Parameters.Print(Line);
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY); // ask exclusivity on UART1
|
||||
Format_String(CONS_UART_Write, Line);
|
||||
xSemaphoreGive(CONS_Mutex); // give back UART1 to other tasks
|
||||
}
|
||||
|
||||
#ifdef WITH_CONFIG
|
||||
static void ReadParameters(void) // read parameters requested by the user in the NMEA sent.
|
||||
{ if((!NMEA.hasCheck()) || NMEA.isChecked() )
|
||||
{ PrintParameters();
|
||||
if(NMEA.Parms==0) // if no parameter given
|
||||
{ xSemaphoreTake(CONS_Mutex, portMAX_DELAY); // print a help message
|
||||
Format_String(CONS_UART_Write, "$POGNS,<aircraft-type>,<addr-type>,<address>,<RFM69(H)W>,<Tx-power[dBm]>,<freq.corr.[kHz]>,<console baudrate[bps]>,<RF temp. corr.[degC]>,<pressure corr.[Pa]>\n");
|
||||
xSemaphoreGive(CONS_Mutex); //
|
||||
return; }
|
||||
Parameters.ReadPOGNS(NMEA);
|
||||
PrintParameters();
|
||||
esp_err_t Err = Parameters.WriteToNVS(); // erase and write the parameters into the Flash
|
||||
// if(Parameters.ReadFromNVS()!=ESP_OK) Parameters.setDefault();
|
||||
// Parameters.WriteToFlash(); // erase and write the parameters into the Flash
|
||||
// if(Parameters.ReadFromFlash()<0) Parameters.setDefault(); // read the parameters back: if invalid, set defaults
|
||||
// page erase lasts 20ms tus about 20 system ticks are lost here
|
||||
}
|
||||
// PrintParameters();
|
||||
}
|
||||
#endif
|
||||
|
||||
static void ProcessNMEA(void) // process a valid NMEA that got to the console
|
||||
{
|
||||
#ifdef WITH_CONFIG
|
||||
if(NMEA.isPOGNS()) ReadParameters();
|
||||
#endif
|
||||
}
|
||||
|
||||
static void ProcessCtrlC(void) // print system state to the console
|
||||
{ xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Parameters.Print(Line);
|
||||
Format_String(CONS_UART_Write, Line);
|
||||
Format_String(CONS_UART_Write, "GPS: ");
|
||||
Format_UnsDec(CONS_UART_Write, GPS_getBaudRate(), 1);
|
||||
Format_String(CONS_UART_Write, "bps");
|
||||
if(GPS_Status.PPS) Format_String(CONS_UART_Write, ",PPS");
|
||||
if(GPS_Status.NMEA) Format_String(CONS_UART_Write, ",NMEA");
|
||||
if(GPS_Status.UBX) Format_String(CONS_UART_Write, ",UBX");
|
||||
if(GPS_Status.MAV) Format_String(CONS_UART_Write, ",MAV");
|
||||
if(GPS_Status.BaudConfig) Format_String(CONS_UART_Write, ",BaudOK");
|
||||
if(GPS_Status.ModeConfig) Format_String(CONS_UART_Write, ",ModeOK");
|
||||
CONS_UART_Write('\r'); CONS_UART_Write('\n');
|
||||
PrintTasks(CONS_UART_Write);
|
||||
size_t Total, Used;
|
||||
if(SPIFFS_Info(Total, Used)==0)
|
||||
{ Format_String(CONS_UART_Write, "SPIFFS: ");
|
||||
Format_UnsDec(CONS_UART_Write, Used/1024);
|
||||
Format_String(CONS_UART_Write, "kB used, ");
|
||||
Format_UnsDec(CONS_UART_Write, Total/1024);
|
||||
Format_String(CONS_UART_Write, "kB total\n"); }
|
||||
Parameters.WriteFile(stdout);
|
||||
xSemaphoreGive(CONS_Mutex); }
|
||||
|
||||
static void ProcessInput(void)
|
||||
{ for( ; ; )
|
||||
{ uint8_t Byte; int Err=CONS_UART_Read(Byte); if(Err<=0) break; // get byte from console, if none: exit the loop
|
||||
if(Byte==0x03) ProcessCtrlC(); // if Ctrl-C received
|
||||
NMEA.ProcessByte(Byte); // pass the byte through the NMEA processor
|
||||
if(NMEA.isComplete()) // if complete NMEA:
|
||||
{ ProcessNMEA(); // interpret the NMEA
|
||||
NMEA.Clear(); } // clear the NMEA processor for the next sentence
|
||||
}
|
||||
}
|
||||
|
||||
// ========================================================================================================================
|
||||
|
||||
extern "C"
|
||||
void vTaskCTRL(void* pvParameters)
|
||||
{ uint32_t PrevTime=0;
|
||||
GPS_Position *PrevGPS=0;
|
||||
for( ; ; )
|
||||
{ ProcessInput();
|
||||
vTaskDelay(5);
|
||||
LED_TimerCheck(5);
|
||||
uint32_t Time=TimeSync_Time();
|
||||
GPS_Position *GPS = GPS_getPosition();
|
||||
bool TimeChange = Time!=PrevTime;
|
||||
bool GPSchange = GPS!=PrevGPS;
|
||||
if( (Time==PrevTime) && (GPS==PrevGPS) ) continue;
|
||||
PrevTime=Time; PrevGPS=GPS;
|
||||
#ifdef WITH_OLED
|
||||
OLED_DisplayStatus(Time, GPS);
|
||||
#endif
|
||||
#ifdef DEBUG_PRINT
|
||||
if(!TimeChange || (Time%60)!=0) continue;
|
||||
ProcessCtrlC();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
// ========================================================================================================================
|
|
@ -0,0 +1,43 @@
|
|||
#include "hal.h"
|
||||
|
||||
#include "ctrl.h"
|
||||
|
||||
void PrintTasks(void (*CONS_UART_Write)(char))
|
||||
{ char Line[32];
|
||||
|
||||
size_t FreeHeap = xPortGetFreeHeapSize();
|
||||
Format_String(CONS_UART_Write, "Task Pr. Stack, ");
|
||||
Format_UnsDec(CONS_UART_Write, (uint32_t)FreeHeap, 4, 3);
|
||||
Format_String(CONS_UART_Write, "kB free\n");
|
||||
|
||||
UBaseType_t uxArraySize = uxTaskGetNumberOfTasks();
|
||||
TaskStatus_t *pxTaskStatusArray = (TaskStatus_t *)pvPortMalloc( uxArraySize * sizeof( TaskStatus_t ) );
|
||||
if(pxTaskStatusArray==0) return;
|
||||
uxArraySize = uxTaskGetSystemState( pxTaskStatusArray, uxArraySize, NULL );
|
||||
for(UBaseType_t T=0; T<uxArraySize; T++)
|
||||
{ TaskStatus_t *Task = pxTaskStatusArray+T;
|
||||
uint8_t Len=Format_String(Line, Task->pcTaskName);
|
||||
for( ; Len<=configMAX_TASK_NAME_LEN; )
|
||||
Line[Len++]=' ';
|
||||
Len+=Format_UnsDec(Line+Len, Task->uxCurrentPriority, 2); Line[Len++]=' ';
|
||||
// Line[Len++]='0'+Task->uxCurrentPriority; Line[Len++]=' ';
|
||||
Len+=Format_UnsDec(Line+Len, Task->usStackHighWaterMark, 3);
|
||||
Line[Len++]='\n'; Line[Len++]=0;
|
||||
Format_String(CONS_UART_Write, Line);
|
||||
}
|
||||
vPortFree( pxTaskStatusArray );
|
||||
}
|
||||
|
||||
extern "C"
|
||||
void vTaskCTRL(void* pvParameters)
|
||||
{
|
||||
while(1)
|
||||
{ vTaskDelay(10000);
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
printf("10000 ticks...\n");
|
||||
|
||||
xSemaphoreGive(CONS_Mutex); // give back Console to other tasks
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,7 @@
|
|||
#include "hal.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
#endif
|
||||
void vTaskCTRL(void* pvParameters);
|
||||
|
|
@ -0,0 +1,132 @@
|
|||
#ifndef __FIFO_H__
|
||||
#define __FIFO_H__
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
template <class Type, const size_t Size=8> // size must be (!) a power of 2 like 4, 8, 16, 32, etc.
|
||||
class FIFO
|
||||
{ public:
|
||||
static const size_t Len = Size;
|
||||
static const size_t PtrMask = Size-1;
|
||||
|
||||
Type Data[Len];
|
||||
size_t ReadPtr;
|
||||
size_t WritePtr;
|
||||
|
||||
public:
|
||||
void Clear(void) // clear all stored data
|
||||
{ ReadPtr=0; WritePtr=0; }
|
||||
|
||||
size_t Write(Type Byte) // write a single element
|
||||
{ size_t Ptr=WritePtr;
|
||||
Data[Ptr]=Byte;
|
||||
Ptr++; Ptr&=PtrMask;
|
||||
if(Ptr==ReadPtr) return 0;
|
||||
WritePtr=Ptr; return 1; }
|
||||
|
||||
bool isFull(void) const // if FIFO full ?
|
||||
{ size_t Ptr=WritePtr;
|
||||
Ptr++; Ptr&=PtrMask;
|
||||
return Ptr==ReadPtr; }
|
||||
|
||||
size_t Free(void) const // number of free elements: how much can you write into te FIFO
|
||||
{ return ((ReadPtr-WritePtr-1)&PtrMask); }
|
||||
|
||||
size_t Full(void) const // number of stored elements: how much you can read from the FIFO
|
||||
{ return ((WritePtr-ReadPtr)&PtrMask); }
|
||||
|
||||
Type *getWrite(void) // get pointer to the next element which can be written
|
||||
{ return Data+WritePtr; }
|
||||
|
||||
size_t Write(void) // advance the write pointer: to be used with getWrite()
|
||||
{ size_t Ptr=WritePtr;
|
||||
Ptr++; Ptr&=PtrMask;
|
||||
if(Ptr==ReadPtr) return 0;
|
||||
WritePtr=Ptr; return 1; }
|
||||
|
||||
size_t Read(Type &Byte) // read a single element
|
||||
{ size_t Ptr=ReadPtr;
|
||||
if(Ptr==WritePtr) return 0;
|
||||
Byte=Data[Ptr];
|
||||
Ptr++; Ptr&=PtrMask;
|
||||
ReadPtr=Ptr; return 1; }
|
||||
|
||||
void Read(void)
|
||||
{ size_t Ptr=ReadPtr;
|
||||
if(Ptr==WritePtr) return;
|
||||
Ptr++; Ptr&=PtrMask;
|
||||
ReadPtr=Ptr; }
|
||||
|
||||
Type *getRead(void)
|
||||
{ if(ReadPtr==WritePtr) return 0;
|
||||
return Data+ReadPtr; }
|
||||
|
||||
Type *getRead(size_t Idx)
|
||||
{ if(Idx>=Full()) return 0;
|
||||
size_t Ptr=(ReadPtr+Idx)&PtrMask;
|
||||
return Data+Ptr; }
|
||||
|
||||
size_t getReadBlock(Type *&Byte) // get a pointer to the first element and the number of consecutive elements available for read
|
||||
{ if(ReadPtr==WritePtr) { Byte=0; return 0; }
|
||||
Byte = Data+ReadPtr;
|
||||
if(ReadPtr<WritePtr) return WritePtr-ReadPtr;
|
||||
return Size-ReadPtr; }
|
||||
|
||||
void flushReadBlock(size_t Len) // flush the elements which were already read: to be used after getReadBlock()
|
||||
{ ReadPtr+=Len; ReadPtr&=PtrMask; }
|
||||
|
||||
bool isEmpty(void) const // is the FIFO all empty ?
|
||||
{ return ReadPtr==WritePtr; }
|
||||
|
||||
size_t Write(const Type *Data, size_t Len) // write a block of elements into the FIFO (could possibly be smarter than colling single Write many times)
|
||||
{ size_t Idx;
|
||||
for(Idx=0; Idx<Len; Idx++)
|
||||
{ if(Write(Data[Idx])==0) break; }
|
||||
return Idx; }
|
||||
|
||||
/*
|
||||
Type Read(void)
|
||||
{ uint16_t Ptr=ReadPtr;
|
||||
if(Ptr==WritePtr) return 0x00;
|
||||
uint8_t Byte=Data[Ptr];
|
||||
Ptr++; Ptr&=PtrMask;
|
||||
ReadPtr=Ptr; return Byte; }
|
||||
|
||||
uint16_t ReadReady(void) const
|
||||
{ return ReadPtr!=WritePtr; }
|
||||
|
||||
uint8_t WriteReady(void) const
|
||||
{ uint8_t Ptr=WritePtr;
|
||||
Ptr++; Ptr&=PtrMask;
|
||||
return Ptr!=ReadPtr; }
|
||||
*/
|
||||
} ;
|
||||
|
||||
template <class Type, const uint8_t Size=8> // size must be (!) a power of 2 like 4, 8, 16, 32, etc.
|
||||
class Delay
|
||||
{ public:
|
||||
static const uint8_t Len = Size;
|
||||
static const uint8_t PtrMask = Size-1;
|
||||
|
||||
Type Data[Len];
|
||||
uint8_t Ptr;
|
||||
|
||||
public:
|
||||
void Clear(Type Zero=0)
|
||||
{ for(uint8_t Idx=0; Idx<Len; Idx++)
|
||||
Data[Idx]=Zero;
|
||||
Ptr=0; }
|
||||
|
||||
Type Input(Type Inp)
|
||||
{ Ptr--; Ptr&=PtrMask;
|
||||
Type Out=Data[Ptr];
|
||||
Data[Ptr]=Inp;
|
||||
return Out; }
|
||||
|
||||
Type & operator[](uint8_t Idx)
|
||||
{ Idx = Ptr-Idx; Idx&=PtrMask;
|
||||
return Data[Idx]; }
|
||||
|
||||
} ;
|
||||
|
||||
#endif // __FIFO_H__
|
|
@ -0,0 +1,166 @@
|
|||
#ifndef __FONT8X8_BASIC_H__
|
||||
#define __FONT8X8_BASIC_H__
|
||||
|
||||
/*
|
||||
Constant: font8x8_basic_tr
|
||||
Contains an 90 digree transposed 8x8 font map for unicode points
|
||||
U+0000 - U+007F (basic latin)
|
||||
|
||||
To make it easy to use with SSD1306's GDDRAM mapping and API,
|
||||
this constant is an 90 degree transposed.
|
||||
The original version written by Marcel Sondaar is availble at:
|
||||
https://github.com/dhepper/font8x8/blob/master/font8x8_basic.h
|
||||
|
||||
Conversion is done via following procedure:
|
||||
|
||||
for (int code = 0; code < 128; code++) {
|
||||
uint8_t trans[8];
|
||||
for (int w = 0; w < 8; w++) {
|
||||
trans[w] = 0x00;
|
||||
for (int b = 0; b < 8; b++) {
|
||||
trans[w] |= ((font8x8_basic[code][b] & (1 << w)) >> w) << b;
|
||||
}
|
||||
|
||||
for (int w = 0; w < 8; w++) {
|
||||
if (w == 0) { printf(" { "); }
|
||||
printf("0x%.2X", trans[w]);
|
||||
if (w < 7) { printf(", "); }
|
||||
if (w == 7) { printf(" }, // U+00%.2X (%c)\n", code, code); }
|
||||
}
|
||||
}
|
||||
*/
|
||||
|
||||
uint8_t font8x8_basic_tr[128][8] = {
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0000 (nul)
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0001
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0002
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0003
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0004
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0005
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0006
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0007
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0008
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0009
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+000A
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+000B
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+000C
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+000D
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+000E
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+000F
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0010
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0011
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0012
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0013
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0014
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0015
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0016
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0017
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0018
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0019
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+001A
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+001B
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+001C
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+001D
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+001E
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+001F
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0020 (space)
|
||||
{ 0x00, 0x00, 0x06, 0x5F, 0x5F, 0x06, 0x00, 0x00 }, // U+0021 (!)
|
||||
{ 0x00, 0x03, 0x03, 0x00, 0x03, 0x03, 0x00, 0x00 }, // U+0022 (")
|
||||
{ 0x14, 0x7F, 0x7F, 0x14, 0x7F, 0x7F, 0x14, 0x00 }, // U+0023 (#)
|
||||
{ 0x24, 0x2E, 0x6B, 0x6B, 0x3A, 0x12, 0x00, 0x00 }, // U+0024 ($)
|
||||
{ 0x46, 0x66, 0x30, 0x18, 0x0C, 0x66, 0x62, 0x00 }, // U+0025 (%)
|
||||
{ 0x30, 0x7A, 0x4F, 0x5D, 0x37, 0x7A, 0x48, 0x00 }, // U+0026 (&)
|
||||
{ 0x04, 0x07, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00 }, // U+0027 (')
|
||||
{ 0x00, 0x1C, 0x3E, 0x63, 0x41, 0x00, 0x00, 0x00 }, // U+0028 (()
|
||||
{ 0x00, 0x41, 0x63, 0x3E, 0x1C, 0x00, 0x00, 0x00 }, // U+0029 ())
|
||||
{ 0x08, 0x2A, 0x3E, 0x1C, 0x1C, 0x3E, 0x2A, 0x08 }, // U+002A (*)
|
||||
{ 0x08, 0x08, 0x3E, 0x3E, 0x08, 0x08, 0x00, 0x00 }, // U+002B (+)
|
||||
{ 0x00, 0x80, 0xE0, 0x60, 0x00, 0x00, 0x00, 0x00 }, // U+002C (,)
|
||||
{ 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x00, 0x00 }, // U+002D (-)
|
||||
{ 0x00, 0x00, 0x60, 0x60, 0x00, 0x00, 0x00, 0x00 }, // U+002E (.)
|
||||
{ 0x60, 0x30, 0x18, 0x0C, 0x06, 0x03, 0x01, 0x00 }, // U+002F (/)
|
||||
{ 0x3E, 0x7F, 0x71, 0x59, 0x4D, 0x7F, 0x3E, 0x00 }, // U+0030 (0)
|
||||
{ 0x40, 0x42, 0x7F, 0x7F, 0x40, 0x40, 0x00, 0x00 }, // U+0031 (1)
|
||||
{ 0x62, 0x73, 0x59, 0x49, 0x6F, 0x66, 0x00, 0x00 }, // U+0032 (2)
|
||||
{ 0x22, 0x63, 0x49, 0x49, 0x7F, 0x36, 0x00, 0x00 }, // U+0033 (3)
|
||||
{ 0x18, 0x1C, 0x16, 0x53, 0x7F, 0x7F, 0x50, 0x00 }, // U+0034 (4)
|
||||
{ 0x27, 0x67, 0x45, 0x45, 0x7D, 0x39, 0x00, 0x00 }, // U+0035 (5)
|
||||
{ 0x3C, 0x7E, 0x4B, 0x49, 0x79, 0x30, 0x00, 0x00 }, // U+0036 (6)
|
||||
{ 0x03, 0x03, 0x71, 0x79, 0x0F, 0x07, 0x00, 0x00 }, // U+0037 (7)
|
||||
{ 0x36, 0x7F, 0x49, 0x49, 0x7F, 0x36, 0x00, 0x00 }, // U+0038 (8)
|
||||
{ 0x06, 0x4F, 0x49, 0x69, 0x3F, 0x1E, 0x00, 0x00 }, // U+0039 (9)
|
||||
{ 0x00, 0x00, 0x66, 0x66, 0x00, 0x00, 0x00, 0x00 }, // U+003A (:)
|
||||
{ 0x00, 0x80, 0xE6, 0x66, 0x00, 0x00, 0x00, 0x00 }, // U+003B (;)
|
||||
{ 0x08, 0x1C, 0x36, 0x63, 0x41, 0x00, 0x00, 0x00 }, // U+003C (<)
|
||||
{ 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x00, 0x00 }, // U+003D (=)
|
||||
{ 0x00, 0x41, 0x63, 0x36, 0x1C, 0x08, 0x00, 0x00 }, // U+003E (>)
|
||||
{ 0x02, 0x03, 0x51, 0x59, 0x0F, 0x06, 0x00, 0x00 }, // U+003F (?)
|
||||
{ 0x3E, 0x7F, 0x41, 0x5D, 0x5D, 0x1F, 0x1E, 0x00 }, // U+0040 (@)
|
||||
{ 0x7C, 0x7E, 0x13, 0x13, 0x7E, 0x7C, 0x00, 0x00 }, // U+0041 (A)
|
||||
{ 0x41, 0x7F, 0x7F, 0x49, 0x49, 0x7F, 0x36, 0x00 }, // U+0042 (B)
|
||||
{ 0x1C, 0x3E, 0x63, 0x41, 0x41, 0x63, 0x22, 0x00 }, // U+0043 (C)
|
||||
{ 0x41, 0x7F, 0x7F, 0x41, 0x63, 0x3E, 0x1C, 0x00 }, // U+0044 (D)
|
||||
{ 0x41, 0x7F, 0x7F, 0x49, 0x5D, 0x41, 0x63, 0x00 }, // U+0045 (E)
|
||||
{ 0x41, 0x7F, 0x7F, 0x49, 0x1D, 0x01, 0x03, 0x00 }, // U+0046 (F)
|
||||
{ 0x1C, 0x3E, 0x63, 0x41, 0x51, 0x73, 0x72, 0x00 }, // U+0047 (G)
|
||||
{ 0x7F, 0x7F, 0x08, 0x08, 0x7F, 0x7F, 0x00, 0x00 }, // U+0048 (H)
|
||||
{ 0x00, 0x41, 0x7F, 0x7F, 0x41, 0x00, 0x00, 0x00 }, // U+0049 (I)
|
||||
{ 0x30, 0x70, 0x40, 0x41, 0x7F, 0x3F, 0x01, 0x00 }, // U+004A (J)
|
||||
{ 0x41, 0x7F, 0x7F, 0x08, 0x1C, 0x77, 0x63, 0x00 }, // U+004B (K)
|
||||
{ 0x41, 0x7F, 0x7F, 0x41, 0x40, 0x60, 0x70, 0x00 }, // U+004C (L)
|
||||
{ 0x7F, 0x7F, 0x0E, 0x1C, 0x0E, 0x7F, 0x7F, 0x00 }, // U+004D (M)
|
||||
{ 0x7F, 0x7F, 0x06, 0x0C, 0x18, 0x7F, 0x7F, 0x00 }, // U+004E (N)
|
||||
{ 0x1C, 0x3E, 0x63, 0x41, 0x63, 0x3E, 0x1C, 0x00 }, // U+004F (O)
|
||||
{ 0x41, 0x7F, 0x7F, 0x49, 0x09, 0x0F, 0x06, 0x00 }, // U+0050 (P)
|
||||
{ 0x1E, 0x3F, 0x21, 0x71, 0x7F, 0x5E, 0x00, 0x00 }, // U+0051 (Q)
|
||||
{ 0x41, 0x7F, 0x7F, 0x09, 0x19, 0x7F, 0x66, 0x00 }, // U+0052 (R)
|
||||
{ 0x26, 0x6F, 0x4D, 0x59, 0x73, 0x32, 0x00, 0x00 }, // U+0053 (S)
|
||||
{ 0x03, 0x41, 0x7F, 0x7F, 0x41, 0x03, 0x00, 0x00 }, // U+0054 (T)
|
||||
{ 0x7F, 0x7F, 0x40, 0x40, 0x7F, 0x7F, 0x00, 0x00 }, // U+0055 (U)
|
||||
{ 0x1F, 0x3F, 0x60, 0x60, 0x3F, 0x1F, 0x00, 0x00 }, // U+0056 (V)
|
||||
{ 0x7F, 0x7F, 0x30, 0x18, 0x30, 0x7F, 0x7F, 0x00 }, // U+0057 (W)
|
||||
{ 0x43, 0x67, 0x3C, 0x18, 0x3C, 0x67, 0x43, 0x00 }, // U+0058 (X)
|
||||
{ 0x07, 0x4F, 0x78, 0x78, 0x4F, 0x07, 0x00, 0x00 }, // U+0059 (Y)
|
||||
{ 0x47, 0x63, 0x71, 0x59, 0x4D, 0x67, 0x73, 0x00 }, // U+005A (Z)
|
||||
{ 0x00, 0x7F, 0x7F, 0x41, 0x41, 0x00, 0x00, 0x00 }, // U+005B ([)
|
||||
{ 0x01, 0x03, 0x06, 0x0C, 0x18, 0x30, 0x60, 0x00 }, // U+005C (\)
|
||||
{ 0x00, 0x41, 0x41, 0x7F, 0x7F, 0x00, 0x00, 0x00 }, // U+005D (])
|
||||
{ 0x08, 0x0C, 0x06, 0x03, 0x06, 0x0C, 0x08, 0x00 }, // U+005E (^)
|
||||
{ 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80 }, // U+005F (_)
|
||||
{ 0x00, 0x00, 0x03, 0x07, 0x04, 0x00, 0x00, 0x00 }, // U+0060 (`)
|
||||
{ 0x20, 0x74, 0x54, 0x54, 0x3C, 0x78, 0x40, 0x00 }, // U+0061 (a)
|
||||
{ 0x41, 0x7F, 0x3F, 0x48, 0x48, 0x78, 0x30, 0x00 }, // U+0062 (b)
|
||||
{ 0x38, 0x7C, 0x44, 0x44, 0x6C, 0x28, 0x00, 0x00 }, // U+0063 (c)
|
||||
{ 0x30, 0x78, 0x48, 0x49, 0x3F, 0x7F, 0x40, 0x00 }, // U+0064 (d)
|
||||
{ 0x38, 0x7C, 0x54, 0x54, 0x5C, 0x18, 0x00, 0x00 }, // U+0065 (e)
|
||||
{ 0x48, 0x7E, 0x7F, 0x49, 0x03, 0x02, 0x00, 0x00 }, // U+0066 (f)
|
||||
{ 0x98, 0xBC, 0xA4, 0xA4, 0xF8, 0x7C, 0x04, 0x00 }, // U+0067 (g)
|
||||
{ 0x41, 0x7F, 0x7F, 0x08, 0x04, 0x7C, 0x78, 0x00 }, // U+0068 (h)
|
||||
{ 0x00, 0x44, 0x7D, 0x7D, 0x40, 0x00, 0x00, 0x00 }, // U+0069 (i)
|
||||
{ 0x60, 0xE0, 0x80, 0x80, 0xFD, 0x7D, 0x00, 0x00 }, // U+006A (j)
|
||||
{ 0x41, 0x7F, 0x7F, 0x10, 0x38, 0x6C, 0x44, 0x00 }, // U+006B (k)
|
||||
{ 0x00, 0x41, 0x7F, 0x7F, 0x40, 0x00, 0x00, 0x00 }, // U+006C (l)
|
||||
{ 0x7C, 0x7C, 0x18, 0x38, 0x1C, 0x7C, 0x78, 0x00 }, // U+006D (m)
|
||||
{ 0x7C, 0x7C, 0x04, 0x04, 0x7C, 0x78, 0x00, 0x00 }, // U+006E (n)
|
||||
{ 0x38, 0x7C, 0x44, 0x44, 0x7C, 0x38, 0x00, 0x00 }, // U+006F (o)
|
||||
{ 0x84, 0xFC, 0xF8, 0xA4, 0x24, 0x3C, 0x18, 0x00 }, // U+0070 (p)
|
||||
{ 0x18, 0x3C, 0x24, 0xA4, 0xF8, 0xFC, 0x84, 0x00 }, // U+0071 (q)
|
||||
{ 0x44, 0x7C, 0x78, 0x4C, 0x04, 0x1C, 0x18, 0x00 }, // U+0072 (r)
|
||||
{ 0x48, 0x5C, 0x54, 0x54, 0x74, 0x24, 0x00, 0x00 }, // U+0073 (s)
|
||||
{ 0x00, 0x04, 0x3E, 0x7F, 0x44, 0x24, 0x00, 0x00 }, // U+0074 (t)
|
||||
{ 0x3C, 0x7C, 0x40, 0x40, 0x3C, 0x7C, 0x40, 0x00 }, // U+0075 (u)
|
||||
{ 0x1C, 0x3C, 0x60, 0x60, 0x3C, 0x1C, 0x00, 0x00 }, // U+0076 (v)
|
||||
{ 0x3C, 0x7C, 0x70, 0x38, 0x70, 0x7C, 0x3C, 0x00 }, // U+0077 (w)
|
||||
{ 0x44, 0x6C, 0x38, 0x10, 0x38, 0x6C, 0x44, 0x00 }, // U+0078 (x)
|
||||
{ 0x9C, 0xBC, 0xA0, 0xA0, 0xFC, 0x7C, 0x00, 0x00 }, // U+0079 (y)
|
||||
{ 0x4C, 0x64, 0x74, 0x5C, 0x4C, 0x64, 0x00, 0x00 }, // U+007A (z)
|
||||
{ 0x08, 0x08, 0x3E, 0x77, 0x41, 0x41, 0x00, 0x00 }, // U+007B ({)
|
||||
{ 0x00, 0x00, 0x00, 0x77, 0x77, 0x00, 0x00, 0x00 }, // U+007C (|)
|
||||
{ 0x41, 0x41, 0x77, 0x3E, 0x08, 0x08, 0x00, 0x00 }, // U+007D (})
|
||||
{ 0x02, 0x03, 0x01, 0x03, 0x02, 0x03, 0x01, 0x00 }, // U+007E (~)
|
||||
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 } // U+007F
|
||||
};
|
||||
|
||||
#endif // __FONT8X8_BASIC_H__
|
||||
|
||||
|
|
@ -0,0 +1,218 @@
|
|||
#include "format.h"
|
||||
|
||||
// ------------------------------------------------------------------------------------------
|
||||
|
||||
char HexDigit(uint8_t Val) { return Val+(Val<10?'0':'A'-10); }
|
||||
|
||||
// ------------------------------------------------------------------------------------------
|
||||
|
||||
void Format_Bytes( void (*Output)(char), const uint8_t *Bytes, uint8_t Len)
|
||||
{ for( ; Len; Len--)
|
||||
(*Output)(*Bytes++);
|
||||
}
|
||||
|
||||
void Format_String( void (*Output)(char), const char *String)
|
||||
{ for( ; ; )
|
||||
{ uint8_t ch = (*String++); if(ch==0) break;
|
||||
if(ch=='\n') (*Output)('\r');
|
||||
(*Output)(ch); }
|
||||
}
|
||||
|
||||
uint8_t Format_String(char *Str, const char *String)
|
||||
{ uint8_t OutLen=0;
|
||||
for( ; ; )
|
||||
{ char ch = (*String++); if(ch==0) break;
|
||||
if(ch=='\n') Str[OutLen++]='\r';
|
||||
Str[OutLen++]=ch; }
|
||||
return OutLen; }
|
||||
|
||||
uint8_t Format_String(char *Str, const char *String, uint8_t Len)
|
||||
{ uint8_t OutLen=0;
|
||||
for(uint8_t Idx=0; Idx<Len; Idx++)
|
||||
{ char ch = (*String++);
|
||||
if(ch=='\n') Str[OutLen++]='\r';
|
||||
Str[OutLen++]=ch; }
|
||||
return OutLen; }
|
||||
|
||||
void Format_Hex( void (*Output)(char), uint8_t Byte )
|
||||
{ (*Output)(HexDigit(Byte>>4)); (*Output)(HexDigit(Byte&0x0F)); }
|
||||
|
||||
void Format_Hex( void (*Output)(char), uint16_t Word )
|
||||
{ Format_Hex(Output, (uint8_t)(Word>>8)); Format_Hex(Output, (uint8_t)Word); }
|
||||
|
||||
void Format_Hex( void (*Output)(char), uint32_t Word )
|
||||
{ Format_Hex(Output, (uint8_t)(Word>>24)); Format_Hex(Output, (uint8_t)(Word>>16));
|
||||
Format_Hex(Output, (uint8_t)(Word>>8)); Format_Hex(Output, (uint8_t)Word); }
|
||||
|
||||
uint8_t Format_HHMMSS(char *Str, uint32_t Time)
|
||||
{ uint32_t DayTime=Time%86400;
|
||||
uint32_t Hour=DayTime/3600; DayTime-=Hour*3600;
|
||||
uint32_t Min=DayTime/60; DayTime-=Min*60;
|
||||
uint32_t Sec=DayTime;
|
||||
uint32_t HHMMSS = 10000*Hour + 100*Min + Sec;
|
||||
return Format_UnsDec(Str, HHMMSS, 6); }
|
||||
|
||||
void Format_UnsDec( void (*Output)(char), uint16_t Value, uint8_t MinDigits, uint8_t DecPoint)
|
||||
{ uint16_t Base; uint8_t Pos;
|
||||
for( Pos=5, Base=10000; Base; Base/=10, Pos--)
|
||||
{ uint8_t Dig;
|
||||
if(Value>=Base)
|
||||
{ Dig=Value/Base; Value-=Dig*Base; }
|
||||
else
|
||||
{ Dig=0; }
|
||||
if(Pos==DecPoint) (*Output)('.');
|
||||
if( (Pos<=MinDigits) || (Dig>0) || (Pos<=DecPoint) )
|
||||
{ (*Output)('0'+Dig); MinDigits=Pos; }
|
||||
}
|
||||
}
|
||||
|
||||
void Format_SignDec( void (*Output)(char), int16_t Value, uint8_t MinDigits, uint8_t DecPoint)
|
||||
{ if(Value<0) { (*Output)('-'); Value=(-Value); }
|
||||
else { (*Output)('+'); }
|
||||
Format_UnsDec(Output, (uint16_t)Value, MinDigits, DecPoint); }
|
||||
|
||||
void Format_UnsDec( void (*Output)(char), uint32_t Value, uint8_t MinDigits, uint8_t DecPoint)
|
||||
{ uint32_t Base; uint8_t Pos;
|
||||
for( Pos=10, Base=1000000000; Base; Base/=10, Pos--)
|
||||
{ uint8_t Dig;
|
||||
if(Value>=Base)
|
||||
{ Dig=Value/Base; Value-=Dig*Base; }
|
||||
else
|
||||
{ Dig=0; }
|
||||
if(Pos==DecPoint) (*Output)('.');
|
||||
if( (Pos<=MinDigits) || (Dig>0) || (Pos<=DecPoint) )
|
||||
{ (*Output)('0'+Dig); MinDigits=Pos; }
|
||||
}
|
||||
}
|
||||
|
||||
void Format_SignDec( void (*Output)(char), int32_t Value, uint8_t MinDigits, uint8_t DecPoint)
|
||||
{ if(Value<0) { (*Output)('-'); Value=(-Value); }
|
||||
else { (*Output)('+'); }
|
||||
Format_UnsDec(Output, (uint32_t)Value, MinDigits, DecPoint); }
|
||||
|
||||
// ------------------------------------------------------------------------------------------
|
||||
|
||||
uint8_t Format_UnsDec(char *Str, uint32_t Value, uint8_t MinDigits, uint8_t DecPoint)
|
||||
{ uint32_t Base; uint8_t Pos, Len=0;
|
||||
for( Pos=10, Base=1000000000; Base; Base/=10, Pos--)
|
||||
{ uint8_t Dig;
|
||||
if(Value>=Base)
|
||||
{ Dig=Value/Base; Value-=Dig*Base; }
|
||||
else
|
||||
{ Dig=0; }
|
||||
if(Pos==DecPoint) { (*Str++)='.'; Len++; }
|
||||
if( (Pos<=MinDigits) || (Dig>0) || (Pos<=DecPoint) )
|
||||
{ (*Str++)='0'+Dig; Len++; MinDigits=Pos; }
|
||||
}
|
||||
return Len; }
|
||||
|
||||
uint8_t Format_SignDec(char *Str, int32_t Value, uint8_t MinDigits, uint8_t DecPoint)
|
||||
{ if(Value<0) { (*Str++)='-'; Value=(-Value); }
|
||||
else { (*Str++)='+'; }
|
||||
return 1+Format_UnsDec(Str, Value, MinDigits, DecPoint); }
|
||||
|
||||
uint8_t Format_Hex( char *Output, uint8_t Byte )
|
||||
{ (*Output++) = HexDigit(Byte>>4); (*Output++)=HexDigit(Byte&0x0F); return 2; }
|
||||
|
||||
uint8_t Format_Hex( char *Output, uint16_t Word )
|
||||
{ Format_Hex(Output, (uint8_t)(Word>>8)); Format_Hex(Output+2, (uint8_t)Word); return 4; }
|
||||
|
||||
uint8_t Format_Hex( char *Output, uint32_t Word )
|
||||
{ Format_Hex(Output , (uint8_t)(Word>>24)); Format_Hex(Output+2, (uint8_t)(Word>>16));
|
||||
Format_Hex(Output+4, (uint8_t)(Word>> 8)); Format_Hex(Output+6, (uint8_t) Word ); return 8; }
|
||||
|
||||
uint8_t Format_Hex( char *Output, uint32_t Word, uint8_t Digits)
|
||||
{ for(uint8_t Idx=Digits; Idx>0; )
|
||||
{ Output[--Idx]=HexDigit(Word&0x0F);
|
||||
Word>>=4; }
|
||||
return Digits; }
|
||||
|
||||
// ------------------------------------------------------------------------------------------
|
||||
|
||||
int8_t Read_Hex1(char Digit)
|
||||
{ int8_t Val=Read_Dec1(Digit); if(Val>=0) return Val;
|
||||
if( (Digit>='A') && (Digit<='F') ) return Digit-'A'+10;
|
||||
if( (Digit>='a') && (Digit<='f') ) return Digit-'a'+10;
|
||||
return -1; }
|
||||
|
||||
int8_t Read_Dec1(char Digit) // convert single digit into an integer
|
||||
{ if(Digit<'0') return -1; // return -1 if not a decimal digit
|
||||
if(Digit>'9') return -1;
|
||||
return Digit-'0'; }
|
||||
|
||||
int8_t Read_Dec2(const char *Inp) // convert two digit decimal number into an integer
|
||||
{ int8_t High=Read_Dec1(Inp[0]); if(High<0) return -1;
|
||||
int8_t Low =Read_Dec1(Inp[1]); if(Low<0) return -1;
|
||||
return Low+10*High; }
|
||||
|
||||
int16_t Read_Dec3(const char *Inp) // convert three digit decimal number into an integer
|
||||
{ int8_t High=Read_Dec1(Inp[0]); if(High<0) return -1;
|
||||
int8_t Mid=Read_Dec1(Inp[1]); if(Mid<0) return -1;
|
||||
int8_t Low=Read_Dec1(Inp[2]); if(Low<0) return -1;
|
||||
return (int16_t)Low + (int16_t)10*(int16_t)Mid + (int16_t)100*(int16_t)High; }
|
||||
|
||||
int16_t Read_Dec4(const char *Inp) // convert three digit decimal number into an integer
|
||||
{ int16_t High=Read_Dec2(Inp ); if(High<0) return -1;
|
||||
int16_t Low =Read_Dec2(Inp+2); if(Low<0) return -1;
|
||||
return Low + (int16_t)100*(int16_t)High; }
|
||||
|
||||
// ------------------------------------------------------------------------------------------
|
||||
|
||||
int8_t Read_Coord(int32_t &Lat, const char *Inp)
|
||||
{ uint16_t Deg; int8_t Min, Sec;
|
||||
Lat=0;
|
||||
const char *Start=Inp;
|
||||
int8_t Len=Read_UnsDec(Deg, Inp); if(Len<0) return -1;
|
||||
Inp+=Len;
|
||||
Lat=(uint32_t)Deg*36000;
|
||||
if(Inp[0]!=(char)0xC2) return -1;
|
||||
if(Inp[1]!=(char)0xB0) return -1;
|
||||
Inp+=2;
|
||||
Min=Read_Dec2(Inp); if(Min<0) return -1;
|
||||
Inp+=2;
|
||||
Lat+=(uint32_t)Min*600;
|
||||
if(Inp[0]!=(char)'\'') return -1;
|
||||
Inp++;
|
||||
Sec=Read_Dec2(Inp); if(Sec<0) return -1;
|
||||
Inp+=2;
|
||||
Lat+=(uint32_t)Sec*10;
|
||||
if(Inp[0]=='.')
|
||||
{ Sec=Read_Dec1(Inp+1); if(Sec<0) return -1;
|
||||
Inp+=2; Lat+=Sec; }
|
||||
if(Inp[0]==(char)'\"') { Inp++; }
|
||||
else if( (Inp[0]==(char)'\'') && (Inp[1]==(char)'\'') ) { Inp+=2; }
|
||||
else return -1;
|
||||
return Inp-Start; }
|
||||
|
||||
int8_t Read_LatDDMMSS(int32_t &Lat, const char *Inp)
|
||||
{ Lat=0;
|
||||
const char *Start=Inp;
|
||||
int8_t Sign=0;
|
||||
if(Inp[0]=='N') { Sign= 1 ; Inp++; }
|
||||
else if(Inp[0]=='S') { Sign=(-1); Inp++; }
|
||||
int8_t Len=Read_Coord(Lat, Inp); if(Len<0) return -1;
|
||||
Inp+=Len;
|
||||
if(Sign==0)
|
||||
{ if(Inp[0]=='N') { Sign= 1 ; Inp++; }
|
||||
else if(Inp[0]=='S') { Sign=(-1); Inp++; }
|
||||
}
|
||||
if(Sign==0) return -1;
|
||||
if(Sign<0) Lat=(-Lat);
|
||||
return Inp-Start; }
|
||||
|
||||
int8_t Read_LonDDMMSS(int32_t &Lon, const char *Inp)
|
||||
{ Lon=0;
|
||||
const char *Start=Inp;
|
||||
int8_t Sign=0;
|
||||
if(Inp[0]=='E') { Sign= 1 ; Inp++; }
|
||||
else if(Inp[0]=='W') { Sign=(-1); Inp++; }
|
||||
int8_t Len=Read_Coord(Lon, Inp); if(Len<0) return -1;
|
||||
Inp+=Len;
|
||||
if(Sign==0)
|
||||
{ if(Inp[0]=='E') { Sign= 1 ; Inp++; }
|
||||
else if(Inp[0]=='W') { Sign=(-1); Inp++; }
|
||||
}
|
||||
if(Sign==0) return -1;
|
||||
if(Sign<0) Lon=(-Lon);
|
||||
return Inp-Start; }
|
||||
|
|
@ -0,0 +1,105 @@
|
|||
#ifndef __FORMAT_H__
|
||||
#define __FORMAT_H__
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
char HexDigit(uint8_t Val);
|
||||
|
||||
void Format_Bytes ( void (*Output)(char), const uint8_t *Bytes, uint8_t Len);
|
||||
inline void Format_Bytes ( void (*Output)(char), const char *Bytes, uint8_t Len) { Format_Bytes(Output, (const uint8_t *)Bytes, Len); }
|
||||
|
||||
void Format_String( void (*Output)(char), const char *String);
|
||||
inline void Format_String( void (*Output)(char), const char *String, uint8_t Len) { Format_Bytes(Output, (const uint8_t *)String, Len); }
|
||||
|
||||
void Format_Hex( void (*Output)(char), uint8_t Byte );
|
||||
void Format_Hex( void (*Output)(char), uint16_t Word );
|
||||
void Format_Hex( void (*Output)(char), uint32_t Word );
|
||||
|
||||
void Format_UnsDec ( void (*Output)(char), uint16_t Value, uint8_t MinDigits=1, uint8_t DecPoint=0);
|
||||
void Format_SignDec( void (*Output)(char), int16_t Value, uint8_t MinDigits=1, uint8_t DecPoint=0);
|
||||
|
||||
void Format_UnsDec ( void (*Output)(char), uint32_t Value, uint8_t MinDigits=1, uint8_t DecPoint=0);
|
||||
void Format_SignDec( void (*Output)(char), int32_t Value, uint8_t MinDigits=1, uint8_t DecPoint=0);
|
||||
|
||||
uint8_t Format_String(char *Str, const char *String);
|
||||
uint8_t Format_String(char *Str, const char *String, uint8_t Len);
|
||||
|
||||
uint8_t Format_UnsDec (char *Str, uint32_t Value, uint8_t MinDigits=1, uint8_t DecPoint=0);
|
||||
uint8_t Format_SignDec(char *Str, int32_t Value, uint8_t MinDigits=1, uint8_t DecPoint=0);
|
||||
|
||||
uint8_t Format_Hex( char *Output, uint8_t Byte );
|
||||
uint8_t Format_Hex( char *Output, uint16_t Word );
|
||||
uint8_t Format_Hex( char *Output, uint32_t Word );
|
||||
uint8_t Format_Hex( char *Output, uint32_t Word, uint8_t Digits);
|
||||
|
||||
uint8_t Format_HHMMSS(char *Str, uint32_t Time);
|
||||
|
||||
int8_t Read_Hex1(char Digit);
|
||||
int16_t Read_Hex2(const char *Inp);
|
||||
|
||||
int8_t Read_Dec1(char Digit); // convert single digit into an integer
|
||||
inline int8_t Read_Dec1(const char *Inp) { return Read_Dec1(Inp[0]); }
|
||||
int8_t Read_Dec2(const char *Inp); // convert two digit decimal number into an integer
|
||||
int16_t Read_Dec3(const char *Inp); // convert three digit decimal number into an integer
|
||||
int16_t Read_Dec4(const char *Inp); // convert three digit decimal number into an integer
|
||||
|
||||
template <class Type>
|
||||
int8_t Read_Hex(Type &Int, const char *Inp) // convert variable number of digits hexadecimal number into an integer
|
||||
{ Int=0; int8_t Len=0;
|
||||
if(Inp==0) return 0;
|
||||
for( ; ; )
|
||||
{ int8_t Dig=Read_Hex1(Inp[Len]); if(Dig<0) break;
|
||||
Int = (Int<<4) + Dig; Len++; }
|
||||
return Len; } // return number of characters read
|
||||
|
||||
template <class Type>
|
||||
int8_t Read_UnsDec(Type &Int, const char *Inp) // convert variable number of digits unsigned decimal number into an integer
|
||||
{ Int=0; int8_t Len=0;
|
||||
if(Inp==0) return 0;
|
||||
for( ; ; )
|
||||
{ int8_t Dig=Read_Dec1(Inp[Len]); if(Dig<0) break;
|
||||
Int = 10*Int + Dig; Len++; }
|
||||
return Len; } // return number of characters read
|
||||
|
||||
template <class Type>
|
||||
int8_t Read_SignDec(Type &Int, const char *Inp) // convert signed decimal number into in16_t or int32_t
|
||||
{ Int=0; int8_t Len=0;
|
||||
if(Inp==0) return 0;
|
||||
char Sign=Inp[0];
|
||||
if((Sign=='+')||(Sign=='-')) Len++;
|
||||
Len+=Read_UnsDec(Int, Inp+Len); if(Sign=='-') Int=(-Int);
|
||||
return Len; } // return number of characters read
|
||||
|
||||
template <class Type>
|
||||
int8_t Read_Int(Type &Value, const char *Inp)
|
||||
{ Value=0; int8_t Len=0;
|
||||
if(Inp==0) return 0;
|
||||
char Sign=Inp[0]; int8_t Dig;
|
||||
if((Sign=='+')||(Sign=='-')) Len++;
|
||||
if((Inp[Len]=='0')&&(Inp[Len+1]=='x'))
|
||||
{ Len+=2; Dig=Read_Hex(Value, Inp+Len); }
|
||||
else
|
||||
{ Dig=Read_UnsDec(Value, Inp+Len); }
|
||||
if(Dig<=0) return Dig;
|
||||
Len+=Dig;
|
||||
if(Sign=='-') Value=(-Value); return Len; }
|
||||
|
||||
template <class Type>
|
||||
int8_t Read_Float1(Type &Value, const char *Inp) // read floating point, take just one digit after decimal point
|
||||
{ Value=0; int8_t Len=0;
|
||||
if(Inp==0) return 0;
|
||||
char Sign=Inp[0]; int8_t Dig;
|
||||
if((Sign=='+')||(Sign=='-')) Len++;
|
||||
Len+=Read_UnsDec(Value, Inp+Len); Value*=10;
|
||||
if(Inp[Len]!='.') goto Ret;
|
||||
Len++;
|
||||
Dig=Read_Dec1(Inp[Len]); if(Dig<0) goto Ret;
|
||||
Value+=Dig; Len++;
|
||||
Dig=Read_Dec1(Inp[Len]); if(Dig>=5) Value++;
|
||||
Ret: if(Sign=='-') Value=(-Value); return Len; }
|
||||
|
||||
|
||||
int8_t Read_LatDDMMSS(int32_t &Lat, const char *Inp);
|
||||
int8_t Read_LonDDMMSS(int32_t &Lon, const char *Inp);
|
||||
|
||||
#endif // __FORMAT_H__
|
|
@ -0,0 +1,71 @@
|
|||
#ifndef __FREQPLAN_H__
|
||||
#define __FREQPLAN_H__
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
class FreqPlan
|
||||
{ public:
|
||||
uint8_t Plan; // 1=Europe, 2=USA/Canada, 3=Australia/Chile, 4=New Zeeland
|
||||
uint8_t Channels; // number of channels
|
||||
uint32_t BaseFreq; // [Hz] base channel (#0) frequency
|
||||
uint32_t ChanSepar; // [Hz] channel spacing
|
||||
static const uint8_t MaxChannels=65;
|
||||
|
||||
public:
|
||||
void setPlan(uint8_t NewPlan=0) // preset for a given frequency plan
|
||||
{ Plan=NewPlan;
|
||||
if(Plan==2) { BaseFreq=902200000; ChanSepar=400000; Channels=65; } // USA
|
||||
else if(Plan==3) { BaseFreq=917000000; ChanSepar=400000; Channels=24; } // Australia and South America
|
||||
else if(Plan==4) { BaseFreq=869250000; ChanSepar=200000; Channels= 1; } // New Zeeland
|
||||
else { BaseFreq=868200000; ChanSepar=200000; Channels= 2; } // Europe
|
||||
}
|
||||
|
||||
void setPlan(int32_t Latitude, int32_t Longitude)
|
||||
{ setPlan(calcPlan(Latitude, Longitude)); }
|
||||
|
||||
const char *getPlanName(void) { return getPlanName(Plan); }
|
||||
|
||||
static const char *getPlanName(uint8_t Plan)
|
||||
{ static const char *Name[5] = { "Default", "Europe/Africa", "USA/Canada", "Australia/South America", "New Zeeland" } ;
|
||||
if(Plan>4) return 0;
|
||||
return Name[Plan]; }
|
||||
|
||||
uint8_t getChannel (uint32_t Time, uint8_t Slot=0, uint8_t OGN=1) const // OGN-tracker or FLARM, UTC time, slot: 0 or 1
|
||||
{ if(Channels<=1) return 0; // if single channel (New Zeeland) return channel #0
|
||||
if(Plan>=2) // if USA/Canada or Australia/South America
|
||||
{ uint8_t Channel = FreqHopHash((Time<<1)+Slot) % Channels; // Flarm hopping channel
|
||||
if(OGN) // for OGN tracker
|
||||
{ if(Slot) { uint8_t Channel1=FreqHopHash((Time<<1)) % Channels; // for 2nd slot choose a channel close to the 1st slot
|
||||
Channel1++; if(Channel1>=Channels) Channel1-=2; //
|
||||
uint8_t Channel2=Channel1+1; if(Channel2>=Channels) Channel2-=2;
|
||||
if(Channel2==Channel) Channel=Channel1; // avoid being on same chanel as Flarm
|
||||
else Channel=Channel2; }
|
||||
else { Channel++; if(Channel>=Channels) Channel-=2; } // for 1st slot choose a higher channel (unless already highest, then choose a lower one)
|
||||
}
|
||||
return Channel; } // return 0..Channels-1 for USA/CA or Australia.
|
||||
return Slot^OGN; } // if Europe/South Africa: return 0 or 1 for EU freq. plan
|
||||
|
||||
uint32_t getChanFrequency(int Channel) const { return BaseFreq+ChanSepar*Channel; }
|
||||
|
||||
uint32_t getFrequency(uint32_t Time, uint8_t Slot=0, uint8_t OGN=1) const
|
||||
{ uint8_t Channel=getChannel(Time, Slot, OGN); return BaseFreq+ChanSepar*Channel; } // return frequency [Hz] for given UTC time and slot
|
||||
|
||||
uint8_t static calcPlan(int32_t Latitude, int32_t Longitude) // get the frequency plan from Lat/Lon: 1 = Europe + Africa, 2 = USA/CAnada, 3 = Australia + South America, 4$
|
||||
{ if( (Longitude>=(-20*600000)) && (Longitude<=(60*600000)) ) return 1; // between -20 and 60 deg Lat => Europe + Africa: 868MHz band
|
||||
if( Latitude<(20*600000) ) // below 20deg latitude
|
||||
{ if( ( Longitude>(164*600000)) && (Latitude<(-30*600000)) && (Latitude>(-48*600000)) ) return 4; // => New Zeeland
|
||||
return 3; } // => Australia + South America: upper half of 915MHz band
|
||||
return 2; } // => USA/Canada: full 915MHz band
|
||||
|
||||
private:
|
||||
static uint32_t FreqHopHash(uint32_t Time)
|
||||
{ Time = (Time<<15) + (~Time);
|
||||
Time ^= Time>>12;
|
||||
Time += Time<<2;
|
||||
Time ^= Time>>4;
|
||||
Time *= 2057;
|
||||
return Time ^ (Time>>16); }
|
||||
|
||||
} ;
|
||||
|
||||
#endif // __FREQPLAN_H__
|
|
@ -0,0 +1,569 @@
|
|||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "gps.h"
|
||||
|
||||
#include "nmea.h"
|
||||
#include "ubx.h"
|
||||
#ifdef WITH_MAVLINK
|
||||
#include "mavlink.h"
|
||||
#endif
|
||||
|
||||
#include "ogn.h"
|
||||
|
||||
// #include "ctrl.h"
|
||||
// #include "knob.h"
|
||||
|
||||
#include "lowpass2.h"
|
||||
|
||||
// #define DEBUG_PRINT
|
||||
|
||||
// ----------------------------------------------------------------------------
|
||||
|
||||
// void Debug_Print(uint8_t Byte) { while(!UART1_TxEmpty()) taskYIELD(); UART1_TxChar(Byte); }
|
||||
|
||||
static NMEA_RxMsg NMEA; // NMEA sentences catcher
|
||||
#ifdef WITH_GPS_UBX
|
||||
static UBX_RxMsg UBX; // UBX messages catcher
|
||||
#endif
|
||||
#ifdef WITH_MAVLINK
|
||||
static MAV_RxMsg MAV; // MAVlink message catcher
|
||||
#endif
|
||||
|
||||
static GPS_Position Position[4]; // GPS position pipe
|
||||
static uint8_t PosIdx; // Pipe index, increments with every GPS position received
|
||||
|
||||
static TickType_t Burst_TickCount; // [msec] TickCount when the data burst from GPS started
|
||||
|
||||
uint32_t GPS_TimeSinceLock; // [sec] time since the GPS has a lock
|
||||
uint32_t GPS_FatTime = 0; // [sec] UTC date/time in FAT format
|
||||
int32_t GPS_Altitude = 0; // [0.1m] last valid altitude
|
||||
int32_t GPS_Latitude = 0; //
|
||||
int32_t GPS_Longitude = 0; //
|
||||
int16_t GPS_GeoidSepar= 0; // [0.1m]
|
||||
uint16_t GPS_LatCosine = 3000; //
|
||||
|
||||
Status GPS_Status;
|
||||
|
||||
static union
|
||||
{ uint8_t Flags;
|
||||
struct
|
||||
{ bool Spare:1; //
|
||||
bool Active:1; // has started
|
||||
bool GxRMC:1; // GPRMC or GNRMC registered
|
||||
bool GxGGA:1; // GPGGA or GNGGA registered
|
||||
bool GxGSA:1; // GPGSA or GNGSA registered
|
||||
bool Complete:1; // all GPS data is supplied and thus ready for processing
|
||||
} ;
|
||||
} GPS_Burst;
|
||||
// for the autobaud on the GPS port
|
||||
const int GPS_BurstTimeout = 200; // [ms]
|
||||
|
||||
static const uint8_t BaudRates=7; // number of possible baudrates choices
|
||||
static uint8_t BaudRateIdx=0; // actual choice
|
||||
static const uint32_t BaudRate[BaudRates] = { 4800, 9600, 19200, 38400, 57600, 115200, 230400 } ; // list of baudrate the autobaud scans through
|
||||
|
||||
uint32_t GPS_getBaudRate (void) { return BaudRate[BaudRateIdx]; }
|
||||
uint32_t GPS_nextBaudRate(void) { BaudRateIdx++; if(BaudRateIdx>=BaudRates) BaudRateIdx=0; return GPS_getBaudRate(); }
|
||||
|
||||
const uint32_t GPS_TargetBaudRate = 57600; // BaudRate[4]; // [bps] must be one of the baud rates known by the autbaud
|
||||
const uint8_t GPS_dynModel = 7; // for UBX GPS's: 6 = airborne with >1g, 7 = with >2g
|
||||
|
||||
// ----------------------------------------------------------------------------
|
||||
|
||||
int16_t GPS_AverageSpeed(void) // get average speed based on stored GPS positions
|
||||
{ uint8_t Count=0;
|
||||
int16_t Speed=0;
|
||||
for(uint8_t Idx=0; Idx<4; Idx++) // loop over GPS positions
|
||||
{ GPS_Position *Pos = Position+Idx;
|
||||
if( !Pos->GPS || !Pos->isValid() ) continue; // skip invalid positions
|
||||
Speed += Pos->Speed +abs(Pos->ClimbRate); Count++;
|
||||
}
|
||||
if(Count==0) return -1;
|
||||
if(Count>1) Speed/=Count;
|
||||
return Speed; } // [0.1m/s]
|
||||
|
||||
// ----------------------------------------------------------------------------
|
||||
|
||||
static void GPS_PPS_On(void) // called on rising edge of PPS
|
||||
{ static TickType_t PrevTickCount=0;
|
||||
TickType_t TickCount = xTaskGetTickCount(); // [ms] TickCount now
|
||||
TickType_t Delta = TickCount-PrevTickCount; // [ms] time difference to the previous PPS
|
||||
PrevTickCount = TickCount; // [ms]
|
||||
if(abs((int)Delta-1000)>10) return; // [ms] filter out difference away from 1.00sec
|
||||
TimeSync_HardPPS(TickCount);
|
||||
#ifdef DEBUG_PRINT
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_Time()%60);
|
||||
CONS_UART_Write('.');
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_msTime(),3);
|
||||
Format_String(CONS_UART_Write, " -> PPS\n");
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
GPS_Status.PPS=1;
|
||||
LED_PCB_Flash(50);
|
||||
// uint8_t Sec=GPS_Sec; Sec++; if(Sec>=60) Sec=0; GPS_Sec=Sec;
|
||||
// GPS_UnixTime++;
|
||||
#ifdef WITH_MAVLINK
|
||||
static MAV_SYSTEM_TIME MAV_Time;
|
||||
MAV_Time.time_unix_usec = (uint64_t)1000000*TimeSync_Time();
|
||||
MAV_Time.time_boot_ms = TickCount;
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
MAV_RxMsg::Send(sizeof(MAV_Time), MAV_Seq++, MAV_SysID, MAV_COMP_ID_GPS, MAV_ID_SYSTEM_TIME, (const uint8_t *)&MAV_Time, CONS_UART_Write);
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void GPS_PPS_Off(void) // called on falling edge of PPS
|
||||
{ }
|
||||
|
||||
// ----------------------------------------------------------------------------
|
||||
|
||||
static void GPS_LockStart(void) // called when GPS catches a lock
|
||||
{
|
||||
|
||||
#ifdef WITH_BEEPER
|
||||
if(KNOB_Tick>12)
|
||||
{ Play(Play_Vol_1 | Play_Oct_1 | 0x00, 100);
|
||||
Play(Play_Vol_0 | Play_Oct_1 | 0x00, 100);
|
||||
Play(Play_Vol_1 | Play_Oct_1 | 0x02, 100);
|
||||
Play(Play_Vol_0 | Play_Oct_1 | 0x02, 100); }
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
static void GPS_LockEnd(void) // called when GPS looses a lock
|
||||
{
|
||||
|
||||
#ifdef WITH_BEEPER
|
||||
if(KNOB_Tick>12)
|
||||
{ Play(Play_Vol_1 | Play_Oct_1 | 0x02, 100);
|
||||
Play(Play_Vol_0 | Play_Oct_1 | 0x02, 100);
|
||||
Play(Play_Vol_1 | Play_Oct_1 | 0x00, 100);
|
||||
Play(Play_Vol_0 | Play_Oct_1 | 0x00, 100); }
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
// ----------------------------------------------------------------------------
|
||||
|
||||
const uint8_t GPS_BurstDelay=70; // [ms] time after the PPS when the data burst starts on the UART
|
||||
|
||||
static void GPS_BurstStart(void) // when GPS starts sending the data on the serial port
|
||||
{ Burst_TickCount=xTaskGetTickCount();
|
||||
#ifdef DEBUG_PRINT
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_Time()%60);
|
||||
CONS_UART_Write('.');
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_msTime(),3);
|
||||
Format_String(CONS_UART_Write, " -> GPS...\n");
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
#ifdef WITH_GPS_CONFIG
|
||||
static uint16_t QueryWait=0;
|
||||
if(GPS_Status.NMEA) // if there is communication with the GPS already
|
||||
{ if(QueryWait)
|
||||
{ QueryWait--; }
|
||||
else
|
||||
{ if(!GPS_Status.ModeConfig) // if GPS navigation mode is not done yet
|
||||
{ // Format_String(CONS_UART_Write, "CFG_NAV5 query...\n");
|
||||
#ifdef WITH_GPS_UBX
|
||||
UBX_RxMsg::SendPoll(0x06, 0x24, GPS_UART_Write); // send the query for the navigation mode setting
|
||||
#endif
|
||||
}
|
||||
if(!GPS_Status.BaudConfig) // if GPS baud config is not done yet
|
||||
{ // Format_String(CONS_UART_Write, "CFG_PRT query...\n");
|
||||
#ifdef WITH_GPS_UBX
|
||||
UBX_RxMsg::SendPoll(0x06, 0x00, GPS_UART_Write); // send the query for the port config to have a template configuration packet
|
||||
#endif
|
||||
#ifdef WITH_GPS_MTK
|
||||
static char GPS_Cmd[32];
|
||||
strcpy(GPS_Cmd, "$PMTK251,"); // MTK command to change the baud rate
|
||||
uint8_t Len = strlen(GPS_Cmd);
|
||||
Len += Format_UnsDec(GPS_Cmd+Len, GPS_TargetBaudRate);
|
||||
Len += NMEA_AppendCheck(GPS_Cmd, Len);
|
||||
GPS_Cmd[Len]=0;
|
||||
// Serial.println(GPS_Cmd);
|
||||
Format_String(GPS_UART_Write, GPS_Cmd, Len);
|
||||
GPS_UART_Write('\r'); GPS_UART_Write('\n');
|
||||
#endif
|
||||
#ifdef WITH_GPS_SRF
|
||||
strcpy(GPS_Cmd, "$PSRF100,1,"); // SiRF command to change the baud rate
|
||||
Len = strlen(GPS_Cmd);
|
||||
Len += Format_UnsDec(GPS_Cmd+Len, GPS_TargetBaudRate);
|
||||
strcpy(GPS_Cmd+Len, ",8,1,0");
|
||||
Len = strlen(GPS_Cmd);
|
||||
Len += NMEA_AppendCheck(GPS_Cmd, Len);
|
||||
GPS_Cmd[Len]=0;
|
||||
// Serial.println(GPS_Cmd);
|
||||
Format_String(GPS_UART_Write, GPS_Cmd, Len);
|
||||
GPS_UART_Write('\r'); GPS_UART_Write('\n');
|
||||
#endif
|
||||
}
|
||||
QueryWait=300;
|
||||
}
|
||||
}
|
||||
else { QueryWait=0; }
|
||||
#endif // WITH_GPS_CONFIG
|
||||
}
|
||||
|
||||
static void GPS_BurstComplete(void) // when GPS has sent the essential data for position fix
|
||||
{
|
||||
#ifdef DEBUG_PRINT
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_Time()%60);
|
||||
CONS_UART_Write('.');
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_msTime(),3);
|
||||
Format_String(CONS_UART_Write, " -> ...complete\n");
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
if(Position[PosIdx].GPS) // GPS position data complete
|
||||
{ Position[PosIdx].Ready=1;
|
||||
if(Position[PosIdx].isTimeValid()) // if time is valid already
|
||||
{ if(Position[PosIdx].isDateValid()) // if date is valid as well
|
||||
{ uint32_t UnixTime=Position[PosIdx].getUnixTime();
|
||||
GPS_FatTime=Position[PosIdx].getFatTime();
|
||||
TimeSync_SoftPPS(Burst_TickCount, UnixTime, GPS_BurstDelay); //
|
||||
}
|
||||
}
|
||||
if(Position[PosIdx].isValid()) // position is complete and locked
|
||||
{ Position[PosIdx].calcLatitudeCosine();
|
||||
GPS_TimeSinceLock++;
|
||||
GPS_Altitude=Position[PosIdx].Altitude;
|
||||
GPS_Latitude=Position[PosIdx].Latitude;
|
||||
GPS_Longitude=Position[PosIdx].Longitude;
|
||||
GPS_GeoidSepar=Position[PosIdx].GeoidSeparation;
|
||||
GPS_LatCosine=Position[PosIdx].LatitudeCosine;
|
||||
// GPS_FreqPlan=Position[PosIdx].getFreqPlan();
|
||||
if(GPS_TimeSinceLock==1)
|
||||
{ GPS_LockStart(); }
|
||||
if(GPS_TimeSinceLock>1)
|
||||
{ uint8_t PrevIdx=(PosIdx+3)&3;
|
||||
Position[PosIdx].calcDifferences(Position[PrevIdx]);
|
||||
LED_PCB_Flash(100); }
|
||||
}
|
||||
else // complete but no valid lock
|
||||
{ if(GPS_TimeSinceLock) { GPS_LockEnd(); GPS_TimeSinceLock=0; }
|
||||
}
|
||||
#ifdef WITH_MAVLINK
|
||||
static MAV_GPS_RAW_INT MAV_Position;
|
||||
Position[PosIdx].Encode(MAV_Position);
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
MAV_RxMsg::Send(sizeof(MAV_Position), MAV_Seq++, MAV_SysID, MAV_COMP_ID_GPS, MAV_ID_GPS_RAW_INT, (const uint8_t *)&MAV_Position, CONS_UART_Write);
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
}
|
||||
else // posiiton not complete, no GPS lock
|
||||
{ if(GPS_TimeSinceLock) { GPS_LockEnd(); GPS_TimeSinceLock=0; }
|
||||
}
|
||||
uint8_t NextPosIdx = (PosIdx+1)&3; // next position to be recorded
|
||||
Position[NextPosIdx].Clear(); // clear the next position
|
||||
int8_t Sec = Position[PosIdx].Sec; //
|
||||
Sec++; if(Sec>=60) Sec=0;
|
||||
Position[NextPosIdx].Sec=Sec; // set the correct time for the next position
|
||||
// Position[NextPosIdx].copyTime(Position[PosIdx]); // copy time from current position
|
||||
// Position[NextPosIdx].incrTime(); // increment time by 1 sec
|
||||
PosIdx=NextPosIdx; // advance the index
|
||||
}
|
||||
|
||||
static void GPS_BurstEnd(void) // when GPS stops sending the data on the serial port
|
||||
{ }
|
||||
|
||||
GPS_Position *GPS_getPosition(void) // return most recent GPS_Position which is complete
|
||||
{ uint8_t PrevIdx=PosIdx;
|
||||
GPS_Position *PrevPos = Position+PrevIdx;
|
||||
if(PrevPos->GPS) return PrevPos;
|
||||
PrevIdx=(PrevIdx+3)&3;
|
||||
PrevPos = Position+PrevIdx;
|
||||
if(PrevPos->GPS) return PrevPos;
|
||||
return 0; }
|
||||
|
||||
GPS_Position *GPS_getPosition(int8_t Sec) // return the GPS_Position which corresponds to given Sec (may be incomplete and not valid)
|
||||
{ for(uint8_t Idx=0; Idx<4; Idx++)
|
||||
{ if(Sec==Position[Idx].Sec) return Position+Idx; }
|
||||
return 0; }
|
||||
|
||||
// ----------------------------------------------------------------------------
|
||||
|
||||
static void GPS_NMEA(void) // when GPS gets a correct NMEA sentence
|
||||
{ GPS_Status.NMEA=1;
|
||||
GPS_Status.BaudConfig = (GPS_getBaudRate() == GPS_TargetBaudRate);
|
||||
LED_PCB_Flash(2); // Flash the LED for 2 ms
|
||||
Position[PosIdx].ReadNMEA(NMEA); // read position elements from NMEA
|
||||
if(NMEA.isGxRMC()) GPS_Burst.GxRMC=1;
|
||||
if(NMEA.isGxGGA()) GPS_Burst.GxGGA=1;
|
||||
if(NMEA.isGxGSA()) GPS_Burst.GxGSA=1;
|
||||
#ifdef DEBUG_PRINT
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_Time()%60);
|
||||
CONS_UART_Write('.');
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_msTime(),3);
|
||||
Format_String(CONS_UART_Write, " -> ");
|
||||
Format_Bytes(CONS_UART_Write, NMEA.Data, 6);
|
||||
CONS_UART_Write(' '); Format_Hex(CONS_UART_Write, GPS_Burst.Flags);
|
||||
CONS_UART_Write('\r'); CONS_UART_Write('\n');
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
if( NMEA.isP() || NMEA.isGxRMC() || NMEA.isGxGGA() || NMEA.isGxGSA() || NMEA.isGPTXT() )
|
||||
{ static char CRNL[3] = "\r\n";
|
||||
// if(CONS_UART_Free()>=128)
|
||||
{ xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_Bytes(CONS_UART_Write, NMEA.Data, NMEA.Len);
|
||||
Format_Bytes(CONS_UART_Write, (const uint8_t *)CRNL, 2);
|
||||
xSemaphoreGive(CONS_Mutex); }
|
||||
#ifdef WITH_SDLOG
|
||||
if(Log_Free()>=128)
|
||||
{ xSemaphoreTake(Log_Mutex, portMAX_DELAY);
|
||||
Format_Bytes(Log_Write, NMEA.Data, NMEA.Len);
|
||||
Format_Bytes(Log_Write, (const uint8_t *)CRNL, 2);
|
||||
xSemaphoreGive(Log_Mutex); }
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
static void DumpUBX(void)
|
||||
{ Format_String(CONS_UART_Write, "UBX:");
|
||||
for(uint8_t Idx=0; Idx<20; Idx++)
|
||||
{ CONS_UART_Write(' '); Format_Hex(CONS_UART_Write, UBX.Byte[Idx]); }
|
||||
Format_String(CONS_UART_Write, "\n"); }
|
||||
|
||||
#ifdef WITH_GPS_UBX
|
||||
static void GPS_UBX(void) // when GPS gets an UBX packet
|
||||
{ GPS_Status.UBX=1;
|
||||
GPS_Status.BaudConfig = (GPS_getBaudRate() == GPS_TargetBaudRate);
|
||||
LED_PCB_Flash(2);
|
||||
#ifdef WITH_GPS_UBX_PASS
|
||||
{ xSemaphoreTake(CONS_Mutex, portMAX_DELAY); // send ther UBX packet to the console
|
||||
UBX.Send(CONS_UART_Write);
|
||||
// Format_String(CONS_UART_Write, "UBX");
|
||||
// Format_Hex(CONS_UART_Write, UBX.Class);
|
||||
// Format_Hex(CONS_UART_Write, UBX.ID);
|
||||
xSemaphoreGive(CONS_Mutex); }
|
||||
#endif
|
||||
#ifdef WITH_GPS_CONFIG
|
||||
if(UBX.isCFG_PRT()) // if port configuration
|
||||
{ class UBX_CFG_PRT *CFG = (class UBX_CFG_PRT *)UBX.Word; // create pointer to the packet content
|
||||
#ifdef DEBUG_PRINT
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, "TaskGPS: CFG_PRT\n");
|
||||
DumpUBX();
|
||||
Format_Hex(CONS_UART_Write, CFG->portID);
|
||||
CONS_UART_Write(':');
|
||||
Format_UnsDec(CONS_UART_Write, CFG->baudRate);
|
||||
Format_String(CONS_UART_Write, "bps\n");
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
if(CFG->baudRate==GPS_TargetBaudRate) GPS_Status.BaudConfig=1; // if baudrate same as our target then declare the baud config is done
|
||||
else // otherwise use the received packet as the template
|
||||
{ CFG->baudRate=GPS_TargetBaudRate; // set the baudrate to our target
|
||||
UBX.RecalcCheck(); // reclaculate the check sum
|
||||
#ifdef DEBUG_PRINT
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_UnsDec(CONS_UART_Write, GPS_TargetBaudRate);
|
||||
Format_String(CONS_UART_Write, "bps\n");
|
||||
DumpUBX();
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
UBX.Send(GPS_UART_Write); // send this UBX packet to the GPS
|
||||
}
|
||||
}
|
||||
if(UBX.isCFG_NAV5()) // Navigation config
|
||||
{ class UBX_CFG_NAV5 *CFG = (class UBX_CFG_NAV5 *)UBX.Word;
|
||||
#ifdef DEBUG_PRINT
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, "TaskGPS: CFG_NAV5 ");
|
||||
Format_Hex(CONS_UART_Write, CFG->dynModel);
|
||||
Format_String(CONS_UART_Write, "\n");
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
if(CFG->dynModel==GPS_dynModel) GPS_Status.ModeConfig=1; // dynamic model = 6 => Airborne with >1g acceleration
|
||||
else
|
||||
{ CFG->dynModel=GPS_dynModel; CFG->mask = 0x01; //
|
||||
UBX.RecalcCheck(); // reclaculate the check sum
|
||||
UBX.Send(GPS_UART_Write); // send this UBX packet
|
||||
}
|
||||
}
|
||||
#ifdef DEBUG_PRINT
|
||||
if(UBX.isACK())
|
||||
{ xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, "TaskGPS: ACK_ ");
|
||||
Format_Hex(CONS_UART_Write, UBX.ID);
|
||||
CONS_UART_Write(' ');
|
||||
Format_Hex(CONS_UART_Write, UBX.Byte[0]);
|
||||
CONS_UART_Write(':');
|
||||
Format_Hex(CONS_UART_Write, UBX.Byte[1]);
|
||||
Format_String(CONS_UART_Write, "\n");
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
}
|
||||
#endif
|
||||
#endif // WITH_GPS_CONFIG
|
||||
}
|
||||
#endif // WITH_GPS_UBX
|
||||
|
||||
#ifdef WITH_MAVLINK
|
||||
static void GPS_MAV(void) // when GPS gets an MAV packet
|
||||
{ GPS_Status.MAV=1;
|
||||
GPS_Status.BaudConfig = (GPS_getBaudRate() == GPS_TargetBaudRate);
|
||||
}
|
||||
#endif
|
||||
|
||||
// ----------------------------------------------------------------------------
|
||||
|
||||
// Baud setting for SIRF GPS:
|
||||
// 9600/8/N/1 $PSRF100,1,9600,8,1,0*0D<cr><lf>
|
||||
// 19200/8/N/1 $PSRF100,1,19200,8,1,0*38<cr><lf>
|
||||
// 38400/8/N/1 $PSRF100,1,38400,8,1,0*3D<cr><lf>
|
||||
// $PSRF100,1,57600,8,1,0*36
|
||||
// $PSRF100,1,115200,8,1,0*05
|
||||
|
||||
// static const char *SiRF_SetBaudrate_57600 = "$PSRF100,1,57600,8,1,0*36\r\n";
|
||||
// static const char *SiRF_SetBaudrate_115200 = "$PSRF100,1,115200,8,1,0*05\r\n";
|
||||
|
||||
|
||||
// Baud setting for MTK GPS:
|
||||
// $PMTK251,38400*27<CR><LF>
|
||||
// $PMTK251,57600*2C<CR><LF>
|
||||
// $PMTK251,115200*1F<CR><LF>
|
||||
|
||||
// static const char *MTK_SetBaudrate_115200 = "$PMTK251,115200*1F\r\n";
|
||||
|
||||
|
||||
// Baud setting for UBX GPS:
|
||||
// "$PUBX,41,1,0003,0001,19200,0*23\r\n"
|
||||
// "$PUBX,41,1,0003,0001,38400,0*26\r\n"
|
||||
// "$PUBX,41,1,0003,0001,57600,0*2D\r\n"
|
||||
// static const char *UBX_SetBaudrate_115200 = "$PUBX,41,1,0003,0001,115200,0*1E\r\n";
|
||||
|
||||
// ----------------------------------------------------------------------------
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
#endif
|
||||
void vTaskGPS(void* pvParameters)
|
||||
{
|
||||
GPS_Status.Flags = 0;
|
||||
#ifdef WITH_PPS_IRQ
|
||||
GPS_PPS_IRQ_Callback = PPS_IRQ;
|
||||
#endif
|
||||
|
||||
// PPS_TickCount=0;
|
||||
Burst_TickCount=0;
|
||||
|
||||
vTaskDelay(5);
|
||||
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, "TaskGPS:");
|
||||
Format_String(CONS_UART_Write, "\n");
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
|
||||
GPS_Burst.Flags=0;
|
||||
bool PPS=0;
|
||||
int LineIdle=0; // [ms] counts idle time for the GPS data
|
||||
int NoValidData=0; // [ms] count time without valid data (to decide to change baudrate)
|
||||
NMEA.Clear();
|
||||
#ifdef WITH_GPS_UBX
|
||||
UBX.Clear(); // scans GPS input for NMEA and UBX frames
|
||||
#endif
|
||||
#ifdef WITH_MAVLINK
|
||||
MAV.Clear();
|
||||
#endif
|
||||
for(uint8_t Idx=0; Idx<4; Idx++)
|
||||
Position[Idx].Clear();
|
||||
PosIdx=0;
|
||||
|
||||
TickType_t RefTick = xTaskGetTickCount();
|
||||
for( ; ; ) // main task loop: every milisecond (RTOS time tick)
|
||||
{ vTaskDelay(1); // wait for the next time tick (but apparently it can wait more than one OS tick)
|
||||
TickType_t NewTick = xTaskGetTickCount();
|
||||
TickType_t Delta = NewTick-RefTick;
|
||||
RefTick = NewTick;
|
||||
/*
|
||||
#ifdef DEBUG_PRINT
|
||||
if(Delta>1)
|
||||
{ xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_Time(RefTick)%60);
|
||||
CONS_UART_Write('.');
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_msTime(RefTick),3);
|
||||
Format_String(CONS_UART_Write, " -> ");
|
||||
Format_UnsDec(CONS_UART_Write, Delta);
|
||||
Format_String(CONS_UART_Write, "t\n");
|
||||
xSemaphoreGive(CONS_Mutex); }
|
||||
#endif
|
||||
*/
|
||||
#ifdef WITH_GPS_PPS
|
||||
if(GPS_PPS_isOn()) { if(!PPS) { PPS=1; GPS_PPS_On(); } } // monitor GPS PPS signal
|
||||
else { if( PPS) { PPS=0; GPS_PPS_Off(); } } // and call handling calls
|
||||
#endif
|
||||
LineIdle+=Delta; // count idle time
|
||||
NoValidData+=Delta; // count time without any valid NMEA nor UBX packet
|
||||
uint16_t Bytes=0;
|
||||
uint16_t MaxBytesPerTick = 1+(GPS_getBaudRate()+2500)/5000;
|
||||
for( ; ; ) // loop over bytes in the GPS UART buffer
|
||||
{ uint8_t Byte; int Err=GPS_UART_Read(Byte); if(Err<=0) break; // get Byte from serial port, if no bytes then break this loop
|
||||
Bytes++;
|
||||
LineIdle=0; // if there was a byte: restart idle counting
|
||||
NMEA.ProcessByte(Byte); // process through the NMEA interpreter
|
||||
#ifdef WITH_GPS_UBX
|
||||
UBX.ProcessByte(Byte);
|
||||
#endif
|
||||
#ifdef WITH_MAVLINK
|
||||
MAV.ProcessByte(Byte);
|
||||
#endif
|
||||
if(NMEA.isComplete()) // NMEA completely received ?
|
||||
{ if(NMEA.isChecked()) { GPS_NMEA(); NoValidData=0; } // NMEA check sum is correct ?
|
||||
NMEA.Clear(); break; }
|
||||
#ifdef WITH_GPS_UBX
|
||||
if(UBX.isComplete()) { GPS_UBX(); NoValidData=0; UBX.Clear(); break; }
|
||||
#endif
|
||||
#ifdef WITH_MAVLINK
|
||||
if(MAV.isComplete()) { GPS_MAV(); NoValidData=0; MAV.Clear(); break; }
|
||||
#endif
|
||||
if(Bytes>=MaxBytesPerTick) break;
|
||||
}
|
||||
/*
|
||||
#ifdef DEBUG_PRINT
|
||||
if(Bytes)
|
||||
{ xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_Time(RefTick)%60);
|
||||
CONS_UART_Write('.');
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_msTime(RefTick),3);
|
||||
Format_String(CONS_UART_Write, "..");
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_Time()%60);
|
||||
CONS_UART_Write('.');
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_msTime(),3);
|
||||
Format_String(CONS_UART_Write, " -> ");
|
||||
Format_UnsDec(CONS_UART_Write, Bytes);
|
||||
Format_String(CONS_UART_Write, "B\n");
|
||||
xSemaphoreGive(CONS_Mutex); }
|
||||
#endif
|
||||
*/
|
||||
if(LineIdle==0) // if any bytes were received ?
|
||||
{ if(!GPS_Burst.Active) GPS_BurstStart(); // burst started
|
||||
GPS_Burst.Active=1;
|
||||
if( (!GPS_Burst.Complete) && (GPS_Burst.GxGGA && GPS_Burst.GxRMC && GPS_Burst.GxGSA) )
|
||||
{ GPS_Burst.Complete=1; GPS_BurstComplete(); }
|
||||
}
|
||||
else if(LineIdle>=GPS_BurstTimeout) // if GPS sends no more data for 10 time ticks
|
||||
{ if(GPS_Burst.Active) // if still in burst
|
||||
{ if(!GPS_Burst.Complete) GPS_BurstComplete();
|
||||
GPS_BurstEnd(); } // burst just ended
|
||||
else if(LineIdle>=1000) // if idle for more than 1 sec
|
||||
{ GPS_Status.Flags=0; }
|
||||
GPS_Burst.Flags=0;
|
||||
}
|
||||
|
||||
if(NoValidData>=1200) // if no valid data from GPS for 1sec
|
||||
{ GPS_Status.Flags=0; GPS_Burst.Flags=0; // assume GPS state is unknown
|
||||
uint32_t NewBaudRate = GPS_nextBaudRate(); // switch to the next baud rate
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, "TaskGPS: ");
|
||||
Format_UnsDec(CONS_UART_Write, NewBaudRate);
|
||||
Format_String(CONS_UART_Write, "bps\n");
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
GPS_UART_SetBaudrate(NewBaudRate);
|
||||
NoValidData=0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,50 @@
|
|||
|
||||
#ifdef __cplusplus
|
||||
|
||||
#include "hal.h"
|
||||
|
||||
#include "timesync.h"
|
||||
|
||||
#include "ogn.h"
|
||||
|
||||
#include "lowpass2.h"
|
||||
|
||||
extern uint32_t GPS_FatTime; // [2 sec] UTC time in FAT format (for FatFS)
|
||||
extern int32_t GPS_Altitude; // [0.1m] altitude (height above Geoid)
|
||||
extern int32_t GPS_Latitude; // [0.0001/60 deg]
|
||||
extern int32_t GPS_Longitude; // [0.0001/60 deg]
|
||||
extern int16_t GPS_GeoidSepar; // [0.1m]
|
||||
extern uint16_t GPS_LatCosine; // [1.0/(1<<12)] Latitude Cosine for distance calculations
|
||||
extern uint32_t GPS_TimeSinceLock; // [sec] time since GPS has a valid lock
|
||||
|
||||
typedef union
|
||||
{ uint8_t Flags;
|
||||
struct
|
||||
{ bool NMEA:1; // got at least one valid NMEA message
|
||||
bool UBX:1; // got at least one valid UBX message
|
||||
bool MAV:1; // got at least one valid MAV message
|
||||
bool PPS:1; // got at least one PPS signal
|
||||
bool BaudConfig:1; // baudrate is configured
|
||||
bool ModeConfig:1; // mode is configured
|
||||
bool :1; //
|
||||
bool :1; //
|
||||
} ;
|
||||
} Status;
|
||||
|
||||
extern Status GPS_Status;
|
||||
|
||||
uint32_t GPS_getBaudRate(void); // [bps]
|
||||
|
||||
GPS_Position *GPS_getPosition(void);
|
||||
GPS_Position *GPS_getPosition(int8_t Sec);
|
||||
|
||||
int16_t GPS_AverageSpeed(void); // [0.1m/s] calc. average speed based on most recent GPS positions
|
||||
|
||||
#endif // __cplusplus
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
#endif
|
||||
void vTaskGPS(void* pvParameters);
|
||||
|
|
@ -0,0 +1,436 @@
|
|||
#include <string.h>
|
||||
// #include <sys/select.h>
|
||||
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "freertos/semphr.h"
|
||||
#include "freertos/queue.h"
|
||||
|
||||
#include "driver/gpio.h"
|
||||
#include "driver/uart.h"
|
||||
#include "driver/spi_master.h"
|
||||
#include "driver/i2c.h"
|
||||
|
||||
#include "esp_system.h"
|
||||
#include "esp_freertos_hooks.h"
|
||||
|
||||
#include "nvs.h"
|
||||
#include "nvs_flash.h"
|
||||
|
||||
#include "esp_spiffs.h"
|
||||
|
||||
#include "esp_bt.h"
|
||||
#include "esp_bt_main.h"
|
||||
#include "esp_gap_bt_api.h"
|
||||
#include "esp_bt_device.h"
|
||||
#include "esp_spp_api.h"
|
||||
|
||||
#include "hal.h"
|
||||
|
||||
#ifdef WITH_OLED
|
||||
#include "ssd1306.h"
|
||||
#include "font8x8_basic.h"
|
||||
#endif
|
||||
|
||||
// ======================================================================================================
|
||||
/*
|
||||
The HELTEC Automation board WiFi LoRa 32 with sx1276 (RFM95) for 868/915MHz
|
||||
|
||||
Referenced: http://esp32.net/
|
||||
Pinout: http://esp32.net/images/Heltec/WIFI-LoRa-32/Heltec_WIFI-LoRa-32_DiagramPinoutFromTop.jpg
|
||||
http://esp32.net/images/Heltec/WIFI-LoRa-32/Heltec_WIFI-LoRa-32_DiagramPinoutFromBottom.jpg
|
||||
Arduino code: https://robotzero.one/heltec-wifi-lora-32/
|
||||
ESP32 API: https://esp-idf.readthedocs.io/en/latest/api-reference/index.html
|
||||
UART example: https://github.com/espressif/esp-idf/blob/f4009b94dca9d17b909e1094d6e3d7dbb75d52c0/examples/peripherals/uart_echo
|
||||
SPI example: https://github.com/espressif/esp-idf/tree/f4009b94dca9d17b909e1094d6e3d7dbb75d52c0/examples/peripherals/spi_master
|
||||
I2C example: https://github.com/espressif/esp-idf/tree/f4009b94dca9d17b909e1094d6e3d7dbb75d52c0/examples/peripherals/i2c
|
||||
OLED driver: https://github.com/olikraus/u8g2/tree/master/csrc
|
||||
OLED datasheet: https://cdn-shop.adafruit.com/datasheets/SSD1306.pdf
|
||||
OLED example: https://github.com/yanbe/ssd1306-esp-idf-i2c
|
||||
OLED article: http://robotcantalk.blogspot.co.uk/2015/03/interfacing-arduino-with-ssd1306-driven.html
|
||||
|
||||
SX1276 pins:
|
||||
14 = GPIO14 = RST
|
||||
5 = GPIO5 = SCK
|
||||
18 = GPIO18 = CS = SS
|
||||
19 = GPIO19 = MISO
|
||||
27 = GPIO27 = MOSI
|
||||
26 = GPIO26 = IRQ = DIO0
|
||||
|
||||
OLED type: U8X8_SSD1306_128X64_NONAME_SW_I2C u8x8 (by Arduino)
|
||||
OLED pins:
|
||||
16 = GPIO16 = RST
|
||||
4 = GPIO04 = SDA
|
||||
15 = GPIO15 = SCL
|
||||
|
||||
LED pin:
|
||||
25 = GPIO25
|
||||
|
||||
Button pin:
|
||||
0 = GPIO0
|
||||
|
||||
UART0 pins: taken by console ?
|
||||
1 = GPIO1 = TxD CPU->GPS
|
||||
3 = GPIO3 = RxD GPS->CPU
|
||||
|
||||
GPS pins:
|
||||
22 = GPIO22 = PPS
|
||||
23 = GPIO23 = ENA
|
||||
|
||||
|
||||
UART2 pins:
|
||||
16 = GPIO16 = RxD -> taken by OLED ?
|
||||
17 = GPIO17 = TxD
|
||||
|
||||
*/
|
||||
|
||||
#define PIN_LED_PCB GPIO_NUM_25 // status LED on the PCB
|
||||
|
||||
#define PIN_RFM_RST GPIO_NUM_14 // Reset
|
||||
#define PIN_RFM_IRQ GPIO_NUM_26 // packet done on receive or transmit
|
||||
#define PIN_RFM_SS GPIO_NUM_18 // SPI chip-select
|
||||
#define PIN_RFM_SCK GPIO_NUM_5 // SPI clock
|
||||
#define PIN_RFM_MISO GPIO_NUM_19 // SPI MISO
|
||||
#define PIN_RFM_MOSI GPIO_NUM_27 // SPI MOSI
|
||||
|
||||
// wire colours for VK2828U GPS
|
||||
#define PIN_GPS_TXD GPIO_NUM_12 // green
|
||||
#define PIN_GPS_RXD GPIO_NUM_35 // blue
|
||||
#define PIN_GPS_PPS GPIO_NUM_34 // white
|
||||
#define PIN_GPS_ENA GPIO_NUM_13 // yellow -> well, I had a problem here, thus I tied the enable wire to 3.3V for the time being.
|
||||
|
||||
#define CONS_UART UART_NUM_0 // UART0 for the console (the system does this for us)
|
||||
#define GPS_UART UART_NUM_1 // UART1 for GPS data read and dialog
|
||||
|
||||
#define I2C_BUS I2C_NUM_1 // use bus #1 to talk to OLED and Baro sensor
|
||||
#define I2C_SPEED 1000000 // 1MHz clock on I2C
|
||||
#define PIN_I2C_SCL GPIO_NUM_15 // SCL pin
|
||||
#define PIN_I2C_SDA GPIO_NUM_4 // SDA pin
|
||||
|
||||
#define OLED_I2C_ADDR 0x3C // I2C address of the OLED display
|
||||
#define PIN_OLED_RST GPIO_NUM_16 // OLED RESET pin
|
||||
|
||||
// ======================================================================================================
|
||||
// 48-bit unique ID of the chip
|
||||
|
||||
uint64_t getUniqueID(void)
|
||||
{ uint64_t ID=0; esp_err_t ret=esp_efuse_mac_get_default((uint8_t *)&ID); return ID; }
|
||||
|
||||
// ======================================================================================================
|
||||
|
||||
FlashParameters Parameters;
|
||||
|
||||
//--------------------------------------------------------------------------------------------------------
|
||||
// STatus LED
|
||||
|
||||
void LED_PCB_On (void) { gpio_set_level(PIN_LED_PCB, 1); } // LED is on GPIO25
|
||||
void LED_PCB_Off (void) { gpio_set_level(PIN_LED_PCB, 0); }
|
||||
|
||||
//--------------------------------------------------------------------------------------------------------
|
||||
// Console UART
|
||||
|
||||
SemaphoreHandle_t CONS_Mutex;
|
||||
|
||||
// int CONS_UART_Read (uint8_t &Byte) { return uart_read_bytes (CONS_UART, &Byte, 1, 0); } // non-blocking
|
||||
// void CONS_UART_Write (char Byte) { uart_write_bytes (CONS_UART, &Byte, 1); } // blocking ?
|
||||
void CONS_UART_Write (char Byte) { putchar(Byte); }
|
||||
int CONS_UART_Read (uint8_t &Byte) { int Ret=getchar(); if(Ret>=0) { Byte=Ret; return 1; } else return Ret; }
|
||||
// int CONS_UART_Free (void) { return UART2_Free(); }
|
||||
// int CONS_UART_Full (void) { return UART2_Full(); }
|
||||
|
||||
//--------------------------------------------------------------------------------------------------------
|
||||
// GPS UART
|
||||
|
||||
// int GPS_UART_Full (void) { size_t Full=0; uart_get_buffered_data_len(GPS_UART, &Full); return Full; }
|
||||
int GPS_UART_Read (uint8_t &Byte) { return uart_read_bytes (GPS_UART, &Byte, 1, 0); } // should be buffered and non-blocking
|
||||
void GPS_UART_Write (char Byte) { uart_write_bytes (GPS_UART, &Byte, 1); } // should be buffered and blocking
|
||||
void GPS_UART_SetBaudrate(int BaudRate) { uart_set_baudrate(GPS_UART, BaudRate); }
|
||||
|
||||
#ifdef WITH_GPS_ENABLE
|
||||
void GPS_DISABLE(void) { gpio_set_level(PIN_GPS_ENA, 0); }
|
||||
void GPS_ENABLE (void) { gpio_set_level(PIN_GPS_ENA, 1); }
|
||||
#endif
|
||||
bool GPS_PPS_isOn(void) { return gpio_get_level(PIN_GPS_PPS); }
|
||||
|
||||
//--------------------------------------------------------------------------------------------------------
|
||||
// RF chip
|
||||
|
||||
inline void RFM_RESET_High(void) { gpio_set_level(PIN_RFM_RST, 1); }
|
||||
inline void RFM_RESET_Low (void) { gpio_set_level(PIN_RFM_RST, 0); }
|
||||
|
||||
void RFM_RESET(uint8_t On)
|
||||
{ if(On) RFM_RESET_Low();
|
||||
else RFM_RESET_High(); }
|
||||
|
||||
bool RFM_DIO0_isOn(void) { return gpio_get_level(PIN_RFM_IRQ); }
|
||||
|
||||
static spi_device_handle_t RFM_SPI;
|
||||
|
||||
void RFM_TransferBlock(uint8_t *Data, uint8_t Len)
|
||||
{ spi_transaction_t Trans;
|
||||
memset(&Trans, 0, sizeof(Trans));
|
||||
Trans.tx_buffer = Data;
|
||||
Trans.rx_buffer = Data;
|
||||
Trans.length = 8*Len;
|
||||
esp_err_t ret = spi_device_transmit(RFM_SPI, &Trans); }
|
||||
|
||||
//--------------------------------------------------------------------------------------------------------
|
||||
// OLED display
|
||||
|
||||
#ifdef WITH_OLED
|
||||
void OLED_RESET(bool Level) { gpio_set_level(PIN_OLED_RST, Level); }
|
||||
|
||||
esp_err_t OLED_Init(void)
|
||||
{ i2c_cmd_handle_t cmd = i2c_cmd_link_create();
|
||||
i2c_master_start(cmd);
|
||||
i2c_master_write_byte(cmd, (OLED_I2C_ADDR << 1) | I2C_MASTER_WRITE, true);
|
||||
i2c_master_write_byte(cmd, OLED_CONTROL_BYTE_CMD_STREAM, true);
|
||||
i2c_master_write_byte(cmd, OLED_CMD_SET_CHARGE_PUMP, true);
|
||||
i2c_master_write_byte(cmd, 0x14, true);
|
||||
i2c_master_write_byte(cmd, OLED_CMD_SET_SEGMENT_REMAP, true); // reverse left-right mapping
|
||||
i2c_master_write_byte(cmd, OLED_CMD_SET_COM_SCAN_MODE, true); // reverse up-bottom mapping
|
||||
i2c_master_write_byte(cmd, OLED_CMD_DISPLAY_ON, true);
|
||||
i2c_master_stop(cmd);
|
||||
esp_err_t espRc = i2c_master_cmd_begin(I2C_BUS, cmd, 10);
|
||||
i2c_cmd_link_delete(cmd);
|
||||
return espRc; }
|
||||
|
||||
esp_err_t OLED_SetContrast(uint8_t Contrast)
|
||||
{ i2c_cmd_handle_t cmd = i2c_cmd_link_create();
|
||||
i2c_master_start(cmd);
|
||||
i2c_master_write_byte(cmd, (OLED_I2C_ADDR << 1) | I2C_MASTER_WRITE, true);
|
||||
i2c_master_write_byte(cmd, OLED_CONTROL_BYTE_CMD_STREAM, true);
|
||||
i2c_master_write_byte(cmd, OLED_CMD_SET_CONTRAST, true);
|
||||
i2c_master_write_byte(cmd, Contrast, true);
|
||||
i2c_master_stop(cmd);
|
||||
esp_err_t espRc = i2c_master_cmd_begin(I2C_BUS, cmd, 10);
|
||||
i2c_cmd_link_delete(cmd);
|
||||
return espRc; }
|
||||
|
||||
esp_err_t OLED_PutLine(uint8_t Line, const char *Text)
|
||||
{ if(Line>=8) return ESP_OK;
|
||||
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
|
||||
i2c_master_start(cmd);
|
||||
i2c_master_write_byte(cmd, (OLED_I2C_ADDR << 1) | I2C_MASTER_WRITE, true);
|
||||
i2c_master_write_byte(cmd, OLED_CONTROL_BYTE_CMD_STREAM, true);
|
||||
i2c_master_write_byte(cmd, 0x00, true);
|
||||
i2c_master_write_byte(cmd, 0x10, true);
|
||||
i2c_master_write_byte(cmd, 0xB0 | Line, true);
|
||||
i2c_master_stop(cmd);
|
||||
esp_err_t espRc = i2c_master_cmd_begin(I2C_BUS, cmd, 10);
|
||||
i2c_cmd_link_delete(cmd);
|
||||
if(espRc!=ESP_OK) return espRc;
|
||||
|
||||
for(uint8_t Idx=0; Idx<16; Idx++)
|
||||
{ char Char=0;
|
||||
if(Text)
|
||||
{ Char=Text[Idx];
|
||||
if(Char==0) Text=0;
|
||||
else Char&=0x7F; }
|
||||
cmd = i2c_cmd_link_create();
|
||||
i2c_master_start(cmd);
|
||||
i2c_master_write_byte(cmd, (OLED_I2C_ADDR << 1) | I2C_MASTER_WRITE, true);
|
||||
i2c_master_write_byte(cmd, OLED_CONTROL_BYTE_DATA_STREAM, true);
|
||||
i2c_master_write(cmd, font8x8_basic_tr[(uint8_t)Char], 8, true);
|
||||
i2c_master_stop(cmd);
|
||||
espRc = i2c_master_cmd_begin(I2C_BUS, cmd, 10);
|
||||
i2c_cmd_link_delete(cmd);
|
||||
if(espRc!=ESP_OK) break; }
|
||||
return espRc; }
|
||||
|
||||
esp_err_t OLED_Clear(void)
|
||||
{ esp_err_t espRc;
|
||||
for(uint8_t Line=0; Line<8; Line++)
|
||||
{ espRc=OLED_PutLine(Line, 0); if(espRc!=ESP_OK) break; }
|
||||
return espRc; }
|
||||
#endif
|
||||
|
||||
//--------------------------------------------------------------------------------------------------------
|
||||
|
||||
volatile uint8_t LED_PCB_Counter = 0;
|
||||
|
||||
void LED_PCB_Flash(uint8_t Time) { if(Time>LED_PCB_Counter) LED_PCB_Counter=Time; } // [ms]
|
||||
|
||||
void LED_TimerCheck(uint8_t Ticks)
|
||||
{ uint8_t Counter=LED_PCB_Counter;
|
||||
if(Counter)
|
||||
{ if(Ticks<Counter) Counter-=Ticks;
|
||||
else Counter =0;
|
||||
if(Counter) LED_PCB_On();
|
||||
else LED_PCB_Off();
|
||||
LED_PCB_Counter=Counter; }
|
||||
}
|
||||
|
||||
/*
|
||||
extern "C"
|
||||
void vApplicationIdleHook(void) // when RTOS is idle: should call "sleep until an interrupt"
|
||||
{ // __WFI(); // wait-for-interrupt
|
||||
}
|
||||
|
||||
extern "C"
|
||||
void vApplicationTickHook(void) // RTOS timer tick hook
|
||||
{ LED_TimerCheck();
|
||||
}
|
||||
*/
|
||||
|
||||
//--------------------------------------------------------------------------------------------------------
|
||||
|
||||
void IO_Configuration(void)
|
||||
{
|
||||
CONS_Mutex = xSemaphoreCreateMutex();
|
||||
|
||||
gpio_set_direction(PIN_LED_PCB, GPIO_MODE_OUTPUT); // LED
|
||||
LED_PCB_Off();
|
||||
|
||||
gpio_set_direction(PIN_RFM_RST, GPIO_MODE_OUTPUT); // RF chip GPIO pins
|
||||
gpio_set_direction(PIN_RFM_IRQ, GPIO_MODE_INPUT);
|
||||
RFM_RESET(0);
|
||||
|
||||
spi_bus_config_t BusCfg = // RF chip SPI
|
||||
{ mosi_io_num: PIN_RFM_MOSI,
|
||||
miso_io_num: PIN_RFM_MISO,
|
||||
sclk_io_num: PIN_RFM_SCK,
|
||||
quadwp_io_num: -1,
|
||||
quadhd_io_num: -1,
|
||||
max_transfer_sz: 64
|
||||
};
|
||||
spi_device_interface_config_t DevCfg =
|
||||
{ command_bits: 0,
|
||||
address_bits: 0,
|
||||
dummy_bits: 0,
|
||||
mode: 0,
|
||||
duty_cycle_pos: 0,
|
||||
cs_ena_pretrans: 0,
|
||||
cs_ena_posttrans: 0,
|
||||
clock_speed_hz: 4000000,
|
||||
spics_io_num: PIN_RFM_SS,
|
||||
flags: 0,
|
||||
queue_size: 3,
|
||||
pre_cb: 0,
|
||||
post_cb: 0
|
||||
};
|
||||
esp_err_t ret=spi_bus_initialize(HSPI_HOST, &BusCfg, 1);
|
||||
ret=spi_bus_add_device(HSPI_HOST, &DevCfg, &RFM_SPI);
|
||||
|
||||
gpio_set_direction(PIN_GPS_PPS, GPIO_MODE_INPUT);
|
||||
#ifdef WITH_GPS_ENABLE
|
||||
gpio_set_direction(PIN_GPS_ENA, GPIO_MODE_OUTPUT); // GPS GPIO
|
||||
GPS_ENABLE();
|
||||
#endif
|
||||
|
||||
uart_config_t GPS_UART_Config = // GPS UART
|
||||
{ baud_rate: 9600,
|
||||
data_bits: UART_DATA_8_BITS,
|
||||
parity: UART_PARITY_DISABLE,
|
||||
stop_bits: UART_STOP_BITS_1,
|
||||
flow_ctrl: UART_HW_FLOWCTRL_DISABLE,
|
||||
rx_flow_ctrl_thresh: 0,
|
||||
use_ref_tick: 0
|
||||
};
|
||||
uart_param_config (GPS_UART, &GPS_UART_Config);
|
||||
uart_set_pin (GPS_UART, PIN_GPS_TXD, PIN_GPS_RXD, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
|
||||
uart_driver_install(GPS_UART, 256, 256, 0, 0, 0);
|
||||
|
||||
gpio_set_direction(PIN_OLED_RST, GPIO_MODE_OUTPUT);
|
||||
|
||||
i2c_config_t I2C_Config = // I2C for OLED and pressue sensor
|
||||
{ mode: I2C_MODE_MASTER,
|
||||
sda_io_num: PIN_I2C_SDA,
|
||||
sda_pullup_en: GPIO_PULLUP_ENABLE,
|
||||
scl_io_num: PIN_I2C_SCL,
|
||||
scl_pullup_en: GPIO_PULLUP_ENABLE
|
||||
} ;
|
||||
I2C_Config.master.clk_speed = I2C_SPEED;
|
||||
i2c_param_config (I2C_BUS, &I2C_Config);
|
||||
i2c_driver_install(I2C_BUS, I2C_Config.mode, 0, 0, 0);
|
||||
|
||||
#ifdef WITH_OLED
|
||||
OLED_RESET(0);
|
||||
vTaskDelay(10);
|
||||
OLED_RESET(1);
|
||||
vTaskDelay(10);
|
||||
|
||||
OLED_Init();
|
||||
OLED_Clear();
|
||||
OLED_SetContrast(128);
|
||||
#endif
|
||||
|
||||
// esp_register_freertos_tick_hook(&vApplicationTickHook);
|
||||
}
|
||||
|
||||
// ======================================================================================================
|
||||
|
||||
static const esp_spp_mode_t esp_spp_mode = ESP_SPP_MODE_CB;
|
||||
|
||||
static void esp_spp_cb(esp_spp_cb_event_t event, esp_spp_cb_param_t *param)
|
||||
{ xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, "BT_SPP: ");
|
||||
Format_Hex(CONS_UART_Write, (uint32_t)event);
|
||||
Format_String(CONS_UART_Write, "\n");
|
||||
xSemaphoreGive(CONS_Mutex); }
|
||||
|
||||
int BT_SPP_Init(void)
|
||||
{ esp_bt_controller_config_t BTconf = BT_CONTROLLER_INIT_CONFIG_DEFAULT();
|
||||
esp_err_t Err = esp_bt_controller_init(&BTconf); if(Err!=ESP_OK) return Err;
|
||||
Err = esp_bt_controller_enable(ESP_BT_MODE_CLASSIC_BT); if(Err!=ESP_OK) return Err;
|
||||
Err = esp_bluedroid_init(); if(Err!=ESP_OK) return Err;
|
||||
Err = esp_bluedroid_enable(); if(Err!=ESP_OK) return Err;
|
||||
Err = esp_spp_register_callback(esp_spp_cb); if(Err!=ESP_OK) return Err;
|
||||
Err = esp_spp_init(esp_spp_mode); if(Err!=ESP_OK) return Err;
|
||||
return Err; }
|
||||
|
||||
// ======================================================================================================
|
||||
|
||||
int NVS_Init(void)
|
||||
{ esp_err_t Err = nvs_flash_init();
|
||||
if (Err == ESP_ERR_NVS_NO_FREE_PAGES)
|
||||
{ nvs_flash_erase();
|
||||
Err = nvs_flash_init(); }
|
||||
|
||||
if(Parameters.ReadFromNVS()!=ESP_OK)
|
||||
{ Parameters.setDefault(getUniqueID());
|
||||
Parameters.WriteToNVS(); }
|
||||
|
||||
return Err; }
|
||||
|
||||
// ======================================================================================================
|
||||
|
||||
int SPIFFS_Register(const char *Path, const char *Label, size_t MaxOpenFiles)
|
||||
{ esp_vfs_spiffs_conf_t FSconf =
|
||||
{ base_path: Path,
|
||||
partition_label: Label,
|
||||
max_files: MaxOpenFiles,
|
||||
format_if_mount_failed: true };
|
||||
return esp_vfs_spiffs_register(&FSconf); }
|
||||
|
||||
int SPIFFS_Info(size_t &Total, size_t &Used, const char *Label)
|
||||
{ return esp_spiffs_info(Label, &Total, &Used); }
|
||||
|
||||
// ======================================================================================================
|
||||
/*
|
||||
uint8_t I2C_Read(i2c_port_t Bus, uint8_t Addr, uint8_t Reg, uint8_t *Data, uint8_t Len, uint8_t Wait=10)
|
||||
{ i2c_cmd_handle_t Cmd = i2c_cmd_link_create();
|
||||
i2c_master_start(Cmd);
|
||||
i2c_master_write_byte(Cmd, (Addr<<1) | I2C_MASTER_READ , I2C_MASTER_ACK);
|
||||
i2c_master_write_byte(Cmd, Reg , I2C_MASTER_ACK);
|
||||
i2c_master_start(Cmd);
|
||||
i2c_master_read(Cmd, Data, Len, I2C_MASTER_LAST_NACK);
|
||||
i2c_master_stop(Cmd);
|
||||
esp_err_t Ret = i2c_master_cmd_begin(Bus, Cmd, Wait);
|
||||
i2c_cmd_link_delete(Cmd);
|
||||
return Ret; }
|
||||
|
||||
|
||||
uint8_t I2C_Write(i2c_port_t Bus, uint8_t Addr, uint8_t Reg, uint8_t *Data, uint8_t Len, uint8_t Wait=10)
|
||||
{ i2c_cmd_handle_t Cmd = i2c_cmd_link_create();
|
||||
i2c_master_start(Cmd);
|
||||
i2c_master_write_byte(Cmd, (Addr<<1) | I2C_MASTER_WRITE , I2C_MASTER_ACK);
|
||||
i2c_master_write_byte(Cmd, Reg , I2C_MASTER_ACK);
|
||||
i2c_master_write(Cmd, Data, Len, I2C_MASTER_NACK);
|
||||
i2c_master_stop(Cmd);
|
||||
esp_err_t Ret = i2c_master_cmd_begin(Bus, Cmd, Wait);
|
||||
i2c_cmd_link_delete(Cmd);
|
||||
return Ret; }
|
||||
*/
|
||||
// ======================================================================================================
|
||||
|
|
@ -0,0 +1,72 @@
|
|||
#ifndef __HAL_H__
|
||||
#define __HAL_H__
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/semphr.h"
|
||||
#include "freertos/task.h"
|
||||
#include "freertos/queue.h"
|
||||
|
||||
#define HARDWARE_ID 0x02
|
||||
#define SOFTWARE_ID 0x01
|
||||
|
||||
#define USE_BLOCK_SPI // use block SPI interface for RF chip
|
||||
|
||||
#define WITH_RFM95 // RF chip selection
|
||||
// #define WITH_RFM69
|
||||
|
||||
// #define WITH_GPS_ENABLE // use GPS_ENABLE control line to turn the GPS ON/OFF
|
||||
#define WITH_GPS_PPS // use the PPS signal from GPS for precise time-sync.
|
||||
#define WITH_GPS_CONFIG // attempt to configure higher GPS baud rate and airborne mode
|
||||
#define WITH_GPS_UBX // GPS understands UBX
|
||||
// #define WITH_GPS_MTK // GPS understands MTK
|
||||
// #define WITH_GPS_SRF
|
||||
|
||||
#define WITH_PFLAA
|
||||
#define WITH_CONFIG // interpret the console input: $POGNS to change parameters
|
||||
#define WITH_OLED // OLED display on the I2C
|
||||
|
||||
extern SemaphoreHandle_t CONS_Mutex; // console port Mutex
|
||||
|
||||
#include "parameters.h"
|
||||
extern FlashParameters Parameters;
|
||||
|
||||
uint64_t getUniqueID(void); // get some unique ID of the CPU/chip
|
||||
|
||||
int CONS_UART_Read (uint8_t &Byte); // non-blocking
|
||||
void CONS_UART_Write (char Byte); // blocking
|
||||
int CONS_UART_Free (void); // how many bytes can be written to the transmit buffer
|
||||
int CONS_UART_Full (void); // how many bytes already in the transmit buffer
|
||||
void CONS_UART_SetBaudrate(int BaudRate);
|
||||
|
||||
int GPS_UART_Read (uint8_t &Byte); // non-blocking
|
||||
void GPS_UART_Write (char Byte); // blocking
|
||||
void GPS_UART_SetBaudrate(int BaudRate);
|
||||
|
||||
bool GPS_PPS_isOn(void);
|
||||
|
||||
void RFM_TransferBlock(uint8_t *Data, uint8_t Len);
|
||||
void RFM_RESET(uint8_t On); // RF module reset
|
||||
bool RFM_DIO0_isOn(void); // query the IRQ state
|
||||
|
||||
#ifdef WITH_OLED
|
||||
int OLED_SetContrast(uint8_t Contrast);
|
||||
int OLED_PutLine(uint8_t Line, const char *Text);
|
||||
#endif
|
||||
|
||||
void LED_PCB_On (void); // LED on the PCB for vizual indications
|
||||
void LED_PCB_Off (void);
|
||||
|
||||
void LED_PCB_Flash(uint8_t Time=100); // Flash the PCB LED for a period of [ms]
|
||||
void LED_TimerCheck(uint8_t Ticks=1);
|
||||
|
||||
void IO_Configuration(void); // Configure I/O
|
||||
|
||||
int NVS_Init(void); // initialize non-volatile-storage in the Flash
|
||||
|
||||
int BT_SPP_Init(void);
|
||||
int SPIFFS_Register(const char *Path="/spiffs", const char *Label=0, size_t MaxOpenFiles=5);
|
||||
int SPIFFS_Info(size_t &Total, size_t &Used, const char *Label=0);
|
||||
|
||||
#endif // __HAL_H__
|
|
@ -0,0 +1,157 @@
|
|||
#include "intmath.h"
|
||||
|
||||
static const uint32_t SinePoints=256;
|
||||
// static const uint32_t SineScale=0x80000000;
|
||||
static const int32_t SineTable[SinePoints/4+1] =
|
||||
{ 0x00000000, 0x03242ABF, 0x0647D97C, 0x096A9049, 0x0C8BD35E, 0x0FAB272B, 0x12C8106F, 0x15E21445,
|
||||
0x18F8B83C, 0x1C0B826A, 0x1F19F97B, 0x2223A4C5, 0x25280C5E, 0x2826B928, 0x2B1F34EB, 0x2E110A62,
|
||||
0x30FBC54D, 0x33DEF287, 0x36BA2014, 0x398CDD32, 0x3C56BA70, 0x3F1749B8, 0x41CE1E65, 0x447ACD50,
|
||||
0x471CECE7, 0x49B41533, 0x4C3FDFF4, 0x4EBFE8A5, 0x5133CC94, 0x539B2AF0, 0x55F5A4D2, 0x5842DD54,
|
||||
0x5A82799A, 0x5CB420E0, 0x5ED77C8A, 0x60EC3830, 0x62F201AC, 0x64E88926, 0x66CF8120, 0x68A69E81,
|
||||
0x6A6D98A4, 0x6C242960, 0x6DCA0D14, 0x6F5F02B2, 0x70E2CBC6, 0x72552C85, 0x73B5EBD1, 0x7504D345,
|
||||
0x7641AF3D, 0x776C4EDB, 0x78848414, 0x798A23B1, 0x7A7D055B, 0x7B5D039E, 0x7C29FBEE, 0x7CE3CEB2,
|
||||
0x7D8A5F40, 0x7E1D93EA, 0x7E9D55FC, 0x7F0991C4, 0x7F62368F, 0x7FA736B4, 0x7FD8878E, 0x7FF62182,
|
||||
0x7FFFFFFF } ;
|
||||
|
||||
// get Sine from the SineTable
|
||||
// Angle is 0..255 which corresponds to <0..2*PI)
|
||||
int32_t IntSine(uint8_t Angle)
|
||||
{ uint8_t Idx=Angle;
|
||||
if(Angle&0x80) { Angle^=0x40; Idx=(-Idx); }
|
||||
if(Angle&0x40) Idx=0x80-Idx;
|
||||
int32_t Val=SineTable[Idx];
|
||||
if(Angle&0x80) Val=(-Val);
|
||||
return Val; }
|
||||
|
||||
// precise Sine with for 16-bit angles 2nd derivative interpolation
|
||||
// max. result error is about 2.3e-7
|
||||
int32_t IntSine(uint16_t Angle)
|
||||
{ uint8_t Int = Angle>>8;
|
||||
int32_t Frac = Angle&0x00FF;
|
||||
int32_t Value = IntSine(Int); Int+=1;
|
||||
int32_t Delta = (IntSine(Int)-Value)>>8;
|
||||
Value += Frac*Delta;
|
||||
// printf(" [%02X %02X %+11.8f] ", Int-1, Frac, (double)Value/(uint32_t)0x80000000);
|
||||
int32_t Frac2 = (Frac*(Frac-0x100));
|
||||
const int32_t Coeff = (int32_t)floor(2*M_PI*M_PI*0x80+0.5);
|
||||
int32_t Deriv2 = (Coeff*(Value>>12));
|
||||
int32_t Corr = ((Deriv2>>16)*Frac2)>>11;
|
||||
Value -= Corr;
|
||||
// printf("[%04X %+11.8f %+11.8f] ", -Frac2, (double)Deriv2/(uint32_t)0x80000000, (double)Corr/(uint32_t)0x80000000);
|
||||
return Value; }
|
||||
|
||||
// precise Sine for 32-bit angles with 2nd derivative interpolation
|
||||
// max. result error is about 2.3e-7
|
||||
int32_t IntSine(uint32_t Angle)
|
||||
{ uint8_t Int = Angle>>24;
|
||||
int32_t Frac = Angle&0x00FFFFFF;
|
||||
int32_t Value = IntSine(Int); Int+=1;
|
||||
int32_t Delta = (IntSine(Int)-Value);
|
||||
Value += ((int64_t)Frac*(int64_t)Delta)>>24;
|
||||
// printf(" [%02X %06X %+11.8f] ", Int-1, Frac, (double)Value/(uint32_t)0x80000000);
|
||||
int64_t Frac2 = ((int64_t)Frac*(Frac-0x1000000))>>32;
|
||||
const int64_t Coeff = (int64_t)floor(2*M_PI*M_PI*0x4000000+0.5);
|
||||
int64_t Deriv2 = (Coeff*Value)>>26;
|
||||
int64_t Corr = (Deriv2*Frac2)>>32;
|
||||
Value -= Corr;
|
||||
// printf(" [%04X %+11.8f %+11.8f] ", -Frac2, (double)Deriv2/(uint32_t)0x80000000, (double)Corr/(uint32_t)0x80000000);
|
||||
return Value; }
|
||||
|
||||
// Less precise sine for 16-bit angles
|
||||
// source: http://www.coranac.com/2009/07/sines/
|
||||
/// A sine approximation via a fourth-order cosine approx.
|
||||
/// @param x angle (with 2^16 units/circle)
|
||||
/// @return Sine value (Q12)
|
||||
int16_t Isin(int16_t Angle) // input: full angle = 16-bit range
|
||||
{
|
||||
int32_t x=Angle;
|
||||
int32_t c, y;
|
||||
static const int qN= 14, qA= 12, B=19900, C=3516;
|
||||
|
||||
c= x<<(30-qN); // Semi-circle info into carry.
|
||||
x -= 1<<qN; // sine -> cosine calc
|
||||
|
||||
x= x<<(31-qN); // Mask with PI
|
||||
x= x>>(31-qN); // Note: SIGNED shift! (to qN)
|
||||
x= (x*x)>>(2*qN-14); // x=x^2 To Q14
|
||||
|
||||
y= B - ((x*C)>>14); // B - x^2*C
|
||||
y= (1<<qA)-((x*y)>>16); // A - x^2*(B-x^2*C)
|
||||
|
||||
return c>=0 ? y : -y; } // result: -4096..+4096 (max. error = +/-12)
|
||||
|
||||
|
||||
/*
|
||||
int16_t IntAtan2(int16_t Y, int16_t X)
|
||||
{ uint16_t Angle=0; // printf(" [%+5d,%+5d] %04X\n", X, Y, Angle);
|
||||
if(Y<0) { Angle+=0x8000; X=(-X); Y=(-Y); } // printf(" [%+5d,%+5d] %04X\n", X, Y, Angle);
|
||||
if(X<0) { Angle+=0x4000; int16_t tmp=Y; Y=(-X); X=tmp; } // printf(" [%+5d,%+5d] %04X\n", X, Y, Angle);
|
||||
if(X<Y) { Angle+=0x4000; int16_t tmp=Y; Y=(-X); X=tmp; } // printf(" [%+5d,%+5d] %04X\n", X, Y, Angle);
|
||||
if(X==0) return 0;
|
||||
int16_t D = (((int32_t)Y<<14) + (X>>1))/ X;
|
||||
int16_t DD = ((int32_t)D*(int32_t)D)>>14;
|
||||
int16_t DDD = ((int32_t)DD*(int32_t)D)>>14;
|
||||
// printf(" %08X %08X %08X\n", D, DD, DDD);
|
||||
Angle += ((5*D)>>3) - (DDD>>3); return Angle; } // good to about 1/2 degree
|
||||
*/
|
||||
|
||||
int16_t IntAtan2(int16_t Y, int16_t X)
|
||||
{ uint16_t Angle=0; // printf(" [%+5d,%+5d] %04X\n", X, Y, Angle);
|
||||
const int32_t CosPi8 = 30274; // cos(PI/8)*32768
|
||||
const int32_t SinPi8 = 12540; // sin(PI/8)*32768
|
||||
if(Y<0) { Angle+=0x8000; X=(-X); Y=(-Y); } // printf(" [%+5d,%+5d] %04X\n", X, Y, Angle);
|
||||
if(X<0) { Angle+=0x4000; int16_t tmp=Y; Y=(-X); X=tmp; } // printf(" [%+5d,%+5d] %04X\n", X, Y, Angle);
|
||||
if(X<Y) { Angle+=0x4000; int16_t tmp=Y; Y=(-X); X=tmp; } // printf(" [%+5d,%+5d] %04X\n", X, Y, Angle);
|
||||
if(X==0) return 0;
|
||||
int16_t Yc = (Y<<1)+(Y>>1);
|
||||
if(Y<0)
|
||||
{ if(X<(-Yc))
|
||||
{ int32_t NewX = CosPi8*X - SinPi8*Y;
|
||||
int32_t NewY = SinPi8*X + CosPi8*Y;
|
||||
X=NewX>>15; if(NewX&0x4000) X+=1;
|
||||
Y=NewY>>15; if(NewY&0x4000) Y+=1;
|
||||
Angle-=0x1000; }
|
||||
} else // Y>=0
|
||||
{ if(X<Yc)
|
||||
{ int32_t NewX = CosPi8*X + SinPi8*Y;
|
||||
int32_t NewY = - SinPi8*X + CosPi8*Y;
|
||||
X=NewX>>15; if(NewX&0x4000) X+=1;
|
||||
Y=NewY>>15; if(NewY&0x4000) Y+=1;
|
||||
Angle+=0x1000; }
|
||||
} // printf(" [%+5d,%+5d] %04X\n", X, Y, Angle);
|
||||
int16_t D = (((int32_t)Y<<14) + (X>>1))/ X;
|
||||
// int16_t D = ((int32_t)Y<<14) / X;
|
||||
int16_t DD = ((int32_t)D*(int32_t)D)>>14;
|
||||
int16_t DDD = ((int32_t)DD*(int32_t)D)>>14;
|
||||
// printf(" %08X %08X %08X\n", D, DD, DDD);
|
||||
Angle += ((5*D)>>3) - (DDD>>3);
|
||||
return Angle; } // good to about 1/6 degree
|
||||
|
||||
/*
|
||||
// integer square root
|
||||
uint32_t IntSqrt(uint32_t Inp)
|
||||
{ uint32_t Out = 0;
|
||||
uint32_t Mask = 0x40000000;
|
||||
|
||||
while(Mask>Inp) Mask>>=2;
|
||||
while(Mask)
|
||||
{ if(Inp >= (Out+Mask))
|
||||
{ Inp -= Out+Mask; Out += Mask<<1; }
|
||||
Out>>=1; Mask>>=2; }
|
||||
if(Inp>Out) Out++;
|
||||
|
||||
return Out; }
|
||||
|
||||
uint64_t IntSqrt(uint64_t Inp)
|
||||
{ uint64_t Out = 0;
|
||||
uint64_t Mask = 0x4000000000000000;
|
||||
|
||||
while(Mask>Inp) Mask>>=2;
|
||||
while(Mask)
|
||||
{ if(Inp >= (Out+Mask))
|
||||
{ Inp -= Out+Mask; Out += Mask<<1; }
|
||||
Out>>=1; Mask>>=2; }
|
||||
if(Inp>Out) Out++;
|
||||
|
||||
return Out; }
|
||||
*/
|
|
@ -0,0 +1,68 @@
|
|||
#include <math.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#ifndef __INTMATH_H__
|
||||
#define __INTMATH_H__
|
||||
|
||||
const uint32_t IntSine_Scale=0x80000000;
|
||||
|
||||
// get Sine from the SineTable
|
||||
// Angle is 0..255 which corresponds to <0..2*PI)
|
||||
int32_t IntSine(uint8_t Angle);
|
||||
|
||||
// precise Sine with for 16-bit angles 2nd derivative interpolation
|
||||
// max. result error is about 2.3e-7
|
||||
int32_t IntSine(uint16_t Angle);
|
||||
|
||||
// precise Sine for 32-bit angles with 2nd derivative interpolation
|
||||
// max. result error is about 2.3e-7
|
||||
int32_t IntSine(uint32_t Angle);
|
||||
|
||||
// less precise sine for 16-bit angles
|
||||
const int16_t Isine_Scale=0x4000;
|
||||
int16_t Isin(int16_t Angle);
|
||||
int16_t inline Icos(int16_t Angle) { return Isin(Angle+0x4000); }
|
||||
|
||||
// atan2(Y, X)
|
||||
// max. result error is 1/6 degree
|
||||
int16_t IntAtan2(int16_t Y, int16_t X);
|
||||
|
||||
// integer square root
|
||||
// uint32_t IntSqrt(uint32_t Inp);
|
||||
// uint64_t IntSqrt(uint64_t Inp);
|
||||
|
||||
template<class Type> // integer square root for 16-bit or 32-bit
|
||||
Type IntSqrt(Type Inp) // must be made with unsigned type or signed types with _positive_ values
|
||||
{ Type Out = 0;
|
||||
Type Mask = 1; Mask<<=(sizeof(Type)*8-2);
|
||||
|
||||
while(Mask>Inp) Mask>>=2;
|
||||
while(Mask)
|
||||
{ if(Inp >= (Out+Mask))
|
||||
{ Inp -= Out+Mask; Out += Mask<<1; }
|
||||
Out>>=1; Mask>>=2; }
|
||||
if(Inp>Out) Out++;
|
||||
|
||||
return Out; }
|
||||
|
||||
// Distance = sqrt(dX*dX+dY*dY)
|
||||
|
||||
inline uint32_t IntDistance(int32_t dX, int32_t dY) { return IntSqrt((uint64_t)((int64_t)dX*dX + (int64_t)dY*dY)); }
|
||||
inline uint16_t IntDistance(int16_t dX, int16_t dY) { return IntSqrt((uint32_t)((int32_t)dX*dX + (int32_t)dY*dY)); }
|
||||
|
||||
template <class IntType>
|
||||
IntType IntFastDistance(IntType dX, IntType dY) // after: http://www.flipcode.com/archives/Fast_Approximate_Distance_Functions.shtml
|
||||
{ IntType min, max, approx;
|
||||
|
||||
if(dX<0) dX = -dX;
|
||||
if(dY<0) dY = -dY;
|
||||
|
||||
if(dX<dY) { min = dX; max = dY; }
|
||||
else { min = dY; max = dX; }
|
||||
|
||||
approx = max*1007 + min*441;
|
||||
if( max < (min<<4) ) approx -= max*40;
|
||||
|
||||
return (approx+512)>>10; }
|
||||
|
||||
#endif // of __INTMATH_H__
|
|
@ -0,0 +1,751 @@
|
|||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "ldpc.h"
|
||||
|
||||
#ifndef __AVR__
|
||||
#include <math.h>
|
||||
#endif
|
||||
|
||||
#ifdef __AVR__
|
||||
#include <avr/pgmspace.h>
|
||||
#endif
|
||||
|
||||
// ===================================================================================================================
|
||||
|
||||
// FindVectors65432bit(10,20,23, 500) => 208, Delta=2579
|
||||
|
||||
// every row represents a parity check to be performed on the received codeword
|
||||
static const uint32_t LDPC_ParityCheck_n208k160[48][7]
|
||||
#ifdef __AVR__
|
||||
PROGMEM
|
||||
#endif
|
||||
= { // parity check vectors: 48 vectors for 48 parity checks
|
||||
// Eaech vector applied to the data packet should yield even number of bits
|
||||
{ 0x00000805, 0x00000020, 0x04000000, 0x20000000, 0x00000040, 0x00044020, 0x00000000 },
|
||||
{ 0x00000001, 0x00800800, 0x00000000, 0x00000000, 0x00000000, 0x10010000, 0x00008C98 },
|
||||
{ 0x00004001, 0x01000080, 0x80000400, 0x00000000, 0x08000200, 0x00200000, 0x00000005 },
|
||||
{ 0x00000101, 0x20000200, 0x00000022, 0x00000000, 0x00000000, 0xCC008000, 0x00005002 },
|
||||
{ 0x00000401, 0x00000000, 0x00004900, 0x00000020, 0x00000000, 0x20C00349, 0x00000020 },
|
||||
{ 0x03140001, 0x00000002, 0x00000000, 0x40000001, 0x41534100, 0x00102C00, 0x00002000 },
|
||||
{ 0x04008800, 0x82000642, 0x00000000, 0x00000020, 0x88040020, 0x03000010, 0x00000400 },
|
||||
{ 0x00000802, 0x20000000, 0x02000014, 0x01200000, 0x04000403, 0x00800004, 0x0000A004 },
|
||||
{ 0x02020820, 0x00000000, 0x80020820, 0x10190040, 0x30000000, 0x00000002, 0x00000900 },
|
||||
{ 0x40804950, 0x00090000, 0x00000000, 0x00021204, 0x40001000, 0x10001100, 0x00000000 },
|
||||
{ 0x08000A00, 0x00020008, 0x00040000, 0x02400010, 0x01002000, 0x40280280, 0x00000010 },
|
||||
{ 0x00000000, 0x00008010, 0x118000A0, 0x00040080, 0x01000084, 0x00040100, 0x00000444 },
|
||||
{ 0x20040108, 0x18000000, 0x08608800, 0x0000000A, 0x08000010, 0x00040080, 0x00008000 },
|
||||
{ 0x00004080, 0x00422201, 0x00010000, 0x0000A400, 0x00400800, 0x00840000, 0x00000800 },
|
||||
{ 0x00000000, 0x60200000, 0x80100240, 0x08000021, 0x02800000, 0x100C0000, 0x00000000 },
|
||||
{ 0x00001000, 0x01010002, 0x00082001, 0x04000000, 0x00000001, 0x00040002, 0x00004030 },
|
||||
{ 0x00002300, 0x04000000, 0xA0080000, 0x20004000, 0x00028000, 0x00800000, 0x00000400 },
|
||||
{ 0x00004000, 0x00104100, 0x40041028, 0x24000020, 0x00200000, 0x00100000, 0x00008000 },
|
||||
{ 0x08011000, 0x20040000, 0x00000000, 0xA0800000, 0x08090000, 0x00000100, 0x00000A00 },
|
||||
{ 0x10180000, 0x00000204, 0x00002800, 0x20400800, 0x00000000, 0x10000000, 0x00000004 },
|
||||
{ 0x00000000, 0xC0000000, 0x10200000, 0x20028000, 0x20000000, 0x80000008, 0x00002011 },
|
||||
{ 0x82004000, 0x20000000, 0x04202000, 0x00000000, 0x00000000, 0x00020200, 0x00000400 },
|
||||
{ 0x08600000, 0x00001200, 0x94000000, 0x00000000, 0x40000008, 0x00000000, 0x00008020 },
|
||||
{ 0x04040000, 0x04010000, 0x04100000, 0x00000100, 0x00200000, 0x40000008, 0x00000804 },
|
||||
{ 0x00000200, 0x00000110, 0x04000100, 0x00000000, 0x28400400, 0x10000000, 0x00004000 },
|
||||
{ 0x00080000, 0x00000080, 0x04001000, 0x01882007, 0x00008024, 0x04000001, 0x00000010 },
|
||||
{ 0x20200000, 0x00000020, 0x00010040, 0x81000800, 0x10001000, 0x00300008, 0x00004400 },
|
||||
{ 0x90000010, 0x89841021, 0x00000118, 0x08080000, 0x00020000, 0x40000000, 0x00000040 },
|
||||
{ 0x04C20000, 0x10404034, 0x00000000, 0x00004000, 0x00810001, 0x04000200, 0x00000009 },
|
||||
{ 0x40102000, 0x020020A0, 0x40100000, 0x00100080, 0x00080400, 0x80030080, 0x00000020 },
|
||||
{ 0x00010000, 0x04020920, 0x00000200, 0x00060000, 0x00000218, 0x01002007, 0x00001000 },
|
||||
{ 0x00020008, 0x00A08040, 0x00080000, 0x40001400, 0x04200040, 0x80200001, 0x00000200 },
|
||||
{ 0x40000402, 0x01100000, 0x20808000, 0x00008000, 0x10100060, 0x00080000, 0x00001008 },
|
||||
{ 0x200010A0, 0x00000000, 0x01040100, 0x00000104, 0x02040042, 0x08012000, 0x00000001 },
|
||||
{ 0x01000000, 0x50000880, 0x00000092, 0x14400000, 0x00001840, 0x02400000, 0x00000000 },
|
||||
{ 0x00000010, 0x02000000, 0x00014000, 0x00200018, 0x00000240, 0x04000800, 0x00000180 },
|
||||
{ 0x00008000, 0x00880008, 0x08000044, 0x00100000, 0x00000004, 0x00400820, 0x00001001 },
|
||||
{ 0x01000000, 0x00002000, 0x02004001, 0x00000042, 0x00000000, 0x09201020, 0x00000048 },
|
||||
{ 0x00800000, 0x01000400, 0x00400002, 0xC0002000, 0x00002080, 0x00010064, 0x00000100 },
|
||||
{ 0x00000400, 0x08400840, 0x00000400, 0x00000890, 0x00008102, 0x00000020, 0x00000002 },
|
||||
{ 0x00200040, 0x00000081, 0x00000000, 0x02050000, 0x04940000, 0x20008020, 0x00000080 },
|
||||
{ 0x00000404, 0x00800000, 0x00001000, 0x00014000, 0x00082200, 0x0A000400, 0x00000000 },
|
||||
{ 0x0000A024, 0x00000000, 0x00000402, 0x08A01000, 0x00004010, 0x20000000, 0x00000008 },
|
||||
{ 0x00480046, 0x00008000, 0x00000208, 0x00000048, 0x00000000, 0x00410010, 0x00000002 },
|
||||
{ 0x0000008C, 0x00044C00, 0x00824004, 0x00000200, 0x00000000, 0x00028000, 0x00000000 },
|
||||
{ 0x10010004, 0x00080000, 0x43008000, 0x10000400, 0x80000100, 0x00000040, 0x00000080 },
|
||||
{ 0x80000000, 0x0020000C, 0x20420480, 0x00000100, 0x00000008, 0x00005410, 0x00000080 },
|
||||
{ 0x00000000, 0x00101000, 0x08000001, 0x02000200, 0x82004A80, 0x00004000, 0x00000202 }
|
||||
} ;
|
||||
|
||||
|
||||
const uint8_t LDPC_ParityCheckIndex_n208k160[48][24]
|
||||
#ifdef __AVR__
|
||||
PROGMEM
|
||||
#endif
|
||||
= { // number of, indicies to bits to be taken for parity checks
|
||||
{ 10, 0, 2, 11, 37, 90, 125, 134, 165, 174, 178 },
|
||||
{ 11, 0, 43, 55, 176, 188, 195, 196, 199, 202, 203, 207 },
|
||||
{ 11, 0, 14, 39, 56, 74, 95, 137, 155, 181, 192, 194, },
|
||||
{ 14, 0, 8, 41, 61, 65, 69, 175, 186, 187, 190, 191, 193, 204, 206 },
|
||||
{ 15, 0, 10, 72, 75, 78, 101, 160, 163, 166, 168, 169, 182, 183, 189, 197 },
|
||||
{ 21, 0, 18, 20, 24, 25, 33, 96, 126, 136, 142, 144, 145, 148, 150, 152, 158, 170, 171, 173, 180, 205 },
|
||||
{ 18, 11, 15, 26, 33, 38, 41, 42, 57, 63, 101, 133, 146, 155, 159, 164, 184, 185, 202 },
|
||||
{ 17, 1, 11, 61, 66, 68, 89, 117, 120, 128, 129, 138, 154, 162, 183, 194, 205, 207 },
|
||||
{ 18, 5, 11, 17, 25, 69, 75, 81, 95, 102, 112, 115, 116, 124, 156, 157, 161, 200, 203 },
|
||||
{ 18, 4, 6, 8, 11, 14, 23, 30, 48, 51, 98, 105, 108, 113, 140, 158, 168, 172, 188 },
|
||||
{ 17, 9, 11, 27, 35, 49, 82, 100, 118, 121, 141, 152, 167, 169, 179, 181, 190, 196 },
|
||||
{ 17, 36, 47, 69, 71, 87, 88, 92, 103, 114, 130, 135, 152, 168, 178, 194, 198, 202 },
|
||||
{ 18, 3, 8, 18, 29, 59, 60, 75, 79, 85, 86, 91, 97, 99, 132, 155, 167, 178, 207 },
|
||||
{ 16, 7, 14, 32, 41, 45, 49, 54, 80, 106, 109, 111, 139, 150, 178, 183, 203 },
|
||||
{ 15, 53, 61, 62, 70, 73, 84, 95, 96, 101, 123, 151, 153, 178, 179, 188 },
|
||||
{ 14, 12, 33, 48, 56, 64, 77, 83, 122, 128, 161, 178, 196, 197, 206 },
|
||||
{ 13, 8, 9, 13, 58, 83, 93, 95, 110, 125, 143, 145, 183, 202 },
|
||||
{ 15, 14, 40, 46, 52, 67, 69, 76, 82, 94, 101, 122, 125, 149, 180, 207 },
|
||||
{ 14, 12, 16, 27, 50, 61, 119, 125, 127, 144, 147, 155, 168, 201, 203 },
|
||||
{ 12, 19, 20, 28, 34, 41, 75, 77, 107, 118, 125, 188, 194 },
|
||||
{ 13, 62, 63, 85, 92, 111, 113, 125, 157, 163, 191, 192, 196, 205 },
|
||||
{ 10, 14, 25, 31, 61, 77, 85, 90, 169, 177, 202 },
|
||||
{ 12, 21, 22, 27, 41, 44, 90, 92, 95, 131, 158, 197, 207 },
|
||||
{ 12, 18, 26, 48, 58, 84, 90, 104, 149, 163, 190, 194, 203 },
|
||||
{ 11, 9, 36, 40, 72, 90, 138, 150, 155, 157, 188, 206 },
|
||||
{ 17, 19, 39, 76, 90, 96, 97, 98, 109, 115, 119, 120, 130, 133, 143, 160, 186, 196 },
|
||||
{ 15, 21, 29, 37, 70, 80, 107, 120, 127, 140, 156, 163, 180, 181, 202, 206 },
|
||||
{ 19, 4, 28, 31, 32, 37, 44, 50, 55, 56, 59, 63, 67, 68, 72, 115, 123, 145, 190, 198 },
|
||||
{ 18, 17, 22, 23, 26, 34, 36, 37, 46, 54, 60, 110, 128, 144, 151, 169, 186, 192, 195 },
|
||||
{ 18, 13, 20, 30, 37, 39, 45, 57, 84, 94, 103, 116, 138, 147, 167, 176, 177, 191, 197 },
|
||||
{ 18, 16, 37, 40, 43, 49, 58, 73, 113, 114, 131, 132, 137, 160, 161, 162, 173, 184, 204 },
|
||||
{ 17, 3, 17, 38, 47, 53, 55, 83, 106, 108, 126, 134, 149, 154, 160, 181, 191, 201 },
|
||||
{ 16, 1, 10, 30, 52, 56, 79, 87, 93, 111, 133, 134, 148, 156, 179, 195, 204 },
|
||||
{ 17, 5, 7, 12, 29, 72, 82, 88, 98, 104, 129, 134, 146, 153, 173, 176, 187, 192 },
|
||||
{ 16, 24, 39, 43, 60, 62, 65, 68, 71, 118, 122, 124, 134, 139, 140, 182, 185 },
|
||||
{ 13, 4, 57, 78, 80, 99, 100, 117, 134, 137, 171, 186, 199, 200 },
|
||||
{ 14, 15, 35, 51, 55, 66, 70, 91, 116, 130, 165, 171, 182, 192, 204 },
|
||||
{ 14, 24, 45, 64, 78, 89, 97, 102, 165, 172, 181, 184, 187, 195, 198 },
|
||||
{ 15, 23, 42, 56, 65, 86, 109, 126, 127, 135, 141, 162, 165, 166, 176, 200 },
|
||||
{ 14, 10, 38, 43, 54, 59, 74, 100, 103, 107, 129, 136, 143, 165, 193 },
|
||||
{ 15, 6, 21, 32, 39, 112, 114, 121, 146, 148, 151, 154, 165, 175, 189, 199 },
|
||||
{ 12, 2, 10, 55, 76, 110, 112, 137, 141, 147, 170, 185, 187 },
|
||||
{ 14, 2, 5, 13, 15, 65, 74, 108, 117, 119, 123, 132, 142, 189, 195 },
|
||||
{ 14, 1, 2, 6, 19, 22, 47, 67, 73, 99, 102, 164, 176, 182, 193 },
|
||||
{ 14, 2, 3, 7, 42, 43, 46, 50, 66, 78, 81, 87, 105, 175, 177 },
|
||||
{ 14, 2, 16, 28, 51, 79, 88, 89, 94, 106, 124, 136, 159, 166, 199 },
|
||||
{ 16, 31, 34, 35, 53, 71, 74, 81, 86, 93, 104, 131, 164, 170, 172, 174, 199 },
|
||||
{ 15, 44, 52, 64, 91, 105, 121, 135, 137, 139, 142, 153, 159, 174, 193, 201 }
|
||||
} ;
|
||||
|
||||
static const uint8_t LDPC_BitWeight_n208k160[208] // weight of parity checks for every codeword bit
|
||||
#ifdef __AVR__
|
||||
PROGMEM
|
||||
#endif
|
||||
= { 6, 3, 6, 3, 3, 3, 3, 3, 4, 3, 4, 6, 3, 3, 5, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3,
|
||||
3, 3, 3, 3, 3, 6, 3, 5, 3, 5, 3, 5, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 5, 5, 3, 3, 3, 3, 5, 3, 3,
|
||||
3, 4, 3, 3, 3, 4, 3, 3, 4, 3, 4, 4, 3, 3, 4, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 6, 3, 3, 3, 3, 5,
|
||||
3, 3, 3, 3, 3, 4, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 6, 3, 3,
|
||||
3, 3, 3, 3, 3, 3, 6, 3, 3, 5, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 5, 3, 3, 3, 3,
|
||||
4, 3, 3, 4, 3, 6, 3, 3, 4, 4, 3, 3, 3, 3, 3, 3, 5, 3, 6, 3, 3, 5, 4, 4, 3, 3, 4, 4, 5, 3, 4, 4,
|
||||
5, 4, 5, 5, 5, 4, 3, 5, 3, 3, 6, 5, 4, 3, 4, 5 } ;
|
||||
|
||||
// every row represents the generator for a parity bit
|
||||
static const uint32_t LDPC_ParityGen_n208k160[48][5]
|
||||
#ifdef __AVR__
|
||||
PROGMEM
|
||||
#endif
|
||||
= { // Parity bits generator: 48 vectors to generate 48 parity bits
|
||||
// Each vector applied to the user data yields a corresponding parity bit
|
||||
{ 0x40A90281, 0x9159D249, 0xCE9D516B, 0x2FDEED0B, 0xD9267CD4 },
|
||||
{ 0xCCBC0FC3, 0xCC4FA4BC, 0x811EC3D0, 0xB07EC1B3, 0xA3B8E8D8 },
|
||||
{ 0x66418D56, 0x3B85ADFF, 0xD2A6532E, 0x48CF52E4, 0x6A16586D },
|
||||
{ 0x44C71240, 0x2C94631F, 0x15F15A4A, 0x7459D901, 0x037863CC },
|
||||
{ 0x7386D718, 0x7F6C9623, 0x738E2E0C, 0xD2351593, 0xEF358669 },
|
||||
{ 0x7BF87232, 0x9E4CCD68, 0xBB82590E, 0x9C9292EA, 0x4CE2AEB9 },
|
||||
{ 0xAA8436BC, 0x94A61C4D, 0x1DA89B11, 0x72EAF204, 0x34D3A041 },
|
||||
{ 0xBCE77760, 0x229935B2, 0xAAF85CE3, 0xFFE7B602, 0xF26BCC64 },
|
||||
{ 0xD0C371D0, 0xA553D12F, 0xA0685BF2, 0x5C553C81, 0x0218EB48 },
|
||||
{ 0x8D29034D, 0xEB20A394, 0x1A8C82A3, 0x41B4DA0C, 0x8632F81E },
|
||||
{ 0x15A50876, 0x9BC10F59, 0xF979D1E0, 0xCFF6BD88, 0x88FE5895 },
|
||||
{ 0x037A9ED5, 0xFA5DB837, 0x61395ACA, 0xE65B5839, 0x9A2D9D02 },
|
||||
{ 0xEE70D18F, 0x8AE909C6, 0x8AF5BECA, 0x66968559, 0x1BD9B5E7 },
|
||||
{ 0xC56397AC, 0xD8FF6A30, 0x8E165AF3, 0xC01686B9, 0xEC26BEDC },
|
||||
{ 0xB2D63859, 0xFACA8CFD, 0x7EE85EB7, 0x19BFDA46, 0xC8C1CA52 },
|
||||
{ 0xD7EB4D94, 0x426104DA, 0x124FBD54, 0xBF610A1D, 0x0E615094 },
|
||||
{ 0x68EFE180, 0x15A1549C, 0x18D20289, 0xBD28AD44, 0x8DADDAEC },
|
||||
{ 0xD7EB4D18, 0x426548DA, 0x12CDFD50, 0xBF61081D, 0x0E615094 },
|
||||
{ 0xC92E426E, 0x648641B5, 0xC16A07B9, 0xA52D48AC, 0x842364AB },
|
||||
{ 0xB71DAB61, 0x2B15995C, 0x6BE7E0C1, 0x97ECE351, 0xDF622A04 },
|
||||
{ 0x55CD7406, 0x5E0F3507, 0x23F6C372, 0x7ECAFE84, 0x7E68A8DF },
|
||||
{ 0x97DB831C, 0xD46D648F, 0x14FA22B3, 0x4F875648, 0x94C23936 },
|
||||
{ 0x60D940EC, 0xFCC18797, 0xD0DE7383, 0xF38F22E5, 0x2E7A733E },
|
||||
{ 0xD8C22D55, 0x8D45EB4E, 0xAC695FF3, 0xDED59211, 0x8851288A },
|
||||
{ 0xCE9D11A1, 0xD8E8F438, 0xAF3102EE, 0xCB2FE547, 0xC11845BD },
|
||||
{ 0x61D940EC, 0xACC18F17, 0xD0DE7311, 0xE7CF22E5, 0x2E7A6B7E },
|
||||
{ 0x66AD8025, 0x493D883C, 0x538E9261, 0x5F0E116B, 0xB17492FA },
|
||||
{ 0x747C4C9E, 0x3780804E, 0x29A7B2F1, 0x2838DF6D, 0xA68C11EB },
|
||||
{ 0x7E33E90F, 0x2FB3D8E9, 0x2A9DE538, 0x3AC1ABDC, 0x59C14EAF },
|
||||
{ 0x16B6095E, 0x4883D57E, 0xF765FF4B, 0x431C6EF3, 0xF2C45F6C },
|
||||
{ 0x3F04D4F4, 0xEEA73108, 0x567ECF38, 0x15200560, 0x56AB6942 },
|
||||
{ 0x1E5ECFFE, 0x29426F53, 0x17057060, 0xA774ED7F, 0x4FE7EACB },
|
||||
{ 0xF9F02A12, 0xFADEBEE2, 0xBE67EB8B, 0x5506F594, 0xC5037599 },
|
||||
{ 0x7BF87632, 0x960CC528, 0xBB825D0E, 0x9C929A7A, 0x4CE22FBB },
|
||||
{ 0x6E2BE90F, 0x2FB3DAED, 0x2A9DCD38, 0x1A81A3DC, 0x59C14EAF },
|
||||
{ 0x16B6A97A, 0x4883D57E, 0xF765FB49, 0x4BBC7EF3, 0xF2C41F7C },
|
||||
{ 0x260C82A4, 0xD8645AF5, 0x9913D30A, 0x7158DC67, 0x68526E0A },
|
||||
{ 0x5DAD3406, 0x5E1F6607, 0xF7F2D35A, 0x5ACAFEA4, 0x3E48A8D7 },
|
||||
{ 0xAF04D4E4, 0x67232129, 0x567ECE20, 0x1D280560, 0x56A96942 },
|
||||
{ 0xBA8536B8, 0x94AE1C4D, 0x5EA81B11, 0x62EAF604, 0xB4D3A141 },
|
||||
{ 0xDF522858, 0x25CE2C46, 0x6C1E93BA, 0xDB9FBF4E, 0x9F8AACF9 },
|
||||
{ 0xC92E4E6B, 0x6CD659D5, 0xCD6A03B8, 0x872D423C, 0x0623AF69 },
|
||||
{ 0xD8C20E55, 0x8945EB4E, 0x0C615FF3, 0xFED5D211, 0x8853A88A },
|
||||
{ 0x11EC2FBB, 0xE98188FA, 0x6D02584A, 0x7BF87EBD, 0x0C324421 },
|
||||
{ 0xE1AB0619, 0x62864C22, 0xBC029B88, 0xDC501DA2, 0x3DB63518 },
|
||||
{ 0x85657508, 0xE76CE85B, 0x35A012AB, 0xD7719D8D, 0xC1CE9294 },
|
||||
{ 0x7E33EB0F, 0x2FB3D9F9, 0x2E9DE438, 0x3AC1ABDC, 0x71814AAF },
|
||||
{ 0x55CD3406, 0x5E1F7407, 0x63F2D35A, 0x5ACAFEA4, 0x7E48A8DF }
|
||||
} ;
|
||||
|
||||
|
||||
// ===================================================================================================================
|
||||
|
||||
#ifdef WITH_PPM
|
||||
|
||||
const uint32_t LDPC_ParityCheck_n354k160[194][12] // 354 codeword = 160 user bits + 194 parity checks
|
||||
#ifdef __AVR__
|
||||
PROGMEM
|
||||
#endif
|
||||
= { // parity check vectors
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x28000000, 0x00000000, 0x00000000, 0x00000400, 0x00E00006, 0x00000000, 0x00000080, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x80000000, 0x000C0040, 0x00010000, 0x00180000, 0x00000000, 0x40000040, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x20003000, 0x58000000, 0x00000000, 0x00000000, 0x00010000, 0x00000000, 0x30000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00200000, 0x18000000, 0x00000400, 0x00000000, 0x00000C00, 0x00008000, 0x00000000, 0x20000020, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00003000, 0x00002030, 0x10000800, 0x00000008, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x20000004, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000C00, 0x00000000, 0x0C000000, 0x00000000, 0x40000001, 0x00000008, 0x00004000, 0x00000000, 0x10000000, 0x00000001 },
|
||||
{ 0x00040000, 0x00800001, 0x00000380, 0x00100000, 0x04000000, 0x00000000, 0x00000000, 0x00000000, 0x00004000, 0x00000000, 0x00000010, 0x00000000 },
|
||||
{ 0x80048000, 0x00002200, 0x00000000, 0x00080200, 0x00000000, 0x00000000, 0x00010001, 0x00000800, 0x00000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000020, 0x00000000, 0x00000000, 0x01000000, 0x00000400, 0x00000000, 0x80000000, 0x00000010, 0x00000000, 0x00000000, 0x0D000100, 0x00000002 },
|
||||
{ 0x00000000, 0x00000400, 0x00000000, 0x00000440, 0x00002000, 0x20000000, 0x20000000, 0x00000000, 0x00000000, 0x00000000, 0x02000082, 0x00000000 },
|
||||
{ 0x80000000, 0x00000400, 0x00004200, 0x00000000, 0x00000000, 0x00000000, 0x00014000, 0x00000800, 0x00003000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x81000040, 0x00040000, 0x00002000, 0x8A000000, 0x00000000, 0x00000002 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00801000, 0x04060000, 0x00000800, 0x10000000, 0x01000200, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x20000100, 0x00000000, 0x0400050C, 0x00000000, 0x00000000, 0x00001000, 0x00000040, 0x00000000, 0x00000000 },
|
||||
{ 0x40000000, 0x00000000, 0x00000000, 0x00000088, 0x03000000, 0x04000000, 0x00002000, 0x00000000, 0x00000008, 0x04000000, 0x00000000, 0x00000000 },
|
||||
{ 0x40000000, 0x00008000, 0x00000070, 0x00000080, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000100, 0x00000000, 0x02200000, 0x00000000 },
|
||||
{ 0x00004000, 0x00004000, 0x01000000, 0x00000000, 0x00002400, 0x00000000, 0x80008000, 0x00000000, 0x00000000, 0x02000000, 0x00100008, 0x00000000 },
|
||||
{ 0x00002000, 0x00000000, 0x01000002, 0x00010040, 0x10000200, 0x00000400, 0x00000000, 0x00000000, 0x00000000, 0x01000000, 0x00000000, 0x00000001 },
|
||||
{ 0x40040000, 0x00000000, 0x00000006, 0x00000020, 0x02000000, 0x02000000, 0x00000800, 0x00000000, 0x20000000, 0x00800000, 0x00000000, 0x00000000 },
|
||||
{ 0x00021800, 0x80000000, 0x00000000, 0x10000000, 0x00000000, 0x00000100, 0x00000000, 0x08000008, 0x00000000, 0x00000000, 0x00000014, 0x00000000 },
|
||||
{ 0x00000601, 0x00000002, 0x00000000, 0x00000000, 0x00000000, 0x02800000, 0x00010000, 0x00000000, 0x00000008, 0x00400020, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000140, 0x08000000, 0x01800000, 0x00000000, 0x00000008, 0x00000000, 0x00000002, 0x20100000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000800, 0x0A004000, 0x00000000, 0x00000003, 0x02001004, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00800A00, 0x00000000, 0x00800240, 0x00008080, 0x00000000, 0x00000000, 0x00000000, 0x00200000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00010020, 0x00000400, 0x00010004, 0x00000000, 0x01008000, 0x00000008, 0x00000000, 0x10000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x04000000, 0x20000000, 0x08000000, 0x01400000, 0x00000000, 0x00000800, 0x00000000, 0x00004000, 0x00000082, 0x00000000 },
|
||||
{ 0x00000000, 0x40000000, 0x00400100, 0x00800000, 0x08000000, 0x00008000, 0x00000000, 0x00000008, 0x00000000, 0x00000002, 0x00000002, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00400100, 0x05000000, 0x00000000, 0x00000000, 0x00000440, 0x00010000, 0x00000000, 0x00080000, 0x00000001 },
|
||||
{ 0x00000000, 0x10000000, 0x00200080, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x80010000, 0x02002000, 0x000C0000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00100000, 0x04000000, 0x00000200, 0x00000004, 0x00040000, 0x01000000, 0x40000004, 0x00000000, 0x00000004, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x41100000, 0x00000000, 0x00000220, 0x00000000, 0x40000080, 0x00000000, 0x80000000, 0x00000000, 0x00000000, 0x00000002 },
|
||||
{ 0x00000000, 0x00000000, 0x00142000, 0x00008000, 0x00000000, 0x00000000, 0x00000080, 0x00004000, 0x00000000, 0x01000000, 0x01001000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x80000000, 0x00080000, 0x00000000, 0x00100400, 0x00000080, 0x08800000, 0x00000000, 0x00000000, 0x80000008, 0x00000000 },
|
||||
{ 0x00000000, 0x20000000, 0x00002000, 0x02800000, 0x00000000, 0x00000040, 0x00000001, 0x00000000, 0x40000000, 0x00000002, 0x00000080, 0x00000000 },
|
||||
{ 0x00000000, 0x08000000, 0x00000400, 0x00004000, 0x00000000, 0x00000000, 0x00480000, 0x00000010, 0x00000005, 0x01000000, 0x00000000, 0x00000000 },
|
||||
{ 0x40000000, 0x00000404, 0x80000000, 0x00000000, 0x00000000, 0x40000010, 0x00000000, 0x80000000, 0x00000000, 0x00400000, 0x10000000, 0x00000000 },
|
||||
{ 0x40000000, 0x00000003, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00200301, 0x20000100, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00008000, 0x00008010, 0x00000100, 0x40401000, 0x00080080, 0x00000000 },
|
||||
{ 0x30000000, 0x00000000, 0x00000000, 0x00004000, 0x00008000, 0x08000420, 0x00000000, 0x08000000, 0x00000000, 0x00002000, 0x00000000, 0x00000000 },
|
||||
{ 0x24000000, 0x00001000, 0x04000000, 0x01010020, 0x00000000, 0x00000000, 0x00000000, 0x01000000, 0x00200000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x0C0C0000, 0x00000000, 0x00000000, 0x21000000, 0x00000500, 0x00000000, 0x00000000, 0x00200000, 0x00008000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x21000000, 0x00000000, 0x00000000, 0x01000000, 0x00080000, 0x20000000, 0x00020000, 0x60000010, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x04000200, 0x00000002, 0x00000100, 0x40008000, 0x00000040, 0x00000400, 0x10000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00010000, 0x0C000400, 0x00000040, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x400000C1, 0x00001000, 0x00000000, 0x00000000 },
|
||||
{ 0x21010000, 0x00000000, 0x00000000, 0x10000800, 0x00000100, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x40000800, 0x00080000, 0x00000000 },
|
||||
{ 0x00004800, 0x00000000, 0x40080000, 0x00000008, 0x00000000, 0x00000050, 0x00000000, 0x00000000, 0x00000000, 0x00000008, 0x00040000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x01080000, 0x00000098, 0x00002000, 0x00000000, 0x00000000, 0x00000000, 0x00000800, 0x80001000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00002000, 0x00002000, 0x00008000, 0x00000000, 0x00082000, 0x04080000, 0x00000000, 0x00000000, 0x00000A00, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00086000, 0x00000008, 0x00000000, 0x00000002, 0x00042040, 0x00000200, 0x00000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000040, 0x00000000, 0x00000000, 0x00000002, 0x00000010, 0x00080000, 0x10000001, 0x00000800, 0x80020000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000400, 0x00000000, 0x02000002, 0x00000000, 0x00000000, 0x00020400, 0x00000000, 0x10200000, 0x00000800, 0x00000002, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00002000, 0x00000000, 0x00081201, 0x00000000, 0x00000000, 0x00300000, 0x00020400, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00080000, 0x00000004, 0x00000000, 0x00000000, 0x04000000, 0x10000004, 0x00400080, 0x00010000, 0x00010000, 0x00000000 },
|
||||
{ 0x00000400, 0x00400000, 0x00001800, 0x00002000, 0x00000002, 0x02000000, 0x00000000, 0x10000000, 0x18000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00080000, 0x0080A000, 0x00000080, 0x00000000, 0x00100000, 0x00000000, 0x00010000, 0x00002100, 0x00000000 },
|
||||
{ 0x00000000, 0x00000900, 0x00000000, 0x00000000, 0x00001000, 0x40080001, 0x00000000, 0x00000000, 0x00000000, 0x02000500, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00080B00, 0x20000208, 0x00000000, 0x00000000, 0x00040000, 0x00000000, 0x00004000, 0x00000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x10000002, 0x00000000, 0x00000000, 0x00000200, 0x00800040, 0x40000000, 0x20000008, 0x00000040, 0x00000000 },
|
||||
{ 0x00000000, 0x80000000, 0x10000000, 0x00000420, 0x00000080, 0x00000020, 0x00000080, 0x00000000, 0x04000000, 0x00000200, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00008400, 0x00000010, 0x00028000, 0x00000000, 0x00000000, 0x00000000, 0x80010000, 0x00040100, 0x00000000 },
|
||||
{ 0x80000000, 0x00000020, 0x80000000, 0x10000010, 0x80000000, 0x00000000, 0x24000000, 0x00000000, 0x80000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00010000, 0x00400000, 0x00000000, 0x40000010, 0x00000001, 0x00000100, 0x00000008, 0x08000008, 0x00000000 },
|
||||
{ 0x00000000, 0x00000084, 0x00000010, 0x00000100, 0x00000002, 0x00000000, 0x00000000, 0x00000000, 0x00200000, 0x30000000, 0x02000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x801D0000, 0x0020C000, 0x00000002 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x40000004, 0x00000000, 0x0082000A, 0x40020000, 0x00000000, 0x00000800, 0x00000000, 0x00000000 },
|
||||
{ 0x30000000, 0x04020000, 0x00000000, 0x00000080, 0x00401000, 0x00000000, 0x00000000, 0x20000000, 0x00000000, 0x00000000, 0x01000000, 0x00000000 },
|
||||
{ 0x00088000, 0x00000010, 0x00000000, 0x00000000, 0x10000800, 0x40000000, 0x00000000, 0x04000000, 0x00060000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00006000, 0x00000000, 0x00000000, 0x00004002, 0x00200000, 0x00000000, 0x00000200, 0x00000000, 0x00000080, 0x00000204, 0x00000000, 0x00000000 },
|
||||
{ 0x10000000, 0x00000000, 0x00000000, 0x00A00000, 0x00000000, 0x00000080, 0x00040000, 0x00000200, 0x00400000, 0x02000000, 0x00040000, 0x00000000 },
|
||||
{ 0x00000000, 0x00100000, 0x01000001, 0x00000000, 0x00000000, 0x00000000, 0x00008206, 0x00001000, 0x00000000, 0x00008000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x10000008, 0x00000000, 0x00008000, 0x00000000, 0x00000010, 0x00020000, 0x04000002, 0x04040000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00040000, 0x00000000, 0x00000001, 0x00000000, 0x00010001, 0x00000000, 0x00000040, 0x00000000, 0x00200100, 0x00010000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x20000000, 0x00000000, 0x20000000, 0x40002000, 0x00000004, 0x00100000, 0x00000028, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x20000000, 0x00000000, 0x02000000, 0x00000000, 0x44000001, 0x00000000, 0x00000004, 0x00408000, 0x00000000, 0x00000000 },
|
||||
{ 0x11200000, 0x00010000, 0x40000000, 0x00000000, 0x00000010, 0x00000000, 0x00000004, 0x00000000, 0x00000000, 0x00000000, 0x08000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000040, 0x00100000, 0x00400000, 0x00000000, 0x80000008, 0x00800000, 0x00002080, 0x00000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00400000, 0x80000010, 0x00000000, 0x00000000, 0x00000026, 0x00000000, 0x00000000, 0x00000000, 0x00002000, 0x00000400, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000042, 0x00000000, 0x00000080, 0x01000000, 0x01000000, 0x00400000, 0x00000000, 0x00000000, 0x00000400, 0x00000020, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000200, 0x00000000, 0x00000400, 0x00000000, 0x00002080, 0x00002000, 0x00008024, 0x00000000 },
|
||||
{ 0x00000000, 0x02000000, 0x00800002, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000002, 0x00004012, 0x00008000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x02800000, 0x10000000, 0x00000000, 0x00000000, 0x00000000, 0x80002000, 0x00100000, 0x00200000, 0x00000000, 0x00008000, 0x00000000 },
|
||||
{ 0x00080100, 0x00000000, 0x00080000, 0x00000010, 0x00000000, 0x08000000, 0x10000001, 0x00000400, 0x00000000, 0x00000000, 0x40000000, 0x00000000 },
|
||||
{ 0x00010080, 0x00000000, 0x00000000, 0x00040000, 0x00000000, 0x00000000, 0x00000000, 0x11000000, 0x00040001, 0x80200000, 0x00000000, 0x00000000 },
|
||||
{ 0x00002010, 0x00000000, 0x00000000, 0x00400014, 0x00004000, 0x00000000, 0x20000000, 0x20000000, 0x00000000, 0x00000000, 0x00000010, 0x00000000 },
|
||||
{ 0x00000440, 0x04000020, 0x08010000, 0x00000000, 0x00000040, 0x08000000, 0x00400000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000002, 0x48000000, 0x00000000, 0x00200000, 0x04001000, 0x02000000, 0x00000000, 0x00000000, 0x00001000, 0x00000000, 0x00000000 },
|
||||
{ 0x00200400, 0x00000000, 0x00800000, 0x02000000, 0x00000000, 0x00000020, 0x04000000, 0x00000000, 0x00000000, 0x00000004, 0x01000000, 0x00000000 },
|
||||
{ 0x01200000, 0x01000000, 0x00000800, 0x00004004, 0x00000000, 0x10000000, 0x00000000, 0x00000000, 0x00000008, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000001, 0x00400001, 0x00000000, 0x00000201, 0x00000020, 0x20000000, 0x08000000, 0x00000000 },
|
||||
{ 0x02000000, 0x00000000, 0x00000800, 0x00000001, 0x00000001, 0x00000000, 0x00000000, 0x01000000, 0x00000020, 0x20000080, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000500, 0x00000000, 0x00000000, 0x00040000, 0x00000000, 0x00000000, 0x11000210, 0x00000000, 0x40000000, 0x00000000 },
|
||||
{ 0x00000020, 0x00000000, 0x00000000, 0x00000000, 0x02000000, 0x20001000, 0x00000000, 0x00000020, 0x41000000, 0x00000400, 0x00000400, 0x00000000 },
|
||||
{ 0x00000000, 0x08000000, 0x00000001, 0x00000040, 0x00000000, 0x01000020, 0x02000000, 0x00008000, 0x80000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00100000, 0x80000100, 0x00000001, 0x00000000, 0x00104040, 0x00001000, 0x00000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000100, 0x00000008, 0x10000000, 0x00100000, 0x00000000, 0x00001000, 0x00008000, 0x00000000, 0x00000002, 0x00100001, 0x00000000, 0x00000000 },
|
||||
{ 0xA0000100, 0x10004000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00008000, 0x00000000, 0x00400000, 0x00000000, 0x00002400, 0x00000000 },
|
||||
{ 0x01800004, 0x00000010, 0x00000000, 0x00020000, 0x00200000, 0x00000040, 0x00000200, 0x00008000, 0x00000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00900000, 0x00000000, 0x00400000, 0x00000000, 0x00000020, 0x00000002, 0x00000000, 0x00100000, 0x00200000, 0x00000080, 0x02000000, 0x00000000 },
|
||||
{ 0x00000000, 0x20000008, 0x00014000, 0x00000000, 0x00000000, 0x00080000, 0x00000000, 0x00000020, 0x00020000, 0x08000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00100000, 0x1000A000, 0x00000100, 0x80000000, 0x00000000, 0x00000000, 0x00020000, 0x80000000, 0x00000000, 0x00000000, 0x00100000, 0x00000000 },
|
||||
{ 0x00020000, 0x00000000, 0x00000000, 0x00000000, 0x00100000, 0x00000000, 0x00200000, 0x00410040, 0x00000400, 0x00080000, 0x00000010, 0x00000000 },
|
||||
{ 0x00000000, 0x08000000, 0x00010000, 0x00400000, 0x40000000, 0x00800800, 0x02000000, 0x00000000, 0x00001000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00120200, 0x00800010, 0x20000000, 0x00000000, 0x00000000, 0x00000300, 0x00000000 },
|
||||
{ 0x00000000, 0x00020000, 0x00000000, 0x00000004, 0x00000080, 0x00000100, 0x00000000, 0x00000020, 0x00000020, 0x00000000, 0x80000040, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000008, 0x00002400, 0x00100800, 0x00000000, 0x00020000, 0x10000002, 0x00000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x10000000, 0x00000220, 0x80000000, 0x00000000, 0x00000000, 0x20000000, 0x00200000, 0x00000020, 0x00080000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x04000000, 0x80008000, 0x00004000, 0x00000000, 0x00000000, 0x00000000, 0x00200200, 0x00000004, 0x00000000, 0x00040000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x40100000, 0x80000800, 0x00000080, 0x00000000, 0x00000000, 0x00000000, 0x00120000, 0x00000008, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00080000, 0x00000018, 0x00100000, 0x00040000, 0x00004000, 0x00800000, 0x00000000, 0x00080000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00C00820, 0x00000000, 0x08000000, 0x00000000, 0x00000000, 0x00000408, 0x00000000, 0x00000000, 0x00000000, 0x00000100, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x20000020, 0x00000000, 0x00002000, 0x00000008, 0x00001000, 0x00004000, 0x00000000, 0x00004000, 0x00800000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00020001, 0x00000000, 0x00000040, 0x00000800, 0x00000000, 0x00001020, 0x00000000, 0x00400200, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00010000, 0x00001010, 0x00000040, 0x00000004, 0x00000000, 0x00000000, 0x00000011, 0x00010000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000400, 0x00000040, 0x00000000, 0x00000000, 0x00001000, 0x00000000, 0x02000000, 0x00002080, 0x00000000, 0x00010000, 0x04001000, 0x00000000 },
|
||||
{ 0x00220040, 0x20000044, 0x00000001, 0x00000000, 0x00000000, 0x00000200, 0x00010000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00008204, 0x00001000, 0x00000000, 0x00000000, 0x80000000, 0x00000000, 0x80000400, 0x80000000, 0x02000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00401300, 0x00000000, 0x00040000, 0x00000000, 0x05000000, 0x00000000, 0x00080000, 0x00000000, 0x00000100, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000020, 0x00000000, 0x00000000, 0x08000000, 0x00080000, 0x00008000, 0x00000900, 0x00000240, 0x04000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x10000000, 0x1C000000, 0x00000200, 0x00000000, 0x20000000, 0x00000100, 0x04000000, 0x01000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00200201, 0x00000000, 0x00000800, 0x00000000, 0x00010800, 0x00001000, 0x00000000, 0x00000008, 0x00040000, 0x00000000, 0x00000000 },
|
||||
{ 0x00080000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x08000000, 0x40010000, 0x00014040, 0x20000000, 0x00000400, 0x00000000 },
|
||||
{ 0x00000000, 0x00840000, 0x00200000, 0x04001000, 0x00000000, 0x00000000, 0x00004000, 0x00000000, 0x00000802, 0x00000000, 0x40000000, 0x00000000 },
|
||||
{ 0x00000800, 0x00014000, 0x00000000, 0x00000000, 0x00080100, 0x00000000, 0x00000000, 0x00000000, 0x00080000, 0x40200000, 0x00800000, 0x00000000 },
|
||||
{ 0x00400000, 0x00000000, 0x00400000, 0x00000000, 0x00080000, 0x00000000, 0x00000000, 0x0001000A, 0x4A000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x08000000, 0x00200000, 0x00000000, 0x80000000, 0x00000100, 0x02002004, 0x20000000, 0x04000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00280000, 0x00000024, 0x00060000, 0x00000000, 0x00000000, 0x00000000, 0x00040001, 0x00000000, 0x04000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000080, 0x00000000, 0x00010000, 0x00000000, 0x00000000, 0x00480000, 0x00000040, 0x000080A0, 0x04000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x10000000, 0x01000002, 0x000A0000, 0x00000000, 0x00000100, 0x00400000, 0x00000004, 0x00020000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00010000, 0x00440000, 0x00004000, 0x00200000, 0x02000000, 0x80000000, 0x00800010, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x20404000, 0x08000100, 0x00100000, 0x80000000, 0x00000200, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00020000, 0x40000000, 0x40000040, 0x00002000, 0x00000000, 0x00300000, 0x80000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000001, 0x00000040, 0x00000000, 0x00000100, 0x00000000, 0x08000000, 0x00000000, 0x0C000002, 0x00000000, 0x00020000, 0x00000000 },
|
||||
{ 0x00010000, 0x00000010, 0x00000000, 0x00040000, 0x00400008, 0x00020000, 0x00000000, 0x00000000, 0x00020000, 0x00800000, 0x00000000, 0x00000000 },
|
||||
{ 0x02404000, 0x00000002, 0x04000000, 0x40000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x01000080, 0x00000000, 0x00000000 },
|
||||
{ 0x00002000, 0x00000000, 0x00010000, 0x00000000, 0x00000000, 0x10000000, 0x00020020, 0x00000100, 0x00000000, 0x10000000, 0x00000020, 0x00000000 },
|
||||
{ 0x00000880, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000100, 0x00080004, 0x00000000, 0x00080010, 0x00000000, 0x00800000, 0x00000000 },
|
||||
{ 0x00008070, 0x00000000, 0x00000002, 0x00000000, 0x00000008, 0x00000002, 0x00000000, 0x00000000, 0x00420000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000200, 0x00000008, 0x80000000, 0x80010000, 0x80400000, 0x00000000, 0x00010000, 0x00000004, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x03000000, 0x00020004, 0x22000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000020, 0x10000000, 0x00100000, 0x00000000 },
|
||||
{ 0x00141000, 0x00080000, 0x00000000, 0x00000000, 0x00000000, 0x80000000, 0x00000010, 0x00000000, 0x00020800, 0x00004000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00280000, 0x48000000, 0x80000080, 0x00000400, 0x00100100, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x24000800, 0x00001020, 0x00802000, 0x02000000, 0x00000000, 0x00002000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x40030010, 0x00000084, 0x00000002, 0x00000080, 0x00000000, 0x00000200, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00010000, 0x02120000, 0x00000000, 0x00004001, 0x00100000, 0x00000000, 0x00000001, 0x00000040, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x40800000, 0x002080A0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x20000000, 0x00820000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000080, 0x00003000, 0x00000000, 0x00000000, 0x00000000, 0x00800000, 0x00000000, 0x00200000, 0x00000800, 0x04000040, 0x00010200, 0x00000000 },
|
||||
{ 0x00000000, 0x00000100, 0x00000000, 0x00000000, 0x00000000, 0x00000010, 0x10000000, 0x42100010, 0x00100000, 0x00000020, 0x00400000, 0x00000000 },
|
||||
{ 0x04080004, 0x00102008, 0x00000400, 0x08000000, 0x00000000, 0x00000000, 0x00000020, 0x00000000, 0x00000000, 0x40000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000081, 0x00000008, 0x00000000, 0x00000002, 0x00000000, 0x00000020, 0x00000000, 0x00020400, 0x00140000, 0x00000001, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00088000, 0x00000000, 0x10040000, 0x00000000, 0x00000000, 0x02000010, 0x00000060, 0x10000000, 0x00000002 },
|
||||
{ 0x08000000, 0x00000000, 0x00000000, 0x00000800, 0x00000000, 0x10010000, 0x00050000, 0x00000000, 0x09000800, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00002008, 0x00000000, 0x02008080, 0x00004000, 0x00000000, 0x04020040, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00400000, 0x00200000, 0x00020000, 0x00000000, 0x00100000, 0x40000000, 0x00000000, 0x01080101, 0x00000000, 0x00000000 },
|
||||
{ 0x00000002, 0x00000000, 0x00068000, 0x08000000, 0x00000000, 0x00004042, 0x10000000, 0x00000000, 0x00000000, 0x00000000, 0x00000800, 0x00000000 },
|
||||
{ 0x00000000, 0x01400000, 0x02004000, 0x00000000, 0x00000020, 0x00000010, 0x00000000, 0x00001000, 0x00000200, 0x00000000, 0x80000080, 0x00000000 },
|
||||
{ 0x00000000, 0x62300000, 0x00000000, 0x00000200, 0x00000000, 0x00000000, 0x00000000, 0x00400000, 0x08800080, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x04000000, 0x000091A0, 0x02000000, 0x00200000, 0x00000000, 0x00000000, 0x00000000, 0x00000100, 0x00000000, 0x00200000, 0x00000000, 0x00000000 },
|
||||
{ 0x00730000, 0x00000040, 0x00000000, 0x00000000, 0x20000000, 0x04000000, 0x00000000, 0x00000000, 0x00000400, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000020, 0x00102000, 0x00202000, 0x00000000, 0x02000000, 0x08040010, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000100, 0x00400000, 0x00000201, 0x00000000, 0x02000200, 0x00000000, 0x00040000, 0x00001000, 0x00000010, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00008000, 0x00000000, 0x00000000, 0x00000000, 0x10100000, 0x00800000, 0x00008000, 0x00081008, 0x00200000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x40828000, 0x00800000, 0x00100000, 0x00120000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00008000, 0x00000000 },
|
||||
{ 0x80020000, 0x01100880, 0x00000000, 0x00000000, 0x00000000, 0x00100010, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000001, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000400, 0x08000000, 0x0000080A, 0x00000000, 0x00000200, 0x00020010, 0x04000000, 0x00000000 },
|
||||
{ 0x00800000, 0x00000000, 0x00000000, 0x06000000, 0x00010001, 0x00000800, 0x00000080, 0x00000000, 0x00000000, 0x08000000, 0x00000040, 0x00000000 },
|
||||
{ 0x00000000, 0x02200000, 0x00000000, 0x00008008, 0x00200000, 0x00000000, 0x00000000, 0x00004000, 0x00000000, 0x40000004, 0x00002000, 0x00000000 },
|
||||
{ 0x00800000, 0x00000000, 0x88000000, 0x84000000, 0x00040000, 0x00000000, 0x00000000, 0x00000000, 0x00800000, 0x00000000, 0x00014000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x40000001, 0x00040000, 0x00001000, 0x01200000, 0x02400004, 0x00000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00004808, 0x04000000, 0x00200000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00080000, 0x00080040, 0x00000040, 0x00000000, 0x00000000 },
|
||||
{ 0x00000310, 0x00002000, 0x00000000, 0x00800200, 0x00000000, 0x00010000, 0x00400000, 0x00000000, 0x01000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x0000100E, 0x00000018, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000002, 0x00000002, 0x00000000, 0x00000000, 0x00000002, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00820000, 0x00200100, 0x09000020, 0x00000800, 0x00000000, 0x00008000, 0x00000000, 0x00000000 },
|
||||
{ 0x08000000, 0x00000000, 0x02200000, 0x00001400, 0x80004000, 0x00000000, 0x00000004, 0x00000000, 0x00001000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00008000, 0x00000000, 0x01000000, 0x00000000, 0x20000080, 0x00000040, 0x10000000, 0x10000000, 0x00000000, 0x00000020, 0x00400000, 0x00000000 },
|
||||
{ 0x00000000, 0x40000080, 0x00020000, 0x00000000, 0x00001000, 0x00004000, 0x00000100, 0x20000000, 0x00000000, 0x00004000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00004800, 0x00000000, 0x04000800, 0x00000000, 0x00400000, 0x00000000, 0x00000000, 0x00000000, 0x00000010, 0x00400000, 0x00000001 },
|
||||
{ 0x00000000, 0x00040004, 0x00041000, 0x00000000, 0x00000008, 0x00000000, 0x00000024, 0x00000000, 0x00000000, 0x00000000, 0x00004000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x02000000, 0x00000000, 0x00040000, 0x00000000, 0x00100008, 0x00000000, 0x20000020, 0x08000040, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00001004, 0x00100000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00008000, 0x00804108, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x01010000, 0x00800000, 0x00001001, 0x00800000, 0x00000000, 0x00000000, 0x00240000, 0x00000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000200, 0x00000000, 0x00000000, 0x00002200, 0x00000002, 0x08200800, 0x00000001 },
|
||||
{ 0x00000000, 0x00000000, 0x00100000, 0x0000C000, 0x00804010, 0x00004000, 0x00000000, 0x00000000, 0x00000400, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x08000000, 0x00480000, 0x00008004, 0x00000000, 0x00040000, 0x00000000, 0x00000100, 0x00000000, 0x00000000, 0x10000000, 0x00000000, 0x00000000 },
|
||||
{ 0x08800000, 0x00040001, 0x00000000, 0x00000000, 0x00080080, 0x00000000, 0x04000000, 0x00000000, 0x04000000, 0x00000000, 0x00000000, 0x00000000 },
|
||||
{ 0x00003200, 0x00000000, 0x00000000, 0x00000000, 0x10420000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00002000, 0x00000400, 0x00000000 },
|
||||
{ 0x00000040, 0x00000000, 0x00000000, 0x00000004, 0x00000008, 0x00000000, 0x00000000, 0x00000000, 0x00000600, 0x00000000, 0x00004801, 0x00000000 },
|
||||
{ 0x00000020, 0x00000000, 0x00000410, 0x00000000, 0x00000004, 0x00000000, 0x00800000, 0x00000000, 0x00900000, 0x00000001, 0x00000000, 0x00000000 },
|
||||
{ 0x02000000, 0x00000000, 0x00000000, 0x00000000, 0x02000040, 0x00000000, 0x00000000, 0x00000000, 0x00840040, 0x00800000, 0x00000001, 0x00000000 },
|
||||
{ 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x44000800, 0x00000000, 0x08001000, 0x20001000, 0x00000000, 0x00000000, 0x00800000, 0x00000000 },
|
||||
{ 0x00000001, 0x00000000, 0x00000000, 0x00000880, 0x00000000, 0x00002000, 0x00000000, 0x00420000, 0x00040000, 0x00002020, 0x00000000, 0x00000000 },
|
||||
{ 0x00000010, 0x00000000, 0x00040000, 0x00000000, 0x20000000, 0x00040000, 0x01000000, 0x04000000, 0x00000000, 0x00000080, 0x00400000, 0x00000001 },
|
||||
{ 0x00000008, 0x00020000, 0x00000000, 0x00021000, 0x00000000, 0x00000000, 0x00000008, 0x00000000, 0x00080000, 0x00000210, 0x00000001, 0x00000000 },
|
||||
{ 0x0000000A, 0x00001080, 0x00000000, 0x00000000, 0x00004000, 0x00200004, 0x00000000, 0x00000000, 0x00008000, 0x00000004, 0x00000000, 0x00000000 },
|
||||
{ 0x00100082, 0x00000000, 0x20008000, 0x00000000, 0x00000000, 0x00004000, 0x00000800, 0x00000000, 0x00000000, 0x00001000, 0x00000000, 0x00000002 }
|
||||
} ;
|
||||
|
||||
const uint32_t LDPC_ParityGen_n354k160[194][5]
|
||||
#ifdef __AVR__
|
||||
PROGMEM
|
||||
#endif
|
||||
= { // parity bits generator
|
||||
{ 0xBF3B0B3C, 0x314E4CB2, 0x1C4219B8, 0xF87E8234, 0x6D121C05 },
|
||||
{ 0x43C31BD3, 0xA49EE0D2, 0xB613CA26, 0x4A06EB31, 0xBBBC4B69 },
|
||||
{ 0xA8E96C9C, 0x5C4BD117, 0x8877A3B7, 0x2C28FCBB, 0xC20F5C52 },
|
||||
{ 0x18E91F00, 0xABA26C2A, 0x20AFA0D3, 0x781A54FD, 0x7AAD3CD7 },
|
||||
{ 0xE2CE0C54, 0x0BBBE7EC, 0xBA8B6D72, 0x3CF41BBE, 0x9847B7BA },
|
||||
{ 0x2119517F, 0xDA38A438, 0x6A3A2341, 0x3C6B3CEE, 0xC45138E0 },
|
||||
{ 0xA03B5560, 0xB650F4D1, 0xF79542B5, 0x8B8A9EE2, 0x0008FAD3 },
|
||||
{ 0x5D2624EF, 0x10DBF749, 0x3CA1F2A0, 0x6EC49CB4, 0xE180DDB9 },
|
||||
{ 0xBFBC0710, 0xD0FA2A89, 0xFE1E22BF, 0x8DB41BAE, 0xE2A0DE6F },
|
||||
{ 0x7C97D8D6, 0xD03734C4, 0x3630E03C, 0xBC0E99D2, 0x5B1663C3 },
|
||||
{ 0xA8CB16AD, 0x006106C3, 0x64F41A4D, 0x98C281B0, 0x7E8055C4 },
|
||||
{ 0x8C2CD493, 0x2CD876DC, 0x00C39BE8, 0x0CC58836, 0xE9B55589 },
|
||||
{ 0x9ECCEF2A, 0xA648F8D7, 0xDB12CECF, 0xDECF8910, 0xFABA64FD },
|
||||
{ 0x2DD164C6, 0xE4E44F87, 0x425F5945, 0xEE48E56B, 0xE7F4349D },
|
||||
{ 0x5916345A, 0xDA049129, 0xCEEF739D, 0x47902FB7, 0x709F8AB4 },
|
||||
{ 0x987D6D27, 0x3448F4E7, 0x20DAF291, 0xF82BCE50, 0x8B591390 },
|
||||
{ 0x4DA99CD3, 0x1A13CC5E, 0xC3CE1A7E, 0xF460FD61, 0x8BA9FE66 },
|
||||
{ 0x72CED441, 0x90AAAB8D, 0xC48C6831, 0x9B52333B, 0xD835B6FC },
|
||||
{ 0x989EAEC0, 0xD9F69D6C, 0x66022DD7, 0x778FD6A5, 0x8B526FEE },
|
||||
{ 0x90861033, 0xCA18E3FB, 0x996E893B, 0x24185E8D, 0x3FD66C7C },
|
||||
{ 0xB8810387, 0x44833D00, 0xD0E0E7B3, 0xC4D91AA6, 0x6B5215F9 },
|
||||
{ 0x1FDA72C6, 0xCBD4BB6B, 0x04BE862D, 0xE1B9EA26, 0x30C01CA7 },
|
||||
{ 0xDAC99950, 0x66FC1E65, 0x734D0861, 0x8C4E7985, 0xBFCD3AD1 },
|
||||
{ 0x17BF566C, 0x26A04744, 0x2F60189D, 0x373BFCA1, 0xA08EBFF8 },
|
||||
{ 0x7EA9713E, 0x6A9A3324, 0x0E59E2A7, 0xCE7C57D0, 0xCBA40287 },
|
||||
{ 0xA442B46F, 0x182CFF0A, 0x9568B31D, 0x82015F2C, 0x4F3AB3A7 },
|
||||
{ 0x5965345A, 0xDA049169, 0xCEFF739D, 0x4790EFB7, 0x501FCAA4 },
|
||||
{ 0x5ACF0524, 0x09664861, 0xC26B69ED, 0x041EC4B6, 0xD3BE71E7 },
|
||||
{ 0xECEA5D89, 0x4C7AB36D, 0x9FA963C5, 0xFD416742, 0x1D331757 },
|
||||
{ 0x1256E1C1, 0x5C2D5E39, 0xFA349FC5, 0x98F81F1D, 0x4921E241 },
|
||||
{ 0x2AF78B26, 0xC3B88A6B, 0xE441147E, 0x68ED4E24, 0x2CD189AB },
|
||||
{ 0x899F3FCE, 0x74270F2B, 0x50C13F29, 0xD7359EEA, 0xDA12BA16 },
|
||||
{ 0x3F5A73D8, 0x71423A62, 0xD2957F27, 0xFE0F86A7, 0xAD98760B },
|
||||
{ 0x17E138A8, 0x77EA7AE4, 0xB08FEC00, 0xF51D5B10, 0x50616E89 },
|
||||
{ 0x9DEA1BA4, 0x864AA36F, 0x15AD6853, 0x4B734C20, 0xF2C935C0 },
|
||||
{ 0x1C61D24D, 0x36304D45, 0x6935994B, 0xCBB771C3, 0x74B76058 },
|
||||
{ 0x9C173562, 0xFF1735DA, 0x0C41BCB7, 0xC3195ADC, 0x60999718 },
|
||||
{ 0x30C81C35, 0x60EE7A6E, 0x9DFC8572, 0xBD28D328, 0xFCD88B0E },
|
||||
{ 0xECB8E63E, 0x8EA3EE2A, 0x61AE3F32, 0xB6B5E43C, 0xEA2DD6DE },
|
||||
{ 0x03219881, 0x126EA7A6, 0x6A130444, 0xA5313241, 0x5DD972B0 },
|
||||
{ 0xBCD7FF20, 0xB4C020BD, 0x9B77A60E, 0x91CA8631, 0xD7D1ACD2 },
|
||||
{ 0xFF80C91E, 0x5BCA2B6E, 0xF8D17E27, 0x770DC19A, 0xB1EEEDA0 },
|
||||
{ 0x7EF4C4F1, 0xC77292D4, 0x2E555DD7, 0x33DE6349, 0x6D79A577 },
|
||||
{ 0x89A41EFF, 0xE7455A6E, 0x4431B80C, 0xB47CB0B1, 0x7A2CD62A },
|
||||
{ 0x9F800F19, 0x2E497949, 0xD321D8DA, 0xF74C666B, 0x8EA103C2 },
|
||||
{ 0x46149176, 0xA17E679C, 0xC6481C0D, 0xBA6BA8B7, 0xDD9E0E80 },
|
||||
{ 0x5FE0198D, 0xE51C0C94, 0x80DA07B0, 0x8BCE8FAC, 0x119400C3 },
|
||||
{ 0x7D66BF7E, 0x75045431, 0x6927222B, 0x7FEF3B1C, 0xB2E5D39D },
|
||||
{ 0x7CB5D896, 0xF0373480, 0x3630E03D, 0xBC0E99D2, 0x5B1663C3 },
|
||||
{ 0x78DC56FF, 0x4967B31E, 0x06291302, 0xB3B4A072, 0x8BB88CEC },
|
||||
{ 0xA0354BC6, 0xD06A06D7, 0x4E724381, 0x3F07A3FD, 0x73AFE6FC },
|
||||
{ 0xF30D48DA, 0x676E5492, 0x177F288F, 0x79E936BC, 0x2016EAC9 },
|
||||
{ 0x8EF77970, 0xBD662325, 0x23C36963, 0xC4AA7264, 0x0A9BE530 },
|
||||
{ 0xFEF2A35E, 0x77C86351, 0x89A87585, 0x8F39F81C, 0xB3853AC4 },
|
||||
{ 0x5ACF0164, 0x0D664841, 0xCA6A69ED, 0x041EC4B6, 0xD3BE71A7 },
|
||||
{ 0xFC14B7B4, 0x4B5C63C5, 0xA72CC3B5, 0x6CD2FE00, 0x57EA6966 },
|
||||
{ 0x3E1E6D7B, 0x79532AE8, 0xA51A3C1B, 0xFC6FF9BD, 0x6BA67425 },
|
||||
{ 0x0E79995B, 0x843292F7, 0x382FEB26, 0x70CD2CB7, 0x7BF29FB1 },
|
||||
{ 0x6425F72F, 0xDFDC3624, 0xC593E31E, 0xE113249B, 0xB7490AFD },
|
||||
{ 0x5819FC79, 0x8A418AC9, 0xD1900B5E, 0xA01E332A, 0xE3937E73 },
|
||||
{ 0x0A475305, 0x7943BCA0, 0x666BBDE0, 0xF88290EA, 0x03436E21 },
|
||||
{ 0xEBD7D24F, 0x0ED6EC40, 0x169BF54D, 0x8F4C3C3A, 0xF288B858 },
|
||||
{ 0x15A1D5ED, 0x065B4DEE, 0xB7170FF2, 0xC110FFE6, 0x43DCAF43 },
|
||||
{ 0xF2717717, 0xD28DAD36, 0x43329E2C, 0xF244AB0A, 0x1D79E529 },
|
||||
{ 0x52FA7334, 0x7CF51534, 0xC14F1120, 0x0FB016BD, 0x11A8EDF7 },
|
||||
{ 0x63BBB512, 0xE79B813B, 0x8329901D, 0xB51B64C4, 0xE88F0253 },
|
||||
{ 0xB6BD7090, 0xF9DABA98, 0xFEFC792B, 0x0A9C05FC, 0xF3E5681E },
|
||||
{ 0xE3E8F94B, 0xB416DFF4, 0x18EA246F, 0xC4847023, 0x520C4290 },
|
||||
{ 0x9D999726, 0x6E454BA5, 0x424A1C3F, 0x9378A8C4, 0x3529A57B },
|
||||
{ 0xD96B5D54, 0xC0FDACD7, 0xC7BC13F2, 0x26604362, 0xB730C113 },
|
||||
{ 0x88F15CAA, 0xE33CD7A2, 0x6580C515, 0x4D51D804, 0x6E4D16DE },
|
||||
{ 0xACB34E0A, 0xACF46901, 0xD1E3790C, 0xCFB8150B, 0x1D24AFDF },
|
||||
{ 0xC15B49C8, 0x2493920E, 0x1EFB0A31, 0x96CF52E4, 0x6A59CC69 },
|
||||
{ 0x495A275D, 0x5B296FB3, 0x5F8FCA98, 0x79DF044F, 0xFFA075CB },
|
||||
{ 0xCB57CA6C, 0x96E56516, 0x34B373AB, 0x1DF6A1FF, 0x55FACA55 },
|
||||
{ 0xC3EB2B4E, 0x81752CE2, 0xE4A59F1A, 0x42091D75, 0xF68E15C8 },
|
||||
{ 0x3DAF86C3, 0xD6D9C19B, 0xC2A751E1, 0x79D118F4, 0xF122332C },
|
||||
{ 0xC1D1D970, 0x382D6985, 0x06B12543, 0x0C05211C, 0xEA714078 },
|
||||
{ 0x989EAEC0, 0xD9FE966C, 0x46022FDF, 0x778FD6A5, 0x8B526FEE },
|
||||
{ 0x5E3B9C7A, 0xED9ADFAF, 0x0F443C92, 0xFC855F78, 0xB1C61773 },
|
||||
{ 0x0EBF15FE, 0x1ECB1B82, 0x848E30D5, 0xE117B243, 0x6F3CE271 },
|
||||
{ 0x424E825C, 0x096A4205, 0xABF29FA4, 0x854E07BF, 0x5E998352 },
|
||||
{ 0xE0418B91, 0x4ADD50AC, 0x56511551, 0x0F0C7673, 0x821A3E84 },
|
||||
{ 0x267BDCEF, 0x04734BB4, 0xF7B4BC80, 0xCC12BA7D, 0x36C612CF },
|
||||
{ 0xC262CA37, 0x7E32C56F, 0x47845A47, 0xDF1B9BA8, 0xE0AFB8FC },
|
||||
{ 0xE0418B91, 0x4BDC50AC, 0x56D11551, 0x0F0C6672, 0x829A3E84 },
|
||||
{ 0x91F50DDE, 0x49E45E51, 0x6428D337, 0x31BCC161, 0x75402FCB },
|
||||
{ 0xB296A10D, 0xF646A5FD, 0x470B0F51, 0x1AFBB1A8, 0xDCE8A51D },
|
||||
{ 0x9848FB90, 0xDB688948, 0x8210D7E4, 0xC93EB1A8, 0x933FF050 },
|
||||
{ 0x79685C41, 0x18ED55A7, 0x6D742D4D, 0xD6B94C2D, 0xA4386DC9 },
|
||||
{ 0xB9E78046, 0xEF98DA9B, 0x74E74A58, 0xF9CCA0FB, 0xC6E7C152 },
|
||||
{ 0x1C42C120, 0x35F81A6E, 0xC633A9F9, 0x8F0AD0F1, 0xBB3588CF },
|
||||
{ 0x1B67E3ED, 0xAEFC3225, 0x85008317, 0x06AFE0B6, 0x632786BF },
|
||||
{ 0x2E623791, 0xDDA5B84C, 0x7531F094, 0x3CE5681A, 0x030D196C },
|
||||
{ 0x9659B78B, 0x6031178A, 0xDB017702, 0x5554FBCE, 0x33525AAC },
|
||||
{ 0x60B57C8B, 0x58A1BF6B, 0x57EE5D97, 0x6F976042, 0x43948F0A },
|
||||
{ 0x03220BC9, 0x2D105DCF, 0x1A2F231E, 0x14F15B28, 0x114227CB },
|
||||
{ 0xB388A264, 0x4A7D76C5, 0x6ABBF6D9, 0x5556254C, 0xEB7DF23E },
|
||||
{ 0x5DE9B360, 0x0C1008CC, 0xA7020795, 0x3A6C552C, 0x8AE262B6 },
|
||||
{ 0xEDCA5D89, 0x4D7AB36D, 0x9FA96BC5, 0xFD412746, 0x1D331757 },
|
||||
{ 0x20C00117, 0x75B2C4BC, 0x7DCBE920, 0x9CE9E0FE, 0xA6F64701 },
|
||||
{ 0xAFAED554, 0xB54C8CCC, 0xE8B0699F, 0xCDE94601, 0x1FF9AF34 },
|
||||
{ 0x684CC6F3, 0x90577B5A, 0x28F4656A, 0x90149AD1, 0x7D065F13 },
|
||||
{ 0xEA63020E, 0x10073485, 0xF7738AF7, 0xECD9DF63, 0xEF52967C },
|
||||
{ 0xF34D5BDA, 0x676E5492, 0x177B288F, 0x79E936BC, 0x2516EAC9 },
|
||||
{ 0x9ED015B6, 0xC305A3CA, 0xC5C5C293, 0x3F78BB2D, 0x45738306 },
|
||||
{ 0x5916345A, 0xDA049129, 0xCEFF739D, 0x4790EFB7, 0x701FCAA4 },
|
||||
{ 0x48E5557C, 0x3867D1E4, 0xA86F29E8, 0xC5FDC9F4, 0xD2765165 },
|
||||
{ 0x95EA1BA4, 0x864AA36F, 0x178D6853, 0x4B735820, 0x72C975C0 },
|
||||
{ 0xF554F1F1, 0x1214B399, 0x45C252C4, 0x3EBA532B, 0xCEC50308 },
|
||||
{ 0xC5B1C5CE, 0xD3F3540D, 0x63AA0659, 0xB3F95434, 0xF585E134 },
|
||||
{ 0xEC4D8B91, 0x4BDC50AC, 0x56D11551, 0x2E0C6672, 0x829A3B84 },
|
||||
{ 0xCF63E412, 0x12B15E91, 0x83051D0F, 0x9CC8BE39, 0x24814888 },
|
||||
{ 0x96DAB33B, 0x403EE24D, 0xD4448F71, 0x3B6ECC5E, 0xCCBE5361 },
|
||||
{ 0x05C2385B, 0x6C1EB2AD, 0x44E2D157, 0xAA4F2281, 0x36881398 },
|
||||
{ 0x25CF1FCB, 0xEB18939F, 0x3420F9B2, 0x31A1A463, 0x4D941996 },
|
||||
{ 0xE9588C02, 0x7BBCECFF, 0x7AA5B0E7, 0x7E5FE165, 0x9984E1B4 },
|
||||
{ 0xBC48FB90, 0xDB689948, 0x8610D7E4, 0xC83FB188, 0x933FF050 },
|
||||
{ 0xD5192898, 0xE4A0029F, 0x62574555, 0x7168276F, 0x77021800 },
|
||||
{ 0x51D69601, 0x62F5524B, 0x16B5D9BC, 0x624E462D, 0xAE500B1D },
|
||||
{ 0x17669EA7, 0x1775A41F, 0x09A47393, 0xF0FE3BD7, 0x58178FC1 },
|
||||
{ 0xEC304D69, 0x4D5E9089, 0x3A899E6C, 0xAE0DA801, 0xB394CF54 },
|
||||
{ 0x6CA5F72F, 0xDFD83625, 0xC593E31E, 0xE113249B, 0xB7410A7D },
|
||||
{ 0x2A4099D1, 0x5926389F, 0x85EE807C, 0xBF2B5A2F, 0x3442B2AA },
|
||||
{ 0x9565CA53, 0xEFB6F5B0, 0x9586A876, 0x3B85C5B5, 0x185F87B0 },
|
||||
{ 0x89F7CDEA, 0x2FFDECB4, 0xC191EC57, 0x964510D8, 0x23DD8018 },
|
||||
{ 0x48DC8D1F, 0x593EED5B, 0xA06A9AB7, 0x81AE548A, 0x5261DF4C },
|
||||
{ 0x0FF22560, 0xD10ADA44, 0x53081653, 0x7E5F18B1, 0xC5C1B2A5 },
|
||||
{ 0x449AAD97, 0x5215DD71, 0xCB3CAEFE, 0x70C35948, 0x603E83CB },
|
||||
{ 0x0FCF09D8, 0x502FD0D4, 0x0BD6ABE3, 0x7C2981A7, 0x69BB3DDA },
|
||||
{ 0x5B7E95C1, 0xDC432A50, 0xDA1830CB, 0xE39D70EF, 0x70553B71 },
|
||||
{ 0x80B7031D, 0x008ACF8A, 0xD6A52F6D, 0xA32E741A, 0x70F87C14 },
|
||||
{ 0xAD7EFC8C, 0x048C390D, 0xE2C42E23, 0x7A70EAAC, 0xE4FF9B20 },
|
||||
{ 0x04F750C8, 0x2EB3118A, 0xC3F13D99, 0xDF48E0AD, 0x28FF9F90 },
|
||||
{ 0x6BF84DDF, 0x7B3CA371, 0xEB402058, 0x6DA784CF, 0x0654544A },
|
||||
{ 0x68D02631, 0x2D4D0277, 0x26727DD6, 0x801214CA, 0x5D217B68 },
|
||||
{ 0x434C131D, 0x68A3DFAE, 0xB017E87F, 0xC7B52C91, 0x42EA8D0F },
|
||||
{ 0x4E9D3ED1, 0x978E35BB, 0xD5BAC41B, 0x78492E14, 0x2EC940AD },
|
||||
{ 0xF514F1F1, 0x9214B389, 0x45C252C4, 0x3EBA532B, 0xCEC5032E },
|
||||
{ 0x5B5F3E79, 0x2ABAB2F5, 0x084C4D5A, 0x31D688D0, 0xD54F32A1 },
|
||||
{ 0xC9D0422B, 0xF87EFB4B, 0x65C25674, 0xE9924A10, 0xD17731E8 },
|
||||
{ 0xFF5F83D6, 0xE6C7F0F4, 0x0A96F918, 0x2FBDE919, 0xD25A140C },
|
||||
{ 0xCBA3FCEB, 0xF3610958, 0x20AB2507, 0xEABFC19C, 0xA4432F0A },
|
||||
{ 0x3542D3AF, 0x09A7674F, 0xF77389BF, 0xCF5DF542, 0x50815658 },
|
||||
{ 0x0AF1DF54, 0xF80803CD, 0x3DA3F21D, 0x6084E0FC, 0x1F9EDFFB },
|
||||
{ 0x6DE2AA90, 0xBFE9A564, 0xD1798BB7, 0x367DEFBD, 0x3716658D },
|
||||
{ 0xB3CF1AD0, 0x55D872A7, 0x8F853289, 0xF2A83C7A, 0xF18EBF7A },
|
||||
{ 0x75E81640, 0xCAAC3405, 0xA1DB2536, 0xE6BAE8B9, 0x463ECA30 },
|
||||
{ 0x14B85EA7, 0xCB24075A, 0x03B2B4C3, 0x84A5CE08, 0xC31CC695 },
|
||||
{ 0xC55B49C8, 0x249303AE, 0x1CFB0A31, 0x96EF52E4, 0x6A59CC69 },
|
||||
{ 0x267531D5, 0xAD722E2B, 0xD0601DE1, 0x2B3DFDB4, 0x816EE75B },
|
||||
{ 0xE415677A, 0xD09449D0, 0x10C8E740, 0xA038FF65, 0x14CBE595 },
|
||||
{ 0x6A906631, 0x2D4D0275, 0x22727DD6, 0xC01214CA, 0x5D217B68 },
|
||||
{ 0xB31272C5, 0xC2594005, 0x94B83E46, 0x4D84ED27, 0xF23A67F3 },
|
||||
{ 0xB2BBF8A5, 0x36004598, 0x971E0455, 0x00BA60CE, 0x93B2D373 },
|
||||
{ 0xDF37FE5C, 0x6ADBAD69, 0x8A9755B8, 0x3916D1B1, 0x4458FE0E },
|
||||
{ 0xB4D7FF20, 0xB48820BD, 0x9B77260A, 0x91CA8631, 0xD7D5ACD2 },
|
||||
{ 0x5D3608F5, 0x436907F3, 0x4CD2CBAD, 0x84C5E362, 0xD1E7240D },
|
||||
{ 0x34C01C31, 0x60FE5A66, 0x9DFC8172, 0xB528D328, 0xFCD88B0E },
|
||||
{ 0x409562A7, 0x100957A1, 0x4526AC8B, 0xE7C47A53, 0xBD8B8ED5 },
|
||||
{ 0xDA4D0FD3, 0x4E28D26C, 0x6A6B8AC1, 0xF82D0118, 0xF315A243 },
|
||||
{ 0x745A9DB4, 0x9071FBC7, 0x33A67C1D, 0x40063FD4, 0xB8EE6CDA },
|
||||
{ 0x85A1E2B5, 0x0267BB1F, 0x436DAAF0, 0x65D3EF48, 0xFA1CF504 },
|
||||
{ 0x247CD0D8, 0x64165577, 0xEE6ACDD4, 0x9C0CBD01, 0x958A76A1 },
|
||||
{ 0xC5B5C5CE, 0xD373540C, 0x63AA05D9, 0xB3E95434, 0xF185E134 },
|
||||
{ 0xD17281AB, 0xF5E8C8AE, 0x81F1D98E, 0xF4D8C0CD, 0xD7DF700E },
|
||||
{ 0x50BAB24E, 0x546D7C13, 0xE047CA14, 0x96E26BC6, 0xF035D936 },
|
||||
{ 0xD872A27F, 0xEE03F33C, 0x8EBC2CC6, 0x8A82CD68, 0x964A6E4E },
|
||||
{ 0x629516BC, 0xF182D7B1, 0x4760C49C, 0xF069128A, 0x19CEC52F },
|
||||
{ 0x9A2CACEB, 0x9C729BAB, 0xBB6024B4, 0x80C26E03, 0xC5C1E2FB },
|
||||
{ 0xFF5FB1D6, 0xE6C7F0F4, 0x0A96F918, 0x2FBDE919, 0xC218140C },
|
||||
{ 0xB0A929EE, 0xB189398A, 0xE904C6EE, 0x769ECA8E, 0xC868552F },
|
||||
{ 0xEF4D67E1, 0x3F7A8BF3, 0x7B4686D9, 0x2E4918B4, 0x88E76F5A },
|
||||
{ 0xF7202730, 0x6763E65A, 0x01E69E66, 0x213AF56A, 0x07FFDF91 },
|
||||
{ 0xAD220791, 0xE6A0D905, 0x8855FD21, 0xF65B9F08, 0x0E11BEC6 },
|
||||
{ 0xCA4FD7C6, 0xD429968D, 0x54EE0F82, 0x5F0B299D, 0xB377A305 },
|
||||
{ 0xFC749190, 0x84558B4E, 0x16E0249D, 0x1015D925, 0xA045B5DB },
|
||||
{ 0xAD7430E3, 0x46C2F2B7, 0xFB569EA5, 0xAB7068D2, 0x8BED359A },
|
||||
{ 0xC2421229, 0xBD61DCB7, 0xDBB300AA, 0x1450F14E, 0xE8B7317D },
|
||||
{ 0x4E9E2248, 0x4A44E893, 0x95B0CC28, 0x94FE53F8, 0x2997B8AF },
|
||||
{ 0x18792A74, 0x01C6AC75, 0x51C74F95, 0x5C23C030, 0xC82C03E6 },
|
||||
{ 0xE6E4579F, 0x4BE76A10, 0x46CE12AC, 0xA4D9E3E7, 0xB01B9244 },
|
||||
{ 0xB5EC3540, 0x4F5C6BDE, 0xD60F41DB, 0xAAEF0E13, 0x68938D5D },
|
||||
{ 0xD4544232, 0xAF748A57, 0xB52772F1, 0x126625AF, 0xDB1D5FF1 },
|
||||
{ 0x1E623791, 0xD9A7B84C, 0x7531F094, 0x3CE5689A, 0x034D096C },
|
||||
{ 0x55A90C45, 0x2C89BE82, 0x51B53A53, 0xDD30D5DB, 0x950D788D },
|
||||
{ 0x86A7B294, 0xD7991A0D, 0xA998C3AD, 0xFDBDE0E8, 0x1BDED0B7 },
|
||||
{ 0x8CCA1BA4, 0x864BA36F, 0x55AD6853, 0x4B734C20, 0xF2C935D0 },
|
||||
{ 0xCEF9CA2C, 0x3DD0F8C3, 0x5944397A, 0x10B3C86C, 0x766C5640 },
|
||||
{ 0x9D48FDB5, 0xA9C5D735, 0x63C23A23, 0x1DC99B85, 0x90B1C1D3 },
|
||||
{ 0xA48DEE95, 0x9782ABB5, 0x422ED881, 0x1F657314, 0x289FA398 },
|
||||
{ 0x99C33D5E, 0xF1247681, 0x315592C6, 0xF0DF750F, 0xBA5C69FE },
|
||||
{ 0xC25B509C, 0x2D2C04B6, 0x47866799, 0x58D1953A, 0x33A12CAC },
|
||||
{ 0x1972680C, 0xC53F300C, 0xCF1C1DE5, 0x1A7ED516, 0xDBC46D76 }
|
||||
} ;
|
||||
|
||||
#endif // WITH_PPM
|
||||
|
||||
// ===================================================================================================================
|
||||
|
||||
#ifdef __AVR__
|
||||
|
||||
// encode Parity from Data: Data is 5x 32-bit words = 160 bits, Parity is 1.5x 32-bit word = 48 bits
|
||||
void LDPC_Encode(const uint32_t *Data, uint32_t *Parity, const uint32_t ParityGen[48][5])
|
||||
{ uint8_t ParIdx=0; Parity[ParIdx]=0; uint32_t Mask=1;
|
||||
for(uint8_t Row=0; Row<48; Row++)
|
||||
{ uint8_t Count=0;
|
||||
const uint32_t *Gen=ParityGen[Row];
|
||||
for(uint8_t Idx=0; Idx<5; Idx++)
|
||||
{ Count+=Count1s(Data[Idx]&pgm_read_dword(Gen+Idx)); }
|
||||
if(Count&1) Parity[ParIdx]|=Mask; Mask<<=1;
|
||||
if(Mask==0) { ParIdx++; Parity[ParIdx]=0; Mask=1; }
|
||||
}
|
||||
}
|
||||
|
||||
void LDPC_Encode(const uint32_t *Data, uint32_t *Parity)
|
||||
{ LDPC_Encode(Data, Parity, LDPC_ParityGen); }
|
||||
|
||||
// encode Parity from Data: Data is 20 bytes = 160 bits, Parity is 6 bytes = 48 bits
|
||||
void LDPC_Encode(const uint8_t *Data, uint8_t *Parity, const uint32_t ParityGen[48][5])
|
||||
{ uint8_t ParIdx=0; Parity[ParIdx]=0; uint8_t Mask=1;
|
||||
for(uint8_t Row=0; Row<48; Row++)
|
||||
{ uint8_t Count=0;
|
||||
const uint8_t *Gen = (uint8_t *)ParityGen[Row];
|
||||
for(uint8_t Idx=0; Idx<20; Idx++)
|
||||
{ Count+=Count1s(Data[Idx]&pgm_read_byte(Gen+Idx)); }
|
||||
if(Count&1) Parity[ParIdx]|=Mask; Mask<<=1;
|
||||
if(Mask==0) { ParIdx++; Parity[ParIdx]=0; Mask=1; }
|
||||
}
|
||||
}
|
||||
|
||||
void LDPC_Encode(const uint8_t *Data, uint8_t *Parity)
|
||||
{ LDPC_Encode(Data, Parity, LDPC_ParityGen); }
|
||||
|
||||
void LDPC_Encode(uint8_t *Data)
|
||||
{ LDPC_Encode(Data, Data+20, LDPC_ParityGen); }
|
||||
|
||||
// check Data against Parity (run 48 parity checks) - return number of failed checks
|
||||
int8_t LDPC_Check(const uint8_t *Data) // 20 data bytes followed by 6 parity bytes
|
||||
{ uint8_t Errors=0;
|
||||
for(uint8_t Row=0; Row<48; Row++)
|
||||
{ uint8_t Count=0;
|
||||
const uint8_t *Check = (uint8_t *)LDPC_ParityCheck[Row];
|
||||
for(uint8_t Idx=0; Idx<26; Idx++)
|
||||
{ Count+=Count1s(Data[Idx] & pgm_read_byte(Check+Idx)); }
|
||||
if(Count&1) Errors++; }
|
||||
return Errors; }
|
||||
|
||||
int8_t LDPC_Check(const uint32_t *Packet)
|
||||
{ return LDPC_Check( (uint8_t *)Packet ); }
|
||||
|
||||
#else // if not 8-bit AVR
|
||||
|
||||
void LDPC_Encode(const uint8_t *Data, uint8_t *Parity, const uint32_t ParityGen[48][5])
|
||||
{ uint8_t ParIdx=0; uint8_t ParByte=0; uint8_t Mask=1;
|
||||
for(uint8_t Row=0; Row<48; Row++)
|
||||
{ uint8_t Count=0;
|
||||
const uint8_t *Gen = (uint8_t *)(ParityGen[Row]);
|
||||
for(uint8_t Idx=0; Idx<20; Idx++)
|
||||
{ Count+=Count1s((uint8_t)(Data[Idx]&Gen[Idx])); }
|
||||
if(Count&1) ParByte|=Mask; Mask<<=1;
|
||||
if(Mask==0) { Parity[ParIdx++]=ParByte; Mask=1; ParByte=0; }
|
||||
}
|
||||
// if(Mask!=1) Parity[ParIdx]=ParByte;
|
||||
}
|
||||
|
||||
void LDPC_Encode(const uint8_t *Data, uint8_t *Parity)
|
||||
{ LDPC_Encode(Data, Parity, LDPC_ParityGen_n208k160); }
|
||||
|
||||
void LDPC_Encode(uint8_t *Data)
|
||||
{ LDPC_Encode(Data, Data+20); }
|
||||
|
||||
// encode Parity from Data: Data is 5x 32-bit words = 160 bits, Parity is 1.5x 32-bit word = 48 bits
|
||||
static void LDPC_Encode(const uint32_t *Data, uint32_t *Parity, uint8_t DataWords, uint8_t Checks, const uint32_t *ParityGen)
|
||||
{ // printf("LDPC_Encode: %08X %08X %08X %08X %08X", Data[0], Data[1], Data[2], Data[3], Data[4] );
|
||||
uint8_t ParIdx=0; Parity[ParIdx]=0; uint32_t Mask=1;
|
||||
const uint32_t *Gen=ParityGen;
|
||||
for(uint8_t Row=0; Row<Checks; Row++)
|
||||
{ uint8_t Count=0;
|
||||
for(uint8_t Idx=0; Idx<DataWords; Idx++)
|
||||
{ Count+=Count1s(Data[Idx]&Gen[Idx]); }
|
||||
if(Count&1) Parity[ParIdx]|=Mask; Mask<<=1;
|
||||
if(Mask==0) { ParIdx++; Parity[ParIdx]=0; Mask=1; }
|
||||
Gen+=DataWords; }
|
||||
// printf(" => %08X %08X\n", Parity[0], Parity[1] );
|
||||
}
|
||||
|
||||
void LDPC_Encode(const uint32_t *Data, uint32_t *Parity) { LDPC_Encode(Data, Parity, 5, 48, (uint32_t *)LDPC_ParityGen_n208k160); }
|
||||
void LDPC_Encode( uint32_t *Data) { LDPC_Encode(Data, Data+5, 5, 48, (uint32_t *)LDPC_ParityGen_n208k160); }
|
||||
|
||||
#ifdef WITH_PPM
|
||||
void LDPC_Encode_n354k160(const uint32_t *Data, uint32_t *Parity) { LDPC_Encode(Data, Parity, 5, 194, (uint32_t *)LDPC_ParityGen_n354k160); }
|
||||
void LDPC_Encode_n354k160( uint32_t *Data) { LDPC_Encode(Data, Data+5, 5, 194, (uint32_t *)LDPC_ParityGen_n354k160); }
|
||||
#endif
|
||||
|
||||
// check Data against Parity (run 48 parity checks) - return number of failed checks
|
||||
uint8_t LDPC_Check(const uint32_t *Data, const uint32_t *Parity) // Data and Parity are 32-bit words
|
||||
{ uint8_t Errors=0;
|
||||
for(uint8_t Row=0; Row<48; Row++)
|
||||
{ uint8_t Count=0;
|
||||
const uint32_t *Check=LDPC_ParityCheck_n208k160[Row];
|
||||
uint8_t Idx;
|
||||
for(Idx=0; Idx<5; Idx++)
|
||||
{ Count+=Count1s(Data[Idx]&Check[Idx]); }
|
||||
Count+=Count1s(Parity[0]&Check[Idx++]);
|
||||
Count+=Count1s((Parity[1]&Check[Idx++])&0xFFFF);
|
||||
if(Count&1) Errors++; }
|
||||
return Errors; }
|
||||
|
||||
uint8_t LDPC_Check(const uint32_t *Data) { return LDPC_Check(Data, Data+5); }
|
||||
|
||||
uint8_t LDPC_Check(const uint8_t *Data) // 20 data bytes followed by 6 parity bytes
|
||||
{ uint8_t Errors=0;
|
||||
for(uint8_t Row=0; Row<48; Row++)
|
||||
{ uint8_t Count=0;
|
||||
const uint8_t *Check = (uint8_t *)LDPC_ParityCheck_n208k160[Row];
|
||||
for(uint8_t Idx=0; Idx<26; Idx++)
|
||||
{ uint8_t And = Data[Idx]&Check[Idx]; Count+=Count1s(And); }
|
||||
if(Count&1) Errors++; }
|
||||
return Errors; }
|
||||
#ifdef WITH_PPM
|
||||
uint8_t LDPC_Check_n354k160(const uint32_t *Data, const uint32_t *Parity) // Data and Parity are 32-bit words
|
||||
{ uint8_t Errors=0;
|
||||
for(uint8_t Row=0; Row<194; Row++)
|
||||
{ uint8_t Count=0;
|
||||
const uint32_t *Check=LDPC_ParityCheck_n354k160[Row];
|
||||
uint8_t Idx;
|
||||
for(Idx=0; Idx<5; Idx++)
|
||||
{ Count+=Count1s(Data[Idx]&Check[Idx]); }
|
||||
uint8_t ParIdx;
|
||||
for(ParIdx=0; ParIdx<6; ParIdx++, Idx++)
|
||||
{ Count+=Count1s(Parity[ParIdx]&Check[Idx]); }
|
||||
Count+=Count1s((Parity[ParIdx]&Check[Idx])&0x0003);
|
||||
if(Count&1) Errors++; }
|
||||
return Errors; }
|
||||
|
||||
uint8_t LDPC_Check_n354k160(const uint32_t *Data) { return LDPC_Check_n354k160(Data, Data+5); }
|
||||
#endif // WITH_PPM
|
||||
|
||||
#endif // __AVR__
|
||||
|
|
@ -0,0 +1,425 @@
|
|||
#ifndef __LDPC_H__
|
||||
#define __LDPC_H__
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <limits>
|
||||
|
||||
#include "bitcount.h"
|
||||
|
||||
#ifndef __AVR__
|
||||
// #include <stdio.h>
|
||||
#include <math.h>
|
||||
#endif
|
||||
|
||||
#ifdef __AVR__
|
||||
#include <avr/pgmspace.h>
|
||||
#endif
|
||||
|
||||
// extern const uint32_t LDPC_ParityGen_n208k160[48][5];
|
||||
// extern const uint32_t LDPC_ParityCheck_n208k160[48][7];
|
||||
// extern const uint8_t LDPC_ParityCheckIndex_n208k160[48][24];
|
||||
// extern const uint8_t LDPC_BitWeight_n208k160[208];
|
||||
#ifdef WITH_PPM
|
||||
extern const uint32_t LDPC_ParityGen_n354k160[194][5];
|
||||
extern const uint32_t LDPC_ParityCheck_n354k160[194][12];
|
||||
#endif
|
||||
|
||||
#ifdef __AVR__
|
||||
|
||||
// encode Parity from Data: Data is 5x 32-bit words = 160 bits, Parity is 1.5x 32-bit word = 48 bits
|
||||
void LDPC_Encode(const uint32_t *Data, uint32_t *Parity, const uint32_t ParityGen[48][5]);
|
||||
void LDPC_Encode(const uint32_t *Data, uint32_t *Parity);
|
||||
|
||||
// encode Parity from Data: Data is 20 bytes = 160 bits, Parity is 6 bytes = 48 bits
|
||||
void LDPC_Encode(const uint8_t *Data, uint8_t *Parity, const uint32_t ParityGen[48][5]);
|
||||
void LDPC_Encode(const uint8_t *Data, uint8_t *Parity);
|
||||
void LDPC_Encode( uint8_t *Data);
|
||||
// check Data against Parity (run 48 parity checks) - return number of failed checks
|
||||
uint8_t LDPC_Check(const uint8_t *Data); // 20 data bytes followed by 6 parity bytes
|
||||
uint8_t LDPC_Check(const uint32_t *Packet);
|
||||
|
||||
#else // if not 8-bit AVR
|
||||
|
||||
void LDPC_Encode(const uint8_t *Data, uint8_t *Parity, const uint32_t ParityGen[48][5]);
|
||||
void LDPC_Encode(const uint8_t *Data, uint8_t *Parity);
|
||||
void LDPC_Encode( uint8_t *Data);
|
||||
// encode Parity from Data: Data is 5x 32-bit words = 160 bits, Parity is 1.5x 32-bit word = 48 bits
|
||||
// void LDPC_Encode(const uint32_t *Data, uint32_t *Parity, const uint32_t ParityGen[48][5]);
|
||||
|
||||
// void LDPC_Encode(const uint32_t *Data, uint32_t *Parity, uint8_t DataWords, uint8_t Checks, const uint32_t *ParityGen);
|
||||
// inline void LDPC_Encode(const uint32_t *Data, uint32_t *Parity) { LDPC_Encode(Data, Parity, 5, 48, (uint32_t *)LDPC_ParityGen_n208k160); }
|
||||
// inline void LDPC_Encode( uint32_t *Data) { LDPC_Encode(Data, Data+5, 5, 48, (uint32_t *)LDPC_ParityGen_n208k160); }
|
||||
// inline void LDPC_Encode_n394k160(const uint32_t *Data, uint32_t *Parity) { LDPC_Encode(Data, Parity, 5, 194, (uint32_t *)LDPC_ParityGen_n354k160); }
|
||||
// inline void LDPC_Encode_n394k160( uint32_t *Data) { LDPC_Encode(Data, Data+5, 5, 194, (uint32_t *)LDPC_ParityGen_n354k160); }
|
||||
|
||||
void LDPC_Encode(const uint32_t *Data, uint32_t *Parity);
|
||||
void LDPC_Encode( uint32_t *Data);
|
||||
#ifdef WITH_PPM
|
||||
void LDPC_Encode_n354k160(const uint32_t *Data, uint32_t *Parity);
|
||||
void LDPC_Encode_n354k160( uint32_t *Data);
|
||||
#endif
|
||||
// check Data against Parity (run 48 parity checks) - return number of failed checks
|
||||
uint8_t LDPC_Check(const uint32_t *Data, const uint32_t *Parity); // Data and Parity are 32-bit words
|
||||
uint8_t LDPC_Check(const uint32_t *Data);
|
||||
uint8_t LDPC_Check(const uint8_t *Data); // 20 data bytes followed by 6 parity bytes
|
||||
#ifdef WITH_PPM
|
||||
uint8_t LDPC_Check_n354k160(const uint32_t *Data, const uint32_t *Parity); // Data and Parity are 32-bit words
|
||||
uint8_t LDPC_Check_n354k160(const uint32_t *Data);
|
||||
#endif
|
||||
|
||||
#endif // __AVR__
|
||||
|
||||
#ifndef __AVR__
|
||||
|
||||
extern const uint8_t LDPC_ParityCheckIndex_n208k160[48][24];
|
||||
|
||||
class LDPC_Decoder
|
||||
{ public:
|
||||
const static uint8_t UserBits = 160; // 5 32-bit bits = 20 bytes
|
||||
const static uint8_t UserWords = UserBits/32;
|
||||
const static uint8_t ParityBits = 48; // 6 bytes (total packet is 26 bytes)
|
||||
const static uint8_t CodeBits = UserBits+ParityBits; // 160+48 = 208 code bits = 26 bytes
|
||||
const static uint8_t CodeBytes = (CodeBits+ 7)/ 8; //
|
||||
const static uint8_t CodeWords = (CodeBits+31)/32; //
|
||||
const static uint8_t MaxCheckWeight = 24;
|
||||
// const static uint8_t MaxBitWeight = 8;
|
||||
|
||||
public:
|
||||
|
||||
int16_t InpBit[CodeBits]; // a-priori bits
|
||||
int16_t ExtBit[CodeBits]; // extrinsic inf.
|
||||
int16_t OutBit[CodeBits]; // a-posteriori bits
|
||||
|
||||
void Input(const uint8_t *Data, const uint8_t *Err)
|
||||
{ uint8_t Mask=1; uint8_t Idx=0; uint8_t DataByte=0; uint8_t ErrByte=0;
|
||||
for(uint8_t Bit=0; Bit<CodeBits; Bit++)
|
||||
{ if(Mask==1) { DataByte=Data[Idx]; ErrByte=Err[Idx]; }
|
||||
int16_t Inp;
|
||||
if(ErrByte&Mask) Inp=0;
|
||||
else Inp=(DataByte&Mask) ? +128:-128;
|
||||
OutBit[Bit] = InpBit[Bit] = Inp; ExtBit[Bit]=0;
|
||||
Mask<<=1; if(Mask==0) { Idx++; Mask=1; }
|
||||
}
|
||||
}
|
||||
|
||||
void Input(const uint32_t Data[CodeWords])
|
||||
{ uint32_t Mask=1; uint8_t Idx=0; uint32_t Word=Data[Idx];
|
||||
for(uint8_t Bit=0; Bit<CodeBits; Bit++)
|
||||
{ OutBit[Bit] = InpBit[Bit] = (Word&Mask) ? +128:-128;
|
||||
ExtBit[Bit]=0;
|
||||
Mask<<=1; if(Mask==0) { Word=Data[++Idx]; Mask=1; }
|
||||
}
|
||||
}
|
||||
|
||||
void Input(const float *Data, float RefAmpl=1.0)
|
||||
{ for(int Bit=0; Bit<CodeBits; Bit++)
|
||||
{ int Inp = floor(128*Data[Bit^7]/RefAmpl+0.5);
|
||||
if(Inp>32767) Inp=32767; else if(Inp<(-32767)) Inp=(-32767);
|
||||
OutBit[Bit] = InpBit[Bit] = Inp;
|
||||
ExtBit[Bit]=0; }
|
||||
}
|
||||
|
||||
void Output(uint32_t Data[CodeWords])
|
||||
{ uint32_t Mask=1; uint8_t Idx=0; uint32_t Word=0;
|
||||
for(uint8_t Bit=0; Bit<CodeBits; Bit++)
|
||||
{ if(OutBit[Bit]>0) Word|=Mask;
|
||||
Mask<<=1; if(Mask==0) { Data[Idx++]=Word; Word=0; Mask=1; }
|
||||
} if(Mask>1) Data[Idx++]=Word;
|
||||
}
|
||||
|
||||
void Output(uint8_t Data[CodeBytes])
|
||||
{ uint8_t Mask=1; uint8_t Idx=0; uint8_t Byte=0;
|
||||
for(uint8_t Bit=0; Bit<CodeBits; Bit++)
|
||||
{ if(OutBit[Bit]>0) Byte|=Mask;
|
||||
Mask<<=1; if(Mask==0) { Data[Idx++]=Byte; Byte=0; Mask=1; }
|
||||
} if(Mask>1) Data[Idx++]=Byte;
|
||||
}
|
||||
|
||||
int8_t ProcessChecks(void)
|
||||
{ for(uint8_t Bit=0; Bit<CodeBits; Bit++)
|
||||
ExtBit[Bit]=0;
|
||||
uint8_t Count=0;
|
||||
for(uint8_t Row=0; Row<ParityBits; Row++)
|
||||
{ int16_t Ret=ProcessCheck(Row);
|
||||
if(Ret<=0) Count++; }
|
||||
// printf("%d parity checks fail\n", Count);
|
||||
if(Count==0) return 0;
|
||||
for(uint8_t Bit=0; Bit<CodeBits; Bit++)
|
||||
{ OutBit[Bit] = InpBit[Bit] + (ExtBit[Bit]>>1); }
|
||||
return Count; }
|
||||
|
||||
int16_t ProcessCheck(uint8_t Row)
|
||||
{ int16_t MinAmpl=32767; uint8_t MinBit=0; int16_t MinAmpl2=MinAmpl;
|
||||
uint32_t Word=0; uint32_t Mask=1;
|
||||
const uint8_t *CheckIndex = LDPC_ParityCheckIndex_n208k160[Row];
|
||||
uint8_t CheckWeight = *CheckIndex++;
|
||||
for(uint8_t Bit=0; Bit<CheckWeight; Bit++)
|
||||
{ uint8_t BitIdx=CheckIndex[Bit];
|
||||
int16_t Ampl=OutBit[BitIdx];
|
||||
if(Ampl>0) Word|=Mask;
|
||||
Mask<<=1;
|
||||
if(Ampl<0) Ampl=(-Ampl);
|
||||
if(Ampl<MinAmpl) { MinAmpl2=MinAmpl; MinAmpl=Ampl; MinBit=Bit; }
|
||||
else if(Ampl<MinAmpl2) { MinAmpl2=Ampl; }
|
||||
}
|
||||
uint8_t CheckFails = Count1s(Word)&1;
|
||||
Mask=1;
|
||||
for(uint8_t Bit=0; Bit<CheckWeight; Bit++)
|
||||
{ uint8_t BitIdx=CheckIndex[Bit];
|
||||
int16_t Ampl = Bit==MinBit ? MinAmpl2 : MinAmpl;
|
||||
if(CheckFails) Ampl=(-Ampl);
|
||||
ExtBit[BitIdx] += (Word&Mask) ? Ampl:-Ampl;
|
||||
Mask<<=1; }
|
||||
return CheckFails?-MinAmpl:MinAmpl; }
|
||||
|
||||
} ;
|
||||
|
||||
template <class Float=float>
|
||||
class LDPC_FloatDecoder
|
||||
{ public:
|
||||
|
||||
const static int MaxCodeBits=512;
|
||||
const static int MaxParityBits=256;
|
||||
const static int MaxParityWeight=32; //
|
||||
int CodeBits; // number of code bits
|
||||
int ParityBits; // number of parity bits
|
||||
uint16_t ParityCheckIndex[MaxParityBits][MaxParityWeight]; // list of 1's in the ParityCheck matrix
|
||||
uint8_t ParityCheckRowWeight[MaxParityBits]; // number of 1's in ParityCheck rows
|
||||
uint8_t ParityCheckColWeight[MaxCodeBits]; // number of 1's in ParityCheck columns
|
||||
|
||||
Float InpBit[MaxCodeBits]; // a-priori bits
|
||||
Float ExtBit[MaxCodeBits]; // extrinsic inf.
|
||||
Float OutBit[MaxCodeBits]; // a-posteriori bits
|
||||
Float Feedback;
|
||||
|
||||
public:
|
||||
|
||||
LDPC_FloatDecoder()
|
||||
{ CodeBits=0; ParityBits=0; Feedback=0.33; }
|
||||
|
||||
void Clear(void)
|
||||
{ for(int Bit=0; Bit<CodeBits; Bit++)
|
||||
{ OutBit[Bit] = InpBit[Bit] = ExtBit[Bit]=0; }
|
||||
}
|
||||
|
||||
int Configure(int NewCodeBits, int NewParityBits, const uint32_t *PackedParityCheck )
|
||||
{ if(CodeBits>MaxCodeBits) return -1;
|
||||
CodeBits=NewCodeBits;
|
||||
if(ParityBits>MaxParityBits) return -1;
|
||||
ParityBits=NewParityBits;
|
||||
for(int Bit=0; Bit<CodeBits; Bit++)
|
||||
ParityCheckColWeight[Bit]=0;
|
||||
const uint32_t *Check=PackedParityCheck;
|
||||
for(int ParBit=0; ParBit<ParityBits; ParBit++)
|
||||
{ int RowWeight=0;
|
||||
uint32_t Word=0; uint32_t Mask=0;
|
||||
for(int Bit=0; Bit<CodeBits; Bit++)
|
||||
{ if(Mask==0) { Mask=1; Word=(*Check++); }
|
||||
if(Word&Mask)
|
||||
{ ParityCheckIndex[ParBit][RowWeight++]=Bit;
|
||||
ParityCheckColWeight[Bit]++; }
|
||||
Mask<<=1;
|
||||
}
|
||||
ParityCheckRowWeight[ParBit]=RowWeight;
|
||||
}
|
||||
return 1; }
|
||||
|
||||
void PrintConfig(void) const
|
||||
{ printf("LDPC_FloatDecoder[%d,%d] Check index table:\n", CodeBits, ParityBits);
|
||||
for(int ParBit=0; ParBit<ParityBits; ParBit++)
|
||||
{ printf("Check[%3d]:", ParityCheckRowWeight[ParBit]);
|
||||
for(int Bit=0; Bit<ParityCheckRowWeight[ParBit]; Bit++)
|
||||
{ printf(" %3d", ParityCheckIndex[ParBit][Bit]); }
|
||||
printf("\n");
|
||||
}
|
||||
printf("ColWeight[%d]:\n", CodeBits);
|
||||
int Bit;
|
||||
for(Bit=0; Bit<CodeBits; Bit++)
|
||||
{ if((Bit&0x1F)==0x00) printf("%03d:", Bit);
|
||||
printf(" %d", ParityCheckColWeight[Bit]);
|
||||
if((Bit&0x1F)==0x1F) printf("\n"); }
|
||||
if((Bit&0x1F)!=0x00) printf("\n");
|
||||
}
|
||||
|
||||
void PrintOutBits(void)
|
||||
{ printf("OutBit[%d]\n", CodeBits);
|
||||
for(int Bit=0; Bit<CodeBits; Bit++)
|
||||
{ if((Bit&0xF)==0x0) printf("%03d:", Bit);
|
||||
printf(" %+6.3f", OutBit[Bit]);
|
||||
if((Bit&0xF)==0xF) printf("\n"); }
|
||||
}
|
||||
|
||||
void addInput(int Bit, Float Ampl)
|
||||
{ InpBit[Bit]+=Ampl; OutBit[Bit] = InpBit[Bit]; }
|
||||
|
||||
void Input(const uint8_t *Data, const uint8_t *Err, Float Ampl=1.0) // get bits from series of bytes and the error pattern (from Manchester decoder)
|
||||
{ uint8_t Mask=1; int Idx=0; uint8_t DataByte=0; uint8_t ErrByte=0;
|
||||
for(int Bit=0; Bit<CodeBits; Bit++)
|
||||
{ if(Mask==1) { DataByte=Data[Idx]; ErrByte=Err[Idx]; }
|
||||
Float Inp;
|
||||
if(ErrByte&Mask) Inp=0;
|
||||
else Inp=(DataByte&Mask) ? +Ampl:-Ampl;
|
||||
OutBit[Bit] = InpBit[Bit] = Inp; ExtBit[Bit]=0;
|
||||
Mask<<=1; if(Mask==0) { Idx++; Mask=1; }
|
||||
}
|
||||
}
|
||||
|
||||
void Input(const uint32_t *Data, Float Ampl=1.0) // get bits from a series of 32-bit words
|
||||
{ uint32_t Mask=0; int Idx=0; uint32_t Word=0;
|
||||
for(int Bit=0; Bit<CodeBits; Bit++)
|
||||
{ if(Mask==0) { Word=Data[Idx++]; Mask=1; }
|
||||
OutBit[Bit] = InpBit[Bit] = (Word&Mask) ? +Ampl:-Ampl; ExtBit[Bit]=0;
|
||||
Mask<<=1;
|
||||
}
|
||||
}
|
||||
|
||||
void Output(uint32_t *Data) // format decoded bits as a series of 32-bit words
|
||||
{ uint32_t Mask=1; int Idx=0; uint32_t Word=0;
|
||||
for(int Bit=0; Bit<CodeBits; Bit++)
|
||||
{ if(OutBit[Bit]>0) Word|=Mask;
|
||||
Mask<<=1; if(Mask==0) { Data[Idx++]=Word; Word=0; Mask=1; }
|
||||
} if(Mask>1) Data[Idx++]=Word;
|
||||
}
|
||||
|
||||
void Output(uint8_t *Data) // format decoded bits as a series of bytes
|
||||
{ uint8_t Mask=1; int Idx=0; uint8_t Byte=0;
|
||||
for(int Bit=0; Bit<CodeBits; Bit++)
|
||||
{ if(OutBit[Bit]>0) Byte|=Mask;
|
||||
Mask<<=1; if(Mask==0) { Data[Idx++]=Byte; Byte=0; Mask=1; }
|
||||
} if(Mask>1) Data[Idx++]=Byte;
|
||||
}
|
||||
|
||||
int ProcessChecks(void)
|
||||
{ for(int Bit=0; Bit<CodeBits; Bit++) // clear the extrinsic inf. for bits
|
||||
ExtBit[Bit]=0;
|
||||
int Count=0;
|
||||
for(int Row=0; Row<ParityBits; Row++) // process all parity checks and count how many have failed
|
||||
{ Float Ret=ProcessCheck(Row);
|
||||
if(Ret<=0) Count++; }
|
||||
// printf("%d parity checks fail\n", Count);
|
||||
if(Count==0) return 0; // if all passed, then return
|
||||
for(int Bit=0; Bit<CodeBits; Bit++) // add Input+Extrinsic and store in Output
|
||||
{ OutBit[Bit] = InpBit[Bit] + Feedback*ExtBit[Bit]; }
|
||||
return Count; }
|
||||
|
||||
Float ProcessCheck(uint8_t Row)
|
||||
{ Float MinAmpl=std::numeric_limits<Float>::max(); int MinBit=0; Float MinAmpl2=MinAmpl; // look for 1st and 2nd smallest LL
|
||||
uint32_t Word=0; uint32_t Mask=1;
|
||||
const uint16_t *CheckIndex = ParityCheckIndex[Row]; // indeces of bits in this parity check
|
||||
int CheckWeight = ParityCheckRowWeight[Row]; // number of bits in this parity check
|
||||
for(int Bit=0; Bit<CheckWeight; Bit++) // loop over bits in the parity check
|
||||
{ int BitIdx=CheckIndex[Bit]; // index of the bit
|
||||
Float Ampl=OutBit[BitIdx]; // LL of the bit
|
||||
if(Ampl>0) Word|=Mask; // store hard bits in the Word
|
||||
Mask<<=1;
|
||||
if(Ampl<0) Ampl=(-Ampl); // strip the LL sign
|
||||
if(Ampl<MinAmpl) { MinAmpl2=MinAmpl; MinAmpl=Ampl; MinBit=Bit; } // find 1st and 2nd smallest
|
||||
else if(Ampl<MinAmpl2) { MinAmpl2=Ampl; }
|
||||
}
|
||||
int CheckFails = __builtin_parityl(Word); // tell if this parity check failed
|
||||
Mask=1;
|
||||
for(int Bit=0; Bit<CheckWeight; Bit++) // loop over bits in this parity check
|
||||
{ int BitIdx=CheckIndex[Bit]; // inndex of the bit
|
||||
Float Ampl = Bit==MinBit ? MinAmpl2 : MinAmpl; // if this is the weakest bit, then use 2nd smallest LL, otherwise 1st
|
||||
if(CheckFails) Ampl=(-Ampl);
|
||||
ExtBit[BitIdx] += (Word&Mask) ? Ampl:-Ampl; // add to the extrinsic inf. with the correct sign
|
||||
Mask<<=1; }
|
||||
return CheckFails?-MinAmpl:MinAmpl; }
|
||||
|
||||
int CountErrors(void)
|
||||
{ int Count=0;
|
||||
for(int Idx=0; Idx<CodeBits; Idx++)
|
||||
{ bool Inp=InpBit[Idx]>0;
|
||||
bool Out=OutBit[Idx]>0;
|
||||
if(Inp!=Out) Count++; }
|
||||
return Count; }
|
||||
|
||||
} ;
|
||||
|
||||
#ifdef WITH_PPM
|
||||
template <class Float>
|
||||
class OGN_PPM_Decoder
|
||||
{ public:
|
||||
static const int DataBits = 32*5; // 5 words = 160 data bits = OGN packet
|
||||
static const int ParityBits = 194; // 194 parity bits (Gallager code)
|
||||
static const int CodeBits = DataBits+ParityBits; // 354 total bits per Gallager code block
|
||||
static const int BitsPerSymbol = 6; // 6 bits per symbol for PPM modulation
|
||||
static const int PulsesPerSlot = 1<<BitsPerSymbol; // 64 (possible) pulses per time slot = 1 symbol = 6 bits
|
||||
static const int CodeSymbols = CodeBits/BitsPerSymbol; // 59 time slots to form complete packet
|
||||
|
||||
LDPC_FloatDecoder<Float> LDPC_Decoder; // inner LDPC code decoder
|
||||
|
||||
Float InpSymb[CodeSymbols][PulsesPerSlot]; // input from the demodulator
|
||||
Float ExtSymb[CodeSymbols][PulsesPerSlot]; // output from the LDPC decoder
|
||||
Float OutSymb[CodeSymbols][PulsesPerSlot]; // input x extrinsic inf.
|
||||
|
||||
public:
|
||||
OGN_PPM_Decoder()
|
||||
{ LDPC_Decoder.Configure(CodeBits, ParityBits, (uint32_t *)LDPC_ParityCheck_n354k160);
|
||||
Clear(); }
|
||||
|
||||
void Clear(void)
|
||||
{ for(int Symb=0; Symb<CodeSymbols; Symb++)
|
||||
{ Float Ext=1.0/PulsesPerSlot;
|
||||
for(int Pulse=0; Pulse<PulsesPerSlot; Pulse++)
|
||||
{ InpSymb[Symb][Pulse]=0; ExtSymb[Symb][Pulse]=Ext; OutSymb[Symb][Pulse]=0; }
|
||||
}
|
||||
}
|
||||
|
||||
void addSymbol(unsigned int Slot, unsigned int Symbol, Float Power=1.0)
|
||||
{ if( (Slot>=CodeSymbols) || (Symbol>=PulsesPerSlot) ) return;
|
||||
InpSymb[Slot][Symbol]+=Power; }
|
||||
|
||||
int Process(int Loops=48)
|
||||
{ LDPC_Decoder.Clear();
|
||||
|
||||
for(int Symb=0; Symb<CodeSymbols; Symb++)
|
||||
{ for(int Pulse=0; Pulse<PulsesPerSlot; Pulse++)
|
||||
{ Float Pwr=InpSymb[Symb][Pulse]*ExtSymb[Symb][Pulse];
|
||||
if(Pwr==0) continue;
|
||||
Pwr=Pwr*Pwr;
|
||||
int Bin=Binary(Pulse);
|
||||
int Idx=Symb;
|
||||
for(int Bit=0; Bit<BitsPerSymbol; Bit++, Idx+=CodeSymbols)
|
||||
{ LDPC_Decoder.addInput(Idx, (Bin&1) ? +Pwr:-Pwr);
|
||||
Bin>>=1; }
|
||||
}
|
||||
}
|
||||
int CheckErr=0;
|
||||
for( int Loop=0; Loop<Loops; Loop++)
|
||||
{ CheckErr=LDPC_Decoder.ProcessChecks();
|
||||
printf("%3d: OGN_PPM_Decoder.Process() => %3d\n", Loop, CheckErr);
|
||||
if(CheckErr==0) break; }
|
||||
return CheckErr; }
|
||||
|
||||
static uint8_t Gray(uint8_t Binary) { return Binary ^ (Binary>>1); }
|
||||
|
||||
static uint8_t Binary(uint8_t Gray)
|
||||
{ Gray = Gray ^ (Gray >> 4);
|
||||
Gray = Gray ^ (Gray >> 2);
|
||||
Gray = Gray ^ (Gray >> 1);
|
||||
return Gray; }
|
||||
|
||||
void NormExtSymb(Float Norm=1.0)
|
||||
{ for(int Symb=0; Symb<CodeSymbols; Symb++)
|
||||
{ NormExtSymb(Symb, Norm); }
|
||||
}
|
||||
|
||||
void NormExtSymp(int Symb, Float Norm=1.0)
|
||||
{ Float Sum=0;
|
||||
for(int Pulse=0; Pulse<PulsesPerSlot; Pulse++)
|
||||
{ Sum+=ExtSymb[Symb][Pulse]; }
|
||||
Sum=Norm/Sum;
|
||||
for(int Pulse=0; Pulse<PulsesPerSlot; Pulse++)
|
||||
{ ExtSymb[Symb][Pulse]*=Sum; }
|
||||
}
|
||||
|
||||
} ;
|
||||
#endif // WITH_PPM
|
||||
|
||||
#endif // __AVR__
|
||||
|
||||
#endif // of __LDPC_H__
|
|
@ -0,0 +1,29 @@
|
|||
#ifndef __LOWPASS2_H__
|
||||
#define __LOWPASS2_H__
|
||||
|
||||
// 2nd order IIR low pass (averaging) filter
|
||||
// When IntegScale2=IntegScale1-2 => no overshoot
|
||||
// When IntegScale2=IntegScale1-1 => overshoots by about 4%
|
||||
|
||||
template <class Int=int64_t, int IntegScale1=10, int IntegScale2=8, int InpScale=16>
|
||||
class LowPass2
|
||||
{ public:
|
||||
// static const int InpScale = 16;
|
||||
// static const int IntegScale1 = 10;
|
||||
// static const int IntegScale2 = IntegScale-2;
|
||||
Int Out1, Out;
|
||||
public:
|
||||
void Set(Int Inp=0) { Out1=Out = Inp<<InpScale; }
|
||||
Int Process( Int Inp)
|
||||
{ Inp<<=InpScale;
|
||||
Out1 = ( Inp -Out + (Out1<<IntegScale1) + (1<<(IntegScale1-1)) )>>IntegScale1;
|
||||
Out = ( Out1-Out + (Out <<IntegScale2) + (1<<(IntegScale2-1)) )>>IntegScale2;
|
||||
return Out ; } // return fractional result
|
||||
Int getOutput(void)
|
||||
{ return ( Out + (1<<(InpScale-1)) )>>InpScale; }
|
||||
} ;
|
||||
|
||||
|
||||
// make filter with gradually growing integration factors.
|
||||
|
||||
#endif // __LOWPASS2_H__
|
|
@ -0,0 +1,36 @@
|
|||
// ======================================================================================================
|
||||
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
// #include "esp_system.h"
|
||||
// #include "nvs_flash.h"
|
||||
|
||||
#include "hal.h"
|
||||
|
||||
#include "rf.h"
|
||||
#include "proc.h"
|
||||
#include "gps.h"
|
||||
#include "ctrl.h"
|
||||
|
||||
extern "C"
|
||||
void app_main(void)
|
||||
{
|
||||
// printf("OGN Tracker on ESP32\n");
|
||||
|
||||
NVS_Init(); // initialize Non-Volatile-Storage in Flash and read the tracker parameters
|
||||
SPIFFS_Register(); // initialize the file system in the Flash
|
||||
|
||||
// BT_SPP_Init();
|
||||
|
||||
IO_Configuration(); // initialize the GPIO/UART/I2C/SPI for Radio, GPS, OLED, Baro
|
||||
|
||||
xTaskCreate(vTaskRF, "RF", 2048, 0, tskIDLE_PRIORITY+4, 0);
|
||||
xTaskCreate(vTaskPROC, "PROC", 2048, 0, tskIDLE_PRIORITY+3, 0);
|
||||
xTaskCreate(vTaskGPS, "GPS", 2048, 0, tskIDLE_PRIORITY+4, 0);
|
||||
// xTaskCreate(vTaskCTRL, "CTRL", 1536, 0, tskIDLE_PRIORITY+2, 0);
|
||||
vTaskCTRL(0); // run directly the CTRL task, instead of creating a separate one.
|
||||
|
||||
// while(1)
|
||||
// { vTaskDelay(10000); }
|
||||
}
|
||||
|
|
@ -0,0 +1,42 @@
|
|||
|
||||
const uint8_t ManchesterEncode[0x10] = // lookup table for 4-bit nibbles for quick Manchester encoding
|
||||
{
|
||||
0xAA, // hex: 0, bin: 0000, manch: 10101010
|
||||
0xA9, // hex: 1, bin: 0001, manch: 10101001
|
||||
0xA6, // hex: 2, bin: 0010, manch: 10100110
|
||||
0xA5, // hex: 3, bin: 0011, manch: 10100101
|
||||
0x9A, // hex: 4, bin: 0100, manch: 10011010
|
||||
0x99, // hex: 5, bin: 0101, manch: 10011001
|
||||
0x96, // hex: 6, bin: 0110, manch: 10010110
|
||||
0x95, // hex: 7, bin: 0111, manch: 10010101
|
||||
0x6A, // hex: 8, bin: 1000, manch: 01101010
|
||||
0x69, // hex: 9, bin: 1001, manch: 01101001
|
||||
0x66, // hex: A, bin: 1010, manch: 01100110
|
||||
0x65, // hex: B, bin: 1011, manch: 01100101
|
||||
0x5A, // hex: C, bin: 1100, manch: 01011010
|
||||
0x59, // hex: D, bin: 1101, manch: 01011001
|
||||
0x56, // hex: E, bin: 1110, manch: 01010110
|
||||
0x55 // hex: F, bin: 1111, manch: 01010101
|
||||
};
|
||||
|
||||
const uint8_t ManchesterDecode[0x100] = // lookup table for quick Manchester decoding
|
||||
{ // lower nibble has the data bits and the upper nibble the error pattern
|
||||
0xF0, 0xE1, 0xE0, 0xF1, 0xD2, 0xC3, 0xC2, 0xD3, 0xD0, 0xC1, 0xC0, 0xD1, 0xF2, 0xE3, 0xE2, 0xF3,
|
||||
0xB4, 0xA5, 0xA4, 0xB5, 0x96, 0x87, 0x86, 0x97, 0x94, 0x85, 0x84, 0x95, 0xB6, 0xA7, 0xA6, 0xB7,
|
||||
0xB0, 0xA1, 0xA0, 0xB1, 0x92, 0x83, 0x82, 0x93, 0x90, 0x81, 0x80, 0x91, 0xB2, 0xA3, 0xA2, 0xB3,
|
||||
0xF4, 0xE5, 0xE4, 0xF5, 0xD6, 0xC7, 0xC6, 0xD7, 0xD4, 0xC5, 0xC4, 0xD5, 0xF6, 0xE7, 0xE6, 0xF7,
|
||||
0x78, 0x69, 0x68, 0x79, 0x5A, 0x4B, 0x4A, 0x5B, 0x58, 0x49, 0x48, 0x59, 0x7A, 0x6B, 0x6A, 0x7B,
|
||||
0x3C, 0x2D, 0x2C, 0x3D, 0x1E, 0x0F, 0x0E, 0x1F, 0x1C, 0x0D, 0x0C, 0x1D, 0x3E, 0x2F, 0x2E, 0x3F,
|
||||
0x38, 0x29, 0x28, 0x39, 0x1A, 0x0B, 0x0A, 0x1B, 0x18, 0x09, 0x08, 0x19, 0x3A, 0x2B, 0x2A, 0x3B,
|
||||
0x7C, 0x6D, 0x6C, 0x7D, 0x5E, 0x4F, 0x4E, 0x5F, 0x5C, 0x4D, 0x4C, 0x5D, 0x7E, 0x6F, 0x6E, 0x7F,
|
||||
0x70, 0x61, 0x60, 0x71, 0x52, 0x43, 0x42, 0x53, 0x50, 0x41, 0x40, 0x51, 0x72, 0x63, 0x62, 0x73,
|
||||
0x34, 0x25, 0x24, 0x35, 0x16, 0x07, 0x06, 0x17, 0x14, 0x05, 0x04, 0x15, 0x36, 0x27, 0x26, 0x37,
|
||||
0x30, 0x21, 0x20, 0x31, 0x12, 0x03, 0x02, 0x13, 0x10, 0x01, 0x00, 0x11, 0x32, 0x23, 0x22, 0x33,
|
||||
0x74, 0x65, 0x64, 0x75, 0x56, 0x47, 0x46, 0x57, 0x54, 0x45, 0x44, 0x55, 0x76, 0x67, 0x66, 0x77,
|
||||
0xF8, 0xE9, 0xE8, 0xF9, 0xDA, 0xCB, 0xCA, 0xDB, 0xD8, 0xC9, 0xC8, 0xD9, 0xFA, 0xEB, 0xEA, 0xFB,
|
||||
0xBC, 0xAD, 0xAC, 0xBD, 0x9E, 0x8F, 0x8E, 0x9F, 0x9C, 0x8D, 0x8C, 0x9D, 0xBE, 0xAF, 0xAE, 0xBF,
|
||||
0xB8, 0xA9, 0xA8, 0xB9, 0x9A, 0x8B, 0x8A, 0x9B, 0x98, 0x89, 0x88, 0x99, 0xBA, 0xAB, 0xAA, 0xBB,
|
||||
0xFC, 0xED, 0xEC, 0xFD, 0xDE, 0xCF, 0xCE, 0xDF, 0xDC, 0xCD, 0xCC, 0xDD, 0xFE, 0xEF, 0xEE, 0xFF
|
||||
} ;
|
||||
|
||||
|
|
@ -0,0 +1,285 @@
|
|||
#ifndef __MAVLINK_H__
|
||||
#define __MAVLINK_H__
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "intmath.h"
|
||||
|
||||
// ============================================================================
|
||||
|
||||
// https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/common.xml
|
||||
|
||||
// System-ID
|
||||
|
||||
|
||||
// Component-ID
|
||||
const uint8_t MAV_COMP_ID_AUTOPILOT1 = 1; // auto-pilot
|
||||
const uint8_t MAV_COMP_ID_ADSB = 156; // ADS-B receiver
|
||||
const uint8_t MAV_COMP_ID_GPS = 220;
|
||||
|
||||
// Message-ID
|
||||
const uint8_t MAV_ID_HEARTBEAT = 0; //
|
||||
const uint8_t MAV_ID_SYS_STATUS = 1;
|
||||
const uint8_t MAV_ID_SYSTEM_TIME = 2;
|
||||
const uint8_t MAV_ID_GPS_RAW_INT = 24; // GPS position estimate
|
||||
const uint8_t MAV_ID_RAW_IMU = 27;
|
||||
const uint8_t MAV_ID_SCALED_PRESSURE = 29; //
|
||||
const uint8_t MAV_ID_ATTITUDE = 30;
|
||||
const uint8_t MAV_ID_GLOBAL_POSITION_INT = 33; // combined position estimate
|
||||
const uint8_t MAV_ID_RC_CHANNELS_RAW = 35;
|
||||
const uint8_t MAV_ID_SERVO_OUTPUT_RAW = 36;
|
||||
const uint8_t MAV_ID_MISSION_CURRENT = 42;
|
||||
const uint8_t MAV_ID_NAV_CONTROLLER_OUTPUT = 62;
|
||||
const uint8_t MAV_ID_VFR_HUD = 74;
|
||||
const uint8_t MAV_ID_TIMESYNC = 111;
|
||||
const uint8_t MAV_ID_HIL_GPS = 113;
|
||||
const uint8_t MAV_ID_ADSB_VEHICLE = 246; // traffic information sent by an ADS-B receiver
|
||||
const uint8_t MAV_ID_COLLISION = 247; // collision threat detected by auto-pilot
|
||||
const uint8_t MAV_ID_STATUSTEXT = 253;
|
||||
const uint8_t MAV_ID_DEBUG = 254;
|
||||
|
||||
// --------------------------------------------------------------------------------
|
||||
|
||||
class MAV_HEARTBEAT
|
||||
{ public:
|
||||
uint32_t custom_mode;
|
||||
uint8_t type; // MAV-aircraft-type: 1=fixed wing, 2=quadrotor, 7=airship, 8=balloon, 13=hexarotor
|
||||
uint8_t autopilot; // 3=ArduPilotMega, 4=OpenPilot, 13=PX4
|
||||
union
|
||||
{ uint8_t base_mode;
|
||||
struct
|
||||
{ bool custom:1;
|
||||
bool test:1;
|
||||
bool autonomous:1;
|
||||
bool guided:1;
|
||||
bool stabilize:1;
|
||||
bool hil_simulation:1;
|
||||
bool remote_control:1;
|
||||
bool armed:1;
|
||||
} ;
|
||||
} ;
|
||||
uint8_t system_status; // 1=boot, 2=calib., 3=standby, 4=active, 5=critical, 6=emergency, 7=power-off, 8=terminate
|
||||
uint8_t mavlink_version;
|
||||
public:
|
||||
void Print(void) const
|
||||
{ printf("HEARTBEAT: t%X v%d\n", type, mavlink_version); }
|
||||
} ;
|
||||
|
||||
class MAV_SYSTEM_TIME
|
||||
{ public:
|
||||
uint64_t time_unix_usec; // [usec]
|
||||
uint32_t time_boot_ms; // [ms]
|
||||
public:
|
||||
void Print(void) const
|
||||
{ printf("SYSTEM_TIME: %14.3f-%8.3f [sec]\n", 1e-6*time_unix_usec, 1e-3*time_boot_ms); }
|
||||
} ;
|
||||
|
||||
class MAV_SYS_STATUS
|
||||
{ public:
|
||||
uint32_t onboard_control_sensors_present;
|
||||
uint32_t onboard_control_sensors_enabled;
|
||||
uint32_t onboard_control_sensors_health;
|
||||
uint16_t load; // [0.1%]
|
||||
uint16_t battery_voltage; // [mV]
|
||||
int16_t battery_current; // [10mA]
|
||||
uint16_t error_comm;
|
||||
uint16_t error_comm1;
|
||||
uint16_t error_comm2;
|
||||
uint16_t error_comm3;
|
||||
uint16_t error_comm4;
|
||||
uint8_t battery_remaining; // [%]
|
||||
void Print(void) const
|
||||
{ printf("SYS_STATUS: %3.1f%% %5.3fV %+5.2fA\n", 0.1*load, 1e-3*battery_voltage, 0.01*battery_current); }
|
||||
} ;
|
||||
|
||||
class MAV_GPS_RAW_INT
|
||||
{ public:
|
||||
uint64_t time_usec; // [usec] Time
|
||||
int32_t lat; // [1e-7deg] Latitude
|
||||
int32_t lon; // [1e-7deg] Longitude
|
||||
int32_t alt; // [mm] Altitude AMSL
|
||||
// int32_t alt_ellipsoid; // [mm]
|
||||
// uint32_t h_acc; // [mm]
|
||||
// uint32_t v_acc; // [mm]
|
||||
// uint32_t vel_acc; // [mm/s]
|
||||
// uint32_t hdg_acc; // [0.00001deg]
|
||||
uint16_t eph; // [0.01] HDOP
|
||||
uint16_t epv; // [0.01] VDOP
|
||||
uint16_t vel; // [0.01m/s] Valocity
|
||||
uint16_t cog; // [0.01deg] course-over-Ground
|
||||
uint8_t fix_type; // [] 0=no GPS, 1=no fix, 2=2D, 3=3D, 4=DGPS
|
||||
uint8_t satellites_visible; // [] Number of satellites
|
||||
public:
|
||||
void Print(void) const
|
||||
{ printf("GPS_RAW_INT: [%+9.5f, %+10.5f]deg %+5.1fm %3.1fm/s %05.1fdeg %d/%dsat\n",
|
||||
1e-7*lat, 1e-7*lon, 1e-3*alt, 0.01*vel, 0.01*cog, fix_type, satellites_visible); }
|
||||
} ;
|
||||
|
||||
class MAV_GLOBAL_POSITION_INT
|
||||
{ public:
|
||||
uint32_t time_boot_ms; // [ms]
|
||||
int32_t lat; // [1e-7deg]
|
||||
int32_t lon; // [1e-7deg]
|
||||
int32_t alt; // [mm]
|
||||
int32_t relative_alt; // [mm]
|
||||
int16_t vx; // [cm]
|
||||
int16_t vy; // [cm]
|
||||
int16_t vz; // [cm]
|
||||
int16_t hdg; // [0.01deg]
|
||||
public:
|
||||
void Print(void) const
|
||||
{ uint16_t Track = IntAtan2(vy, vx);
|
||||
printf("GLOBAL_POSITION_INT: [%+9.5f, %+10.5f]deg %5.1f(%+4.1f)m %3.1fm/s %05.1f/%05.1fdeg %+4.1fm/s\n",
|
||||
1e-7*lat, 1e-7*lon, 1e-3*alt, 1e-3*relative_alt,
|
||||
0.01*IntSqrt((int32_t)vx*vx+(int32_t)vy*vy), 360.0/0x10000*Track, 0.01*hdg,
|
||||
0.01*vz); }
|
||||
} ;
|
||||
|
||||
class MAV_SCALED_PRESSURE
|
||||
{ public:
|
||||
uint32_t time_boot_ms; // [msec]
|
||||
float press_abs; // [hPa]
|
||||
float press_diff; // [hPa]
|
||||
int16_t temperature; // [0.01degC]
|
||||
public:
|
||||
void Print(void) const
|
||||
{ printf("SCALED_PRESSURE: %8.3f [sec] %7.2f %+4.2f [hPa] %+5.2f [degC]\n", 1e-3*time_boot_ms, 2*press_abs, 2*press_diff, 0.01*temperature); }
|
||||
} ;
|
||||
|
||||
class MAV_ADSB_VEHICLE // this message is sent by ADS-B or other traffic receiver
|
||||
{ public:
|
||||
uint32_t ICAO_address; // ICAO ID (for ADS-B), other ID's for FLARM/OGN/...
|
||||
int32_t lat; // [1e-7deg]
|
||||
int32_t lon; // [1e-7deg]
|
||||
int32_t altitude; // [mm]
|
||||
uint16_t heading; // [0.01deg]
|
||||
uint16_t hor_velocity; // [cm/sec]
|
||||
int16_t ver_velocity; // [cm/sec]
|
||||
union
|
||||
{ uint16_t flags; // validity: 1=coord. 2=alt. 4=heading 8=velocity 16=callsign 32=squawk 64=simulated
|
||||
struct
|
||||
{ bool CoordValid:1;
|
||||
bool AltValid:1;
|
||||
bool HeadingValid:1;
|
||||
bool CallsignValid:1;
|
||||
bool VelocityValid:1;
|
||||
bool SquawkValid:1;
|
||||
bool isSimulated:1;
|
||||
} ;
|
||||
} ;
|
||||
uint16_t squawk;
|
||||
uint8_t altitude_type; // 0 = pressure/QNH, 1 = GPS
|
||||
uint8_t callsign[9]; // 8+null
|
||||
uint8_t emiter_type; // 0=no-info, 1=light, 2=small. 3=large, 4=high-vortex, 5=heavy, 6=manuv, 7=rotor, 9=glider, 10=balloon/airship, 11=parachute, 12=ULM, 14=UAV, 15=space, 19=obstacle
|
||||
uint8_t tslc; // [sec] time since last communication
|
||||
public:
|
||||
void Print(void) const
|
||||
{ printf("ADSB_VEHICLE: %02X:%08lX [%+9.5f, %+10.5f]deg %5.1fm %3.1fm/s %05.1fdeg %+4.1fm/s\n",
|
||||
(int)emiter_type, (long int)ICAO_address, 1e-7*lat, 1e-7*lon, 1e-3*altitude, 0.01*hor_velocity, 360.0/0x10000*heading, 0.01*ver_velocity); }
|
||||
} ;
|
||||
|
||||
class COLLISION // this message is sent by the autopilot when it detects a collision threat
|
||||
{ public:
|
||||
uint32_t id;
|
||||
float time_to_minimum_delta;
|
||||
float altitude_minimum_delta;
|
||||
float horizontal_minimum_delta;
|
||||
uint8_t src;
|
||||
uint8_t action;
|
||||
uint8_t threat_level;
|
||||
} ;
|
||||
|
||||
// =============================================================================
|
||||
|
||||
// https://groups.google.com/forum/#!topic/mavlink/-ipDgVeYSiU
|
||||
static const uint8_t mavlink_message_crcs[256] = {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 78, 196, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 59, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 138, 108, 32, 185, 84, 34, 174, 124, 237, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 46, 29, 223, 85, 6, 229, 203, 1, 195, 109, 168, 181, 47, 72, 131, 127, 0, 103, 154, 178, 200, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 34, 71, 15, 0, 0, 0, 0, 0, 0, 0, 163, 105, 0, 35, 0, 0, 0, 0, 0, 0, 0, 90, 104, 85, 95, 130, 184, 0, 8, 204, 49, 170, 44, 83, 46, 0};
|
||||
|
||||
class MAV_RxMsg // receiver for the MAV messages
|
||||
{ public:
|
||||
static const uint8_t MaxBytes = 65; // max. number of bytes
|
||||
static const uint8_t Sync = 0xFE; // MAV sync byte
|
||||
|
||||
uint16_t Check;
|
||||
uint8_t Byte[MaxBytes];
|
||||
uint8_t Idx;
|
||||
|
||||
public:
|
||||
void Clear(void) { Idx=0; CheckInit(Check); }
|
||||
|
||||
uint8_t getLen (void) const { return Byte[1]; } // Payload length (not whole packet length)
|
||||
uint8_t getSeq (void) const { return Byte[2]; } // Sequence (increments with every new message)
|
||||
uint8_t getSysID (void) const { return Byte[3]; } // System-ID
|
||||
uint8_t getCompID(void) const { return Byte[4]; } // Component-ID
|
||||
uint8_t getMsgID (void) const { return Byte[5]; } // Message-ID
|
||||
void *getPayload(void) const { return (void *)(Byte+6); } // message (pointer to) Payload
|
||||
|
||||
void Print(bool Ext=1) const
|
||||
{ printf("MAV[%2d:%2d] [%02X] %02X:%02X %3d:", Idx, getLen(), getSeq(), getSysID(), getCompID(), getMsgID() );
|
||||
if( (getMsgID()==MAV_ID_STATUSTEXT) && isComplete() )
|
||||
{ printf("(%d) %s\n", Byte[6], Byte+7); }
|
||||
else
|
||||
{ for(uint8_t i=6; i<Idx; i++)
|
||||
printf(" %02X", Byte[i]);
|
||||
printf(" %04X (%c)\n", Check, isComplete()?'+':'-');
|
||||
if(Ext)
|
||||
{ if(getMsgID()==MAV_ID_HEARTBEAT ) { ((const MAV_HEARTBEAT *)getPayload())->Print(); }
|
||||
else if(getMsgID()==MAV_ID_SYS_STATUS ) { ((const MAV_SYS_STATUS *)getPayload())->Print(); }
|
||||
else if(getMsgID()==MAV_ID_SYSTEM_TIME ) { ((const MAV_SYSTEM_TIME *)getPayload())->Print(); }
|
||||
else if(getMsgID()==MAV_ID_SCALED_PRESSURE ) { ((const MAV_SCALED_PRESSURE *)getPayload())->Print(); }
|
||||
else if(getMsgID()==MAV_ID_GPS_RAW_INT ) { ((const MAV_GPS_RAW_INT *)getPayload())->Print(); }
|
||||
else if(getMsgID()==MAV_ID_GLOBAL_POSITION_INT ) { ((const MAV_GLOBAL_POSITION_INT *)getPayload())->Print(); }
|
||||
else if(getMsgID()==MAV_ID_ADSB_VEHICLE ) { ((const MAV_ADSB_VEHICLE *)getPayload())->Print(); }
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t ProcessByte(uint8_t RxByte) // process a single byte: add to the message or reject
|
||||
{ // printf("Process[%2d] 0x%02X\n", Idx, RxByte);
|
||||
if(Idx==0) // the very first byte: we only accept SYNC
|
||||
{ if(RxByte==Sync) { Byte[Idx++]=RxByte; return 1; }
|
||||
else { return 0; }
|
||||
}
|
||||
if(Idx==1) // second byte: payload length
|
||||
{ Byte[Idx++]=RxByte; CheckPass(Check, RxByte); return 1; }
|
||||
if(Idx>=MaxBytes) { Clear(); return 0; } // take following bytes
|
||||
Byte[Idx++]=RxByte; if(Idx<(getLen()+7)) CheckPass(Check, RxByte);
|
||||
if(Idx==(getLen()+8))
|
||||
{ CheckPass(Check, mavlink_message_crcs[getMsgID()]);
|
||||
// printf("[%2d]", Idx); for(uint8_t i=0; i<Idx; i++) printf(" %02X", Byte[i]); printf(" %04X\n", Check);
|
||||
if( ((Check&0xFF)!=Byte[Idx-2]) || ((Check>>8)!=Byte[Idx-1]) ) { Clear(); return 0; }
|
||||
}
|
||||
return 1; }
|
||||
|
||||
uint8_t isComplete(void) const { return Idx==(getLen()+8); }
|
||||
|
||||
void static CheckInit(uint16_t &Check) { Check=0xFFFF; }
|
||||
void static CheckPass(uint16_t &Check, uint8_t Byte)
|
||||
{ uint8_t Tmp = Byte ^ (uint8_t)(Check&0xFF);
|
||||
Tmp ^= (Tmp<<4);
|
||||
Check = (Check>>8) ^ ((uint16_t)Tmp<<8) ^ ((uint16_t)Tmp<<3) ^ (Tmp>>4);
|
||||
// printf("CheckPass: 0x%02X => 0x%04X\n", Byte, Check);
|
||||
}
|
||||
|
||||
static uint8_t Send(uint8_t Len, uint8_t Seq, uint8_t SysID, uint8_t CompID, uint8_t MsgID, const uint8_t *Payload, void (*SendByte)(char) )
|
||||
{ uint16_t Check; CheckInit(Check);
|
||||
(*SendByte)(Sync);
|
||||
(*SendByte)(Len); CheckPass(Check, Len);
|
||||
(*SendByte)(Seq); CheckPass(Check, Seq);
|
||||
(*SendByte)(SysID); CheckPass(Check, SysID);
|
||||
(*SendByte)(CompID); CheckPass(Check, CompID);
|
||||
(*SendByte)(MsgID); CheckPass(Check, MsgID);
|
||||
for(uint8_t Idx=0; Idx<Len; Idx++)
|
||||
{ (*SendByte)(Payload[Idx]); CheckPass(Check, Payload[Idx]); }
|
||||
CheckPass(Check, mavlink_message_crcs[MsgID]);
|
||||
(*SendByte)(Check&0xFF); (*SendByte)(Check>>8);
|
||||
return 8+Len; }
|
||||
|
||||
uint8_t Send(void (*SendByte)(char)) const
|
||||
{ return Send(Byte[1], Byte[2], Byte[3], Byte[4], Byte[5], Byte+6, SendByte); }
|
||||
|
||||
} ;
|
||||
|
||||
// ============================================================================
|
||||
|
||||
#endif // __MAVLINK_H__
|
|
@ -0,0 +1,19 @@
|
|||
#include "nmea.h"
|
||||
|
||||
uint8_t NMEA_Check(uint8_t *NMEA, uint8_t Len) // NMEA check-sum
|
||||
{ uint8_t Check=0; // to be calculated over characters between '$' and '*' but _excluding_ those.
|
||||
for(uint8_t Idx=0; Idx<Len; Idx++)
|
||||
Check^=NMEA[Idx];
|
||||
return Check; }
|
||||
|
||||
uint8_t NMEA_AppendCheck(uint8_t *NMEA, uint8_t Len)
|
||||
{ uint8_t Check=NMEA_Check(NMEA+1, Len-1);
|
||||
NMEA[Len ]='*';
|
||||
uint8_t Digit=Check>>4; NMEA[Len+1] = Digit<10 ? Digit+'0':Digit+'A'-10;
|
||||
Digit=Check&0xF; NMEA[Len+2] = Digit<10 ? Digit+'0':Digit+'A'-10;
|
||||
return 3; }
|
||||
|
||||
uint8_t NMEA_AppendCheckCRNL(uint8_t *NMEA, uint8_t Len)
|
||||
{ uint8_t CheckLen=NMEA_AppendCheck(NMEA, Len);
|
||||
Len+=CheckLen; NMEA[Len]='\r'; NMEA[Len+1]='\n';
|
||||
return CheckLen+2; }
|
|
@ -0,0 +1,196 @@
|
|||
#ifndef __NMEA_H__
|
||||
#define __NMEA_H__
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
uint8_t NMEA_Check(uint8_t *NMEA, uint8_t Len);
|
||||
uint8_t NMEA_AppendCheck(uint8_t *NMEA, uint8_t Len);
|
||||
inline uint8_t NMEA_AppendCheck(char *NMEA, uint8_t Len) { return NMEA_AppendCheck((uint8_t*)NMEA, Len); }
|
||||
uint8_t NMEA_AppendCheckCRNL(uint8_t *NMEA, uint8_t Len);
|
||||
inline uint8_t NMEA_AppendCheckCRNL(char *NMEA, uint8_t Len) { return NMEA_AppendCheckCRNL((uint8_t*)NMEA, Len); }
|
||||
|
||||
class NMEA_RxMsg // receiver for the NMEA sentences
|
||||
{ public:
|
||||
static const uint8_t MaxLen=96; // maximum length
|
||||
static const uint8_t MaxParms=24; // maximum number of parameters (commas)
|
||||
uint8_t Data[MaxLen]; // the message itself
|
||||
uint8_t Len; // number of bytes
|
||||
uint8_t Parms; // number of commas
|
||||
uint8_t Parm[MaxParms]; // offset to each comma
|
||||
uint8_t State; // bits: 0:loading, 1:complete, 2:locked,
|
||||
uint8_t Check; // check sum: should be a XOR of all bytes between '$' and '*'
|
||||
|
||||
public:
|
||||
void Clear(void) // Clear the frame: discard all data, ready for next message
|
||||
{ State=0; Len=0; Parms=0; }
|
||||
|
||||
void Send(void (*SendByte)(char) ) const
|
||||
{ for(uint8_t Idx=0; Idx<Len; Idx++)
|
||||
{ (*SendByte)(Data[Idx]); }
|
||||
(*SendByte)('\r'); (*SendByte)('\n'); }
|
||||
|
||||
void ProcessByte(uint8_t Byte) // pass all bytes through this call and it will build the frame
|
||||
{
|
||||
if(isComplete()) return; // if already a complete frame, ignore extra bytes
|
||||
if(Len==0) // if data is empty
|
||||
{ if(Byte!='$') return; // then ignore all bytes but '$'
|
||||
Data[Len++]=Byte; // start storing the frame
|
||||
setLoading(); Check=0x00; Parms=0; // set state to "isLoading", clear checksum
|
||||
} else // if not empty (being loaded)
|
||||
{ if((Byte=='\r')||(Byte=='\n')) // if CR (or NL ?) then frame is complete
|
||||
{ setComplete(); if(Len<MaxLen) Data[Len]=0;
|
||||
return; }
|
||||
else if(Byte<=' ') // other control bytes treat as errors
|
||||
{ Clear(); return; } // and drop the frame
|
||||
else if(Byte==',') // save comma positions to later get back to the fields
|
||||
{ if(Parms<MaxParms) Parm[Parms++]=Len+1; }
|
||||
if(Len<MaxLen) { Data[Len++]=Byte; Check^=Byte; } // store data but if too much then treat as an error
|
||||
else Clear(); // if too long, then drop the frame completely
|
||||
}
|
||||
return; }
|
||||
|
||||
uint8_t isLoading(void) const { return State &0x01; }
|
||||
void setLoading(void) { State|=0x01; }
|
||||
|
||||
uint8_t isComplete(void) const { return State &0x02; }
|
||||
void setComplete(void) { State|=0x02; }
|
||||
|
||||
uint8_t isLocked(void) const { return State&0x04; }
|
||||
|
||||
uint8_t isEmpty(void) const { return Len==0; }
|
||||
|
||||
uint8_t hasCheck(void) const
|
||||
{ if(Len<4) return 0;
|
||||
return Data[Len-3]=='*'; }
|
||||
|
||||
uint8_t isChecked(void) const // is the NMEA checksum OK ?
|
||||
{ if(!hasCheck()) return 0;
|
||||
uint8_t DataCheck = Check^Data[Len-3]^Data[Len-2]^Data[Len-1];
|
||||
int8_t HighDigit=HexValue(Data[Len-2]); if(HighDigit<0) return 0;
|
||||
int8_t LowDigit=HexValue(Data[Len-1]); if(LowDigit<0) return 0;
|
||||
uint8_t FrameCheck = (HighDigit<<4) | LowDigit;
|
||||
return DataCheck==FrameCheck; }
|
||||
/*
|
||||
static int8_t DecValue(uint8_t Char)
|
||||
{ if(Char<'0') return -1;
|
||||
if(Char<='9') return Char-'0';
|
||||
return -1; }
|
||||
*/
|
||||
static int8_t HexValue(uint8_t Char)
|
||||
{ if(Char<'0') return -1;
|
||||
if(Char<='9') return Char-'0';
|
||||
if(Char<'A') return -1;
|
||||
if(Char<='F') return Char-('A'-10);
|
||||
// if(Char<'a') return -1; // check-sum uses uppercase latters
|
||||
// if(Char<='f') return Char-('a'-10);
|
||||
return -1; }
|
||||
|
||||
const uint8_t *ParmPtr(uint8_t Field) const // get a pointer to given (comma separated) field
|
||||
{ if(Field>=Parms) return 0;
|
||||
return Data+Parm[Field]; }
|
||||
/*
|
||||
uint8_t ParmLen(uint8_t Field) const
|
||||
{ if(Field>=Parms) return 0;
|
||||
if(Field==(Parms-1)) return Len-4-Comma[Field];
|
||||
return Parm[Field+1]-Parm[Field]-1; }
|
||||
*/
|
||||
|
||||
uint8_t isGP(void) const // GPS sentence ?
|
||||
// { return isGP((const char *)Data); }
|
||||
// uint8_t static isGP(const char *Data)
|
||||
{ if(Data[1]!='G') return 0;
|
||||
return Data[2]=='P'; }
|
||||
|
||||
uint8_t isGN(void) const
|
||||
// { return isGN((const char *)Data); }
|
||||
// uint8_t static isGN(const char *Data)
|
||||
{ if(Data[1]!='G') return 0;
|
||||
return Data[2]=='N'; }
|
||||
|
||||
uint8_t isGx(void) const // GPS or GLONASS sentence ?
|
||||
{ return Data[1]=='G'; }
|
||||
|
||||
uint8_t isGPRMC(void) const // GPS recomended minimum data
|
||||
{ if(!isGP()) return 0;
|
||||
if(Data[3]!='R') return 0;
|
||||
if(Data[4]!='M') return 0;
|
||||
return Data[5]=='C'; }
|
||||
|
||||
uint8_t isGNRMC(void) const // GPS recomended minimum data
|
||||
{ if(!isGN()) return 0;
|
||||
if(Data[3]!='R') return 0;
|
||||
if(Data[4]!='M') return 0;
|
||||
return Data[5]=='C'; }
|
||||
|
||||
uint8_t isGxRMC(void) const // GPS recomended minimum data
|
||||
{ if(!isGx()) return 0;
|
||||
if(Data[3]!='R') return 0;
|
||||
if(Data[4]!='M') return 0;
|
||||
return Data[5]=='C'; }
|
||||
|
||||
uint8_t isGPGGA(void) const // GPS 3-D fix data
|
||||
{ if(!isGP()) return 0;
|
||||
if(Data[3]!='G') return 0;
|
||||
if(Data[4]!='G') return 0;
|
||||
return Data[5]=='A'; }
|
||||
|
||||
uint8_t isGNGGA(void) const // GPS 3-D fix data
|
||||
{ if(!isGN()) return 0;
|
||||
if(Data[3]!='G') return 0;
|
||||
if(Data[4]!='G') return 0;
|
||||
return Data[5]=='A'; }
|
||||
|
||||
uint8_t isGxGGA(void) const //
|
||||
{ if(!isGx()) return 0;
|
||||
if(Data[3]!='G') return 0;
|
||||
if(Data[4]!='G') return 0;
|
||||
return Data[5]=='A'; }
|
||||
|
||||
uint8_t isGPGSA(void) const // GPS satellite data
|
||||
{ if(!isGP()) return 0;
|
||||
if(Data[3]!='G') return 0;
|
||||
if(Data[4]!='S') return 0;
|
||||
return Data[5]=='A'; }
|
||||
|
||||
uint8_t isGNGSA(void) const //
|
||||
{ if(!isGN()) return 0;
|
||||
if(Data[3]!='G') return 0;
|
||||
if(Data[4]!='S') return 0;
|
||||
return Data[5]=='A'; }
|
||||
|
||||
uint8_t isGxGSA(void) const //
|
||||
{ if(!isGx()) return 0;
|
||||
if(Data[3]!='G') return 0;
|
||||
if(Data[4]!='S') return 0;
|
||||
return Data[5]=='A'; }
|
||||
|
||||
uint8_t isGPTXT(void) const // GPS satellite data
|
||||
{ if(!isGP()) return 0;
|
||||
if(Data[3]!='T') return 0;
|
||||
if(Data[4]!='X') return 0;
|
||||
return Data[5]=='T'; }
|
||||
|
||||
uint8_t isP(void) const
|
||||
{ return Data[1]=='P'; }
|
||||
|
||||
uint8_t isPOGN(void) const // OGN dedicated NMEA sentence
|
||||
{ if(Data[1]!='P') return 0;
|
||||
if(Data[2]!='O') return 0;
|
||||
if(Data[3]!='G') return 0;
|
||||
return Data[4]=='N'; }
|
||||
|
||||
uint8_t isPOGNB(void) // barometric report from the OGN tracker
|
||||
{ if(!isPOGN()) return 0;
|
||||
return Data[5]=='B'; }
|
||||
|
||||
uint8_t isPOGNT(void) // other aircraft position (tracking) report from OGN trackers
|
||||
{ if(!isPOGN()) return 0;
|
||||
return Data[5]=='T'; }
|
||||
|
||||
uint8_t isPOGNS(void) // tracker parameters setup
|
||||
{ if(!isPOGN()) return 0;
|
||||
return Data[5]=='S'; }
|
||||
|
||||
} ;
|
||||
|
||||
#endif // of __NMEA_H__
|
Plik diff jest za duży
Load Diff
|
@ -0,0 +1,304 @@
|
|||
#ifndef __PARAMETERS_H__
|
||||
#define __PARAMETERS_H__
|
||||
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "nvs.h"
|
||||
// #include "flashsize.h"
|
||||
// #include "uniqueid.h"
|
||||
|
||||
// #include "stm32f10x_flash.h"
|
||||
|
||||
#include "nmea.h"
|
||||
#include "format.h"
|
||||
|
||||
// Parameters stored in Flash
|
||||
class FlashParameters
|
||||
{ public:
|
||||
union
|
||||
{ uint32_t AcftID; // identification: Private:AcftType:AddrType:Address - must be different for every tracker
|
||||
struct
|
||||
{ uint32_t Address:24; // address (ID)
|
||||
uint8_t AddrType:2;
|
||||
uint8_t AcftType:4;
|
||||
bool NoTrack:1;
|
||||
bool Stealth:1;
|
||||
} ;
|
||||
} ;
|
||||
int16_t RFchipFreqCorr; // [10Hz] frequency correction for crystal frequency offset
|
||||
int8_t RFchipTxPower; // [dBm] highest bit set => HW module (up to +20dBm Tx power)
|
||||
int8_t RFchipTempCorr; // [degC] correction to the temperature measured in the RF chip
|
||||
uint32_t CONbaud; // [bps] Console baud rate
|
||||
uint16_t PressCorr; // [0.25Pa] pressure correction for the baro
|
||||
union
|
||||
{ uint16_t Flags;
|
||||
struct
|
||||
{ bool SaveToFlash:1; // Save parameters from the config file to Flash
|
||||
bool hasBT:1; // has BT interface on the console
|
||||
bool BT_ON:1; // BT on after power up
|
||||
} ;
|
||||
} ; //
|
||||
// char BTname[8];
|
||||
// char BTpin[4];
|
||||
// char Pilot[16];
|
||||
// char Copilot[16]
|
||||
// char Category[16]
|
||||
|
||||
// static const uint32_t Words=sizeof(FlashParameters)/sizeof(uint32_t);
|
||||
public:
|
||||
int8_t getTxPower(void) const { int8_t Pwr=RFchipTxPower&0x7F; if(Pwr&0x40) Pwr|=0x80; return Pwr; }
|
||||
void setTxPower(int8_t Pwr) { RFchipTxPower = (RFchipTxPower&0x80) | (Pwr&0x7F); }
|
||||
|
||||
void setTxTypeHW(void) { RFchipTxPower|=0x80; }
|
||||
void clrTxTypeHW(void) { RFchipTxPower&=0x7F; }
|
||||
uint8_t isTxTypeHW(void) const { return RFchipTxPower& 0x80; } // if this RFM69HW (Tx power up to +20dBm) ?
|
||||
|
||||
static const uint32_t CheckInit = 0x89ABCDEF;
|
||||
|
||||
public:
|
||||
// void setDefault(void) { setDefaults(UniqueID[0] ^ UniqueID[1] ^ UniqueID[2]); }
|
||||
|
||||
void setDefault(uint32_t UniqueID)
|
||||
{ AcftID = 0x07000000 | (UniqueID&0x00FFFFFF);
|
||||
RFchipFreqCorr = 0; // [10Hz]
|
||||
#ifdef WITH_RFM69W
|
||||
RFchipTxPower = 13; // [dBm] for RFM69W
|
||||
#else
|
||||
RFchipTxPower = 0x80 | 14; // [dBm] for RFM69HW
|
||||
#endif
|
||||
RFchipTempCorr = 0; // [degC]
|
||||
PressCorr = 0; // [0.25Pa]
|
||||
CONbaud = 115200; // [bps]
|
||||
}
|
||||
|
||||
uint32_t static CheckSum(const uint32_t *Word, uint32_t Words) // calculate check-sum of pointed data
|
||||
{ uint32_t Check=CheckInit;
|
||||
for(uint32_t Idx=0; Idx<Words; Words++)
|
||||
{ Check+=Word[Idx]; }
|
||||
return Check; }
|
||||
|
||||
uint32_t CheckSum(void) const // calc. check-sum of this class data
|
||||
{ return CheckSum((uint32_t *)this, sizeof(FlashParameters)/sizeof(uint32_t) ); }
|
||||
|
||||
esp_err_t WriteToNVS(const char *Name="Parameters", const char *NameSpace="TRACKER")
|
||||
{ nvs_handle Handle;
|
||||
esp_err_t Err = nvs_open(NameSpace, NVS_READWRITE, &Handle);
|
||||
if(Err!=ESP_OK) return Err;
|
||||
Err = nvs_set_blob(Handle, Name, this, sizeof(FlashParameters));
|
||||
if(Err==ESP_OK) Err = nvs_commit(Handle);
|
||||
nvs_close(Handle);
|
||||
return Err; }
|
||||
|
||||
esp_err_t ReadFromNVS(const char *Name="Parameters", const char *NameSpace="TRACKER")
|
||||
{ nvs_handle Handle;
|
||||
esp_err_t Err = nvs_open(NameSpace, NVS_READWRITE, &Handle);
|
||||
if(Err!=ESP_OK) return Err;
|
||||
size_t Size=0;
|
||||
Err = nvs_get_blob(Handle, Name, 0, &Size);
|
||||
if( (Err==ESP_OK) && (Size==sizeof(FlashParameters)) )
|
||||
Err = nvs_get_blob(Handle, Name, this, &Size);
|
||||
nvs_close(Handle);
|
||||
return Err; }
|
||||
|
||||
/*
|
||||
static uint32_t *DefaultFlashAddr(void) { return FlashStart+((uint32_t)(getFlashSizeKB()-1)<<8); }
|
||||
|
||||
int8_t ReadFromFlash(uint32_t *Addr=0) // read parameters from Flash
|
||||
{ if(Addr==0) Addr = DefaultFlashAddr();
|
||||
const uint32_t Words=sizeof(FlashParameters)/sizeof(uint32_t);
|
||||
uint32_t Check=CheckSum(Addr, Words); // check-sum of Flash data
|
||||
if(Check!=Addr[Words]) return -1; // agree with the check-sum in Flash ?
|
||||
uint32_t *Dst = (uint32_t *)this;
|
||||
for(uint32_t Idx=0; Idx<Words; Idx++) // read data from Flash
|
||||
{ Dst[Idx] = Addr[Idx]; }
|
||||
return 1; } // return: correct
|
||||
|
||||
int8_t CompareToFlash(uint32_t *Addr=0)
|
||||
{ if(Addr==0) Addr = DefaultFlashAddr(); // address in the Flash
|
||||
const uint32_t Words=sizeof(FlashParameters)/sizeof(uint32_t);
|
||||
uint32_t Check=CheckSum(Addr, Words); // check-sum of Flash data
|
||||
if(Check!=Addr[Words]) return 0; // agree with the check-sum in Flash ?
|
||||
uint32_t *Dst = (uint32_t *)this;
|
||||
for(uint32_t Idx=0; Idx<Words; Idx++) // read data from Flash
|
||||
{ if(Dst[Idx]!=Addr[Idx]) return 0; }
|
||||
return 1; } // return: correct
|
||||
|
||||
int8_t WriteToFlash(uint32_t *Addr=0) const // write parameters to Flash
|
||||
{ if(Addr==0) Addr = DefaultFlashAddr();
|
||||
const uint32_t Words=sizeof(FlashParameters)/sizeof(uint32_t);
|
||||
FLASH_Unlock(); // unlock Flash
|
||||
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
|
||||
FLASH_ErasePage((uint32_t)Addr); // erase Flash page
|
||||
uint32_t *Data=(uint32_t *)this; // take data of this object
|
||||
for(uint32_t Idx=0; Idx<Words; Idx++) // word by word
|
||||
{ FLASH_ProgramWord((uint32_t)Addr, Data[Idx]); Addr++; } // !=FLASH_COMPLETE ? // write to Flash
|
||||
FLASH_ProgramWord((uint32_t)Addr, CheckSum(Data, Words) ); // write the check-sum
|
||||
FLASH_Lock(); // re-lock Flash
|
||||
if(CheckSum(Addr, Words)!=Addr[Words]) return -1; // verify check-sum in Flash
|
||||
return 0; }
|
||||
*/
|
||||
uint8_t Print(char *Line) // print parameters on a single line, suitable for console output
|
||||
{ uint8_t Len=0;
|
||||
Line[Len++]=HexDigit(AcftType); Line[Len++]=':';
|
||||
Line[Len++]=HexDigit(AddrType); Line[Len++]=':';
|
||||
Len+=Format_Hex(Line+Len, Address, 6);
|
||||
#ifdef WITH_RFM69
|
||||
Len+=Format_String(Line+Len, " RFM69");
|
||||
if(isTxTypeHW()) Line[Len++]='H';
|
||||
Line[Len++]='W';
|
||||
#endif
|
||||
#ifdef WITH_RFM95
|
||||
Len+=Format_String(Line+Len, " RFM95");
|
||||
#endif
|
||||
Line[Len++]='/';
|
||||
Len+=Format_SignDec(Line+Len, (int16_t)getTxPower());
|
||||
Len+=Format_String(Line+Len, "dBm");
|
||||
Line[Len++]=' '; Len+=Format_SignDec(Line+Len, (int32_t)RFchipFreqCorr/10, 2, 1); Len+=Format_String(Line+Len, "kHz");
|
||||
Len+=Format_String(Line+Len, " CON:");
|
||||
Len+=Format_UnsDec(Line+Len, CONbaud);
|
||||
Len+=Format_String(Line+Len, "bps\n");
|
||||
Line[Len]=0;
|
||||
return Len; }
|
||||
|
||||
int ReadPOGNS(NMEA_RxMsg &NMEA)
|
||||
{ const char *Parm; int8_t Val;
|
||||
Parm = (const char *)NMEA.ParmPtr(0); // [0..15] aircraft-type: 1=glider, 2=tow plane, 3=helicopter, ...
|
||||
if(Parm)
|
||||
{ Val=Read_Hex1(Parm[0]);
|
||||
if( (Val>=0) && (Val<16) ) AcftType=Val; }
|
||||
Parm = (const char *)NMEA.ParmPtr(1); // [0..3] addr-type: 1=ICAO, 2=FLARM, 3=OGN
|
||||
if(Parm)
|
||||
{ Val=Read_Hex1(Parm[0]);
|
||||
if( (Val>=0) && (Val<4) ) AddrType=Val; }
|
||||
Parm = (const char *)NMEA.ParmPtr(2); // [HHHHHH] Address (ID): 6 hex digits, 24-bit
|
||||
uint32_t Addr;
|
||||
int8_t Len=Read_Hex(Addr, Parm);
|
||||
if( (Len==6) && (Addr<0x01000000) ) Address=Addr;
|
||||
Parm = (const char *)NMEA.ParmPtr(3); // [0..1] RFM69HW (up to +20dBm) or W (up to +13dBm)
|
||||
if(Parm)
|
||||
{ Val=Read_Dec1(Parm[0]);
|
||||
if(Val==0) clrTxTypeHW();
|
||||
else if(Val==1) setTxTypeHW(); }
|
||||
Parm = (const char *)NMEA.ParmPtr(4); // [dBm] Tx power
|
||||
int32_t TxPwr;
|
||||
Len=Read_SignDec(TxPwr, Parm);
|
||||
if( (Len>0) && (TxPwr>=(-10)) && (TxPwr<=20) ) setTxPower(TxPwr);
|
||||
Parm = (const char *)NMEA.ParmPtr(5); // [kHz] Tx/Rx frequency correction
|
||||
int32_t FreqCorr;
|
||||
Len=Read_Float1(FreqCorr, Parm);
|
||||
if( (Len>0) && (FreqCorr>=(-1000)) && (FreqCorr<=1000) ) RFchipFreqCorr = 10*FreqCorr;
|
||||
Parm = (const char *)NMEA.ParmPtr(6); // [bps] Console baud rate
|
||||
uint32_t BaudRate;
|
||||
Len=Read_UnsDec(BaudRate, Parm);
|
||||
if( (Len>0) && (BaudRate<=230400) ) CONbaud = BaudRate;
|
||||
return 0; }
|
||||
|
||||
static char *SkipBlanks(char *Inp)
|
||||
{ for( ; ; )
|
||||
{ char ch=(*Inp); if(ch==0) break;
|
||||
if(ch>' ') break;
|
||||
Inp++; }
|
||||
return Inp; }
|
||||
|
||||
bool ReadLine(char *Line)
|
||||
{ char *Name = SkipBlanks(Line); if((*Name)==0) return 0;
|
||||
Line = Name;
|
||||
for( ; ; )
|
||||
{ char ch=(*Line);
|
||||
if(ch<=' ') break;
|
||||
if(ch=='=') break;
|
||||
Line++; }
|
||||
char *NameEnd=Line;
|
||||
Line=SkipBlanks(Line); if((*Line)!='=') return 0;
|
||||
char *Value = SkipBlanks(Line+1); if((*Value)<=' ') return 0;
|
||||
*NameEnd=0;
|
||||
return ReadParam(Name, Value); }
|
||||
|
||||
bool ReadParam(const char *Name, const char *Value)
|
||||
{ if(strcmp(Name, "Address")==0)
|
||||
{ uint32_t Addr=0; if(Read_Int(Addr, Value)<=0) return 0;
|
||||
Address=Addr; return 1; }
|
||||
if(strcmp(Name, "AddrType")==0)
|
||||
{ uint32_t Type=0; if(Read_Int(Type, Value)<=0) return 0;
|
||||
AddrType=Type; return 1; }
|
||||
if(strcmp(Name, "AcftType")==0)
|
||||
{ uint32_t Type=0; if(Read_Int(Type, Value)<=0) return 0;
|
||||
AcftType=Type; return 1; }
|
||||
if(strcmp(Name, "Console")==0)
|
||||
{ uint32_t Baud=0; if(Read_Int(Baud, Value)<=0) return 0;
|
||||
CONbaud=Baud; return 1; }
|
||||
if(strcmp(Name, "TxPower")==0)
|
||||
{ int32_t TxPower=0; if(Read_Int(TxPower, Value)<=0) return 0;
|
||||
setTxPower(TxPower); return 1; }
|
||||
if(strcmp(Name, "FreqCorr")==0)
|
||||
{ int32_t Corr=0; if(Read_Float1(Corr, Value)<=0) return 0;
|
||||
RFchipFreqCorr=10*Corr; return 1; }
|
||||
if(strcmp(Name, "PressCorr")==0)
|
||||
{ int32_t Corr=0; if(Read_Float1(Corr, Value)<=0) return 0;
|
||||
PressCorr=4*Corr/10; return 1; }
|
||||
return 0; }
|
||||
|
||||
int ReadFile(FILE *File)
|
||||
{ char Line[80];
|
||||
size_t Lines=0;
|
||||
for( ; ; )
|
||||
{ if(fgets(Line, 80, File)==0) break;
|
||||
if(strchr(Line, '\n')==0) break;
|
||||
if(ReadLine(Line)) Lines++; }
|
||||
return Lines; }
|
||||
|
||||
int ReadFile(const char *Name = "/spiffs/TRACKER.CFG")
|
||||
{ FILE *File=fopen(Name, "rt"); if(File==0) return 0;
|
||||
int Lines=ReadFile(File);
|
||||
fclose(File); return Lines; }
|
||||
|
||||
int Write_Hex(char *Line, const char *Name, uint32_t Value, uint8_t Digits)
|
||||
{ uint8_t Len=Format_String(Line, Name);
|
||||
Len+=Format_String(Line+Len, "=0x");
|
||||
Len+=Format_Hex(Line+Len, Value, Digits);
|
||||
Len+=Format_String(Line+Len, ";");
|
||||
Line[Len]=0; return Len; }
|
||||
|
||||
int Write_UnsDec(char *Line, const char *Name, uint32_t Value)
|
||||
{ uint8_t Len=Format_String(Line, Name);
|
||||
Len+=Format_String(Line+Len, "=");
|
||||
Len+=Format_UnsDec(Line+Len, Value);
|
||||
Len+=Format_String(Line+Len, ";");
|
||||
Line[Len]=0; return Len; }
|
||||
|
||||
int Write_SignDec(char *Line, const char *Name, int32_t Value)
|
||||
{ uint8_t Len=Format_String(Line, Name);
|
||||
Len+=Format_String(Line+Len, "=");
|
||||
Len+=Format_SignDec(Line+Len, Value);
|
||||
Len+=Format_String(Line+Len, ";");
|
||||
Line[Len]=0; return Len; }
|
||||
|
||||
int Write_Float1(char *Line, const char *Name, int32_t Value)
|
||||
{ uint8_t Len=Format_String(Line, Name);
|
||||
Len+=Format_String(Line+Len, "=");
|
||||
Len+=Format_SignDec(Line+Len, Value, 2, 1);
|
||||
Len+=Format_String(Line+Len, ";");
|
||||
Line[Len]=0; return Len; }
|
||||
|
||||
int WriteFile(FILE *File)
|
||||
{ char Line[80];
|
||||
Write_Hex (Line, "Address" , Address , 6); strcat(Line, " # [24-bit]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_Hex (Line, "AddrType", AddrType, 1); strcat(Line, " # [2-bit]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_Hex (Line, "AcftType", AcftType, 1); strcat(Line, " # [4-bit]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_UnsDec (Line, "Console", CONbaud); strcat(Line, " # [bps]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_SignDec(Line, "TxPower", getTxPower()); strcat(Line, " # [ dBm]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_Float1 (Line, "FreqCorr", (int32_t)RFchipFreqCorr/10); strcat(Line, " # [kHz]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_SignDec(Line, "TempCorr", (int32_t)RFchipTempCorr ); strcat(Line, " # [degC]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_Float1 (Line, "PressCorr",(int32_t)PressCorr*10/4 ); strcat(Line, " # [Pa]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
return 8; }
|
||||
|
||||
int WriteFile(const char *Name = "/spiffs/TRACKER.CFG")
|
||||
{ FILE *File=fopen(Name, "wt"); if(File==0) return 0;
|
||||
int Lines=WriteFile(File);
|
||||
fclose(File); return Lines; }
|
||||
|
||||
} ;
|
||||
|
||||
#endif // __PARAMETERS_H__
|
||||
|
|
@ -0,0 +1,321 @@
|
|||
#include <stdint.h>
|
||||
|
||||
#include "hal.h"
|
||||
#include "proc.h"
|
||||
|
||||
#include "ogn.h"
|
||||
|
||||
#include "rf.h"
|
||||
#include "gps.h"
|
||||
|
||||
static char Line[128]; // for printing out to serial port, etc.
|
||||
|
||||
static LDPC_Decoder Decoder; // error corrector for the OGN Gallager code
|
||||
|
||||
// #define DEBUG_PRINT
|
||||
|
||||
// ==================================================================
|
||||
|
||||
// ---------------------------------------------------------------------------------------------------------------------------------------
|
||||
|
||||
static OGN_PrioQueue<16> RelayQueue; // received packets and candidates to be relayed
|
||||
|
||||
static void PrintRelayQueue(uint8_t Idx) // for debug
|
||||
{ uint8_t Len=0;
|
||||
// Len+=Format_String(Line+Len, "");
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
// Format_String(CONS_UART_Write, Line, Len);
|
||||
Line[Len++]='['; Len+=Format_Hex(Line+Len, Idx); Line[Len++]=']'; Line[Len++]=' ';
|
||||
Len+=RelayQueue.Print(Line+Len);
|
||||
Format_String(CONS_UART_Write, Line);
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
}
|
||||
|
||||
static bool GetRelayPacket(OGN_TxPacket *Packet) // prepare a packet to be relayed
|
||||
{ if(RelayQueue.Sum==0) return 0;
|
||||
XorShift32(RX_Random);
|
||||
uint8_t Idx=RelayQueue.getRand(RX_Random);
|
||||
if(RelayQueue.Packet[Idx].Rank==0) return 0;
|
||||
memcpy(Packet->Packet.Byte(), RelayQueue[Idx]->Byte(), OGN_Packet::Bytes);
|
||||
Packet->Packet.Header.RelayCount+=1;
|
||||
Packet->Packet.Whiten(); Packet->calcFEC();
|
||||
// PrintRelayQueue(Idx); // for debug
|
||||
RelayQueue.decrRank(Idx);
|
||||
return 1; }
|
||||
|
||||
static void CleanRelayQueue(uint32_t Time, uint32_t Delay=20)
|
||||
{ RelayQueue.cleanTime((Time-Delay)%60); }
|
||||
|
||||
// ---------------------------------------------------------------------------------------------------------------------------------------
|
||||
|
||||
static void ReadStatus(OGN_TxPacket &StatPacket)
|
||||
{
|
||||
|
||||
// uint16_t MCU_VCC = Measure_MCU_VCC(); // [0.001V]
|
||||
// StatPacket.Packet.EncodeVoltage(((MCU_VCC<<3)+62)/125); // [1/64V]
|
||||
// int16_t MCU_Temp = Measure_MCU_Temp(); // [0.1degC]
|
||||
// if(StatPacket.Packet.Status.Pressure==0) StatPacket.Packet.EncodeTemperature(MCU_Temp); // [0.1degC]
|
||||
StatPacket.Packet.Status.RadioNoise = RX_AverRSSI; // [-0.5dBm] write radio noise to the status packet
|
||||
|
||||
StatPacket.Packet.Status.TxPower = Parameters.getTxPower()-4;
|
||||
|
||||
uint16_t RxRate = RX_OGN_Count64;
|
||||
uint8_t RxRateLog2=0; RxRate>>=1; while(RxRate) { RxRate>>=1; RxRateLog2++; }
|
||||
StatPacket.Packet.Status.RxRate = RxRateLog2;
|
||||
|
||||
{ uint8_t Len=0;
|
||||
Len+=Format_String(Line+Len, "$POGNR,"); // NMEA report: radio status
|
||||
Len+=Format_UnsDec(Line+Len, RF_FreqPlan.Plan); // which frequency plan
|
||||
Line[Len++]=',';
|
||||
Len+=Format_UnsDec(Line+Len, RX_OGN_Count64); // number of OGN packets received
|
||||
Line[Len++]=',';
|
||||
Line[Len++]=',';
|
||||
Len+=Format_SignDec(Line+Len, -5*RX_AverRSSI, 2, 1); // average RF level (over all channels)
|
||||
Line[Len++]=',';
|
||||
Len+=Format_UnsDec(Line+Len, (uint16_t)TX_Credit);
|
||||
Line[Len++]=',';
|
||||
Len+=Format_SignDec(Line+Len, (int16_t)RF_Temp); // the temperature of the RF chip
|
||||
Line[Len++]=',';
|
||||
// Len+=Format_SignDec(Line+Len, MCU_Temp, 2, 1);
|
||||
Line[Len++]=',';
|
||||
// Len+=Format_UnsDec(Line+Len, (MCU_VCC+5)/10, 3, 2);
|
||||
|
||||
Len+=NMEA_AppendCheckCRNL(Line, Len); // append NMEA check-sum and CR+NL
|
||||
// LogLine(Line);
|
||||
// if(CONS_UART_Free()>=128)
|
||||
{ xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, Line, Len); // send the NMEA out to the console
|
||||
xSemaphoreGive(CONS_Mutex); }
|
||||
#ifdef WITH_SDLOG
|
||||
if(Log_Free()>=128)
|
||||
{ xSemaphoreTake(Log_Mutex, portMAX_DELAY);
|
||||
Format_String(Log_Write, Line, Len); // send the NMEA out to the log file
|
||||
xSemaphoreGive(Log_Mutex); }
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
// ---------------------------------------------------------------------------------------------------------------------------------------
|
||||
|
||||
static void ProcessRxPacket(OGN_RxPacket *RxPacket, uint8_t RxPacketIdx) // process every (correctly) received packet
|
||||
{ int32_t LatDist=0, LonDist=0; uint8_t Warn=0;
|
||||
if( RxPacket->Packet.Header.Other || RxPacket->Packet.Header.Encrypted ) return ; // status packet or encrypted: ignore
|
||||
uint8_t MyOwnPacket = ( RxPacket->Packet.Header.Address == Parameters.Address )
|
||||
&& ( RxPacket->Packet.Header.AddrType == Parameters.AddrType );
|
||||
bool DistOK = RxPacket->Packet.calcDistanceVector(LatDist, LonDist, GPS_Latitude, GPS_Longitude, GPS_LatCosine)>=0;
|
||||
if(DistOK)
|
||||
{ if(!MyOwnPacket)
|
||||
{ RxPacket->calcRelayRank(GPS_Altitude/10); // calculate the relay-rank (priority for relay)
|
||||
RelayQueue.addNew(RxPacketIdx); }
|
||||
uint8_t Len=RxPacket->WritePOGNT(Line); // print on the console as $POGNT
|
||||
if(!MyOwnPacket)
|
||||
{ xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, Line, Len);
|
||||
xSemaphoreGive(CONS_Mutex); }
|
||||
#ifdef WITH_LOOKOUT
|
||||
const LookOut_Target *Tgt=Look.ProcessTarget(RxPacket->Packet); // process the received target postion
|
||||
if(Tgt) Warn=Tgt->WarnLevel; // remember warning level of this target
|
||||
#ifdef WITH_BEEPER
|
||||
if(KNOB_Tick>12) Play(Play_Vol_1 | Play_Oct_2 | (7+2*Warn), 3+16*Warn); // if Knob>12 => make a beep for every received packet
|
||||
#endif
|
||||
#else // WITH_LOOKOUT
|
||||
#ifdef WITH_BEEPER
|
||||
if(KNOB_Tick>12) Play(Play_Vol_1 | Play_Oct_2 | 7, 3); // if Knob>12 => make a beep for every received packet
|
||||
#endif
|
||||
#endif // WITH_LOOKOUT
|
||||
#ifdef WITH_SDLOG
|
||||
if(Log_Free()>=128)
|
||||
{ xSemaphoreTake(Log_Mutex, portMAX_DELAY);
|
||||
Format_String(Log_Write, Line, Len);
|
||||
xSemaphoreGive(Log_Mutex); }
|
||||
#endif
|
||||
#ifdef WITH_PFLAA
|
||||
if(!MyOwnPacket)
|
||||
{ Len=RxPacket->Packet.WritePFLAA(Line, Warn, LatDist, LonDist, RxPacket->Packet.DecodeAltitude()-GPS_Altitude/10); // print on the console $
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, Line, Len);
|
||||
xSemaphoreGive(CONS_Mutex); }
|
||||
#endif
|
||||
#ifdef WITH_MAVLINK
|
||||
if(!MyOwnPacket)
|
||||
{ MAV_ADSB_VEHICLE MAV_RxReport;
|
||||
RxPacket->Packet.Encode(MAV_RxReport);
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
MAV_RxMsg::Send(sizeof(MAV_RxReport), MAV_Seq++, MAV_SysID, MAV_COMP_ID_ADSB, MAV_ID_ADSB_VEHICLE, (const uint8_t *)&MAV_RxReport, CONS_UART_Write);
|
||||
xSemaphoreGive(CONS_Mutex); }
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
static void DecodeRxPacket(RFM_RxPktData *RxPkt)
|
||||
{
|
||||
uint8_t RxPacketIdx = RelayQueue.getNew(); // get place for this new packet
|
||||
OGN_RxPacket *RxPacket = RelayQueue[RxPacketIdx];
|
||||
// PrintRelayQueue(RxPacketIdx); // for debug
|
||||
// RxPacket->RxRSSI=RxPkt.RSSI;
|
||||
// TickType_t ExecTime=xTaskGetTickCount();
|
||||
|
||||
RX_OGN_Packets++;
|
||||
uint8_t Check = RxPkt->Decode(*RxPacket, Decoder);
|
||||
#ifdef DEBUG_PRINT
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, "RxPacket: ");
|
||||
Format_Hex(CONS_UART_Write, RxPacket->Packet.HeaderWord);
|
||||
CONS_UART_Write(' ');
|
||||
Format_UnsDec(CONS_UART_Write, (uint16_t)Check);
|
||||
CONS_UART_Write('/');
|
||||
Format_UnsDec(CONS_UART_Write, (uint16_t)RxPacket->RxErr);
|
||||
Format_String(CONS_UART_Write, "\n");
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
if( (Check==0) && (RxPacket->RxErr<15) ) // what limit on number of detected bit errors ?
|
||||
{ RxPacket->Packet.Dewhiten();
|
||||
ProcessRxPacket(RxPacket, RxPacketIdx); }
|
||||
|
||||
}
|
||||
|
||||
// -------------------------------------------------------------------------------------------------------------------
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
#endif
|
||||
void vTaskPROC(void* pvParameters)
|
||||
{
|
||||
RelayQueue.Clear();
|
||||
|
||||
OGN_TxPacket PosPacket; // position packet
|
||||
uint32_t PosTime=0; // [sec] when the position was recorded
|
||||
OGN_TxPacket StatPacket; // status report packet
|
||||
|
||||
for( ; ; )
|
||||
{ vTaskDelay(1);
|
||||
static uint32_t PrevSlotTime=0;
|
||||
uint32_t SlotTime = TimeSync_Time();
|
||||
if(TimeSync_msTime()<300) SlotTime--;
|
||||
|
||||
RFM_RxPktData *RxPkt = RF_RxFIFO.getRead(); // check for new received packets
|
||||
if(RxPkt)
|
||||
{
|
||||
#ifdef DEBUG_PRINT
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_Time()%60, 2);
|
||||
CONS_UART_Write('.');
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_msTime(), 3);
|
||||
Format_String(CONS_UART_Write, " RF_RxFIFO -> ");
|
||||
RxPkt->Print(CONS_UART_Write);
|
||||
// CONS_UART_Write('\r'); CONS_UART_Write('\n');
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
DecodeRxPacket(RxPkt); // decode and process the received packet
|
||||
RF_RxFIFO.Read(); }
|
||||
|
||||
if(SlotTime==PrevSlotTime) continue;
|
||||
PrevSlotTime=SlotTime;
|
||||
// this part of the loop is executed only once per slot-time
|
||||
GPS_Position *Position = GPS_getPosition();
|
||||
if(Position) Position->EncodeStatus(StatPacket.Packet); // encode GPS altitude and pressure
|
||||
if( Position && Position->Ready && (!Position->Sent) && Position->GPS && Position->isValid() )
|
||||
{ int16_t AverSpeed=GPS_AverageSpeed(); // [0.1m/s] average speed, including the vertical speed
|
||||
RF_FreqPlan.setPlan(Position->Latitude, Position->Longitude); // set the frequency plan according to the GPS position
|
||||
/*
|
||||
#ifdef DEBUG_PRINT
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_Time()%60);
|
||||
CONS_UART_Write('.');
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_msTime(), 3);
|
||||
Format_String(CONS_UART_Write, " -> Sent\n");
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
*/
|
||||
PosTime=Position->getUnixTime();
|
||||
PosPacket.Packet.HeaderWord=0;
|
||||
PosPacket.Packet.Header.Address = Parameters.Address; // set address
|
||||
PosPacket.Packet.Header.AddrType = Parameters.AddrType; // address-type
|
||||
PosPacket.Packet.calcAddrParity(); // parity of (part of) the header
|
||||
Position->Encode(PosPacket.Packet); // encode position/altitude/speed/etc. from GPS position
|
||||
PosPacket.Packet.Position.Stealth = Parameters.Stealth;
|
||||
PosPacket.Packet.Position.AcftType = Parameters.AcftType; // aircraft-type
|
||||
OGN_TxPacket *TxPacket = RF_TxFIFO.getWrite();
|
||||
TxPacket->Packet = PosPacket.Packet; // copy the position packet to the TxFIFO
|
||||
TxPacket->Packet.Whiten(); TxPacket->calcFEC(); // whiten and calculate FEC code
|
||||
#ifdef DEBUG_PRINT
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_Time()%60);
|
||||
CONS_UART_Write('.');
|
||||
Format_UnsDec(CONS_UART_Write, TimeSync_msTime(), 3);
|
||||
Format_String(CONS_UART_Write, " TxFIFO <- ");
|
||||
Format_Hex(CONS_UART_Write, TxPacket->Packet.HeaderWord);
|
||||
CONS_UART_Write('\r'); CONS_UART_Write('\n');
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
XorShift32(RX_Random);
|
||||
if( (AverSpeed>10) || ((RX_Random&0x3)==0) ) // send only some positions if the speed is less than 1m/s
|
||||
RF_TxFIFO.Write(); // complete the write into the TxFIFO
|
||||
Position->Sent=1;
|
||||
|
||||
} else // if GPS position is not complete, contains no valid position, etc.
|
||||
{ if((SlotTime-PosTime)>=30) { PosPacket.Packet.Position.Time=0x3F; } // if no valid position for more than 30 seconds then set the time as unknown for the transmitted packet
|
||||
OGN_TxPacket *TxPacket = RF_TxFIFO.getWrite();
|
||||
TxPacket->Packet = PosPacket.Packet;
|
||||
TxPacket->Packet.Whiten(); TxPacket->calcFEC(); // whiten and calculate FEC code
|
||||
#ifdef DEBUG_PRINT
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, "TxFIFO: ");
|
||||
Format_Hex(CONS_UART_Write, TxPacket->Packet.HeaderWord);
|
||||
CONS_UART_Write('\r'); CONS_UART_Write('\n');
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
XorShift32(RX_Random);
|
||||
if(PosTime && ((RX_Random&0x3)==0) ) // send if some position in the packet and at 1/4 normal rate
|
||||
RF_TxFIFO.Write(); // complete the write into the TxFIFO
|
||||
if(Position) Position->Sent=1;
|
||||
}
|
||||
#ifdef DEBUG_PRINT
|
||||
// char Line[128];
|
||||
Line[0]='0'+RF_TxFIFO.Full(); Line[1]=' '; // print number of packets in the TxFIFO
|
||||
RelayQueue.Print(Line+2); // dump the relay queue
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, Line);
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
StatPacket.Packet.HeaderWord=0;
|
||||
StatPacket.Packet.Header.Address = Parameters.Address; // set address
|
||||
StatPacket.Packet.Header.AddrType = Parameters.AddrType; // address-type
|
||||
StatPacket.Packet.Header.Other=1;
|
||||
StatPacket.Packet.calcAddrParity(); // parity of (part of) the header
|
||||
StatPacket.Packet.Status.Hardware=HARDWARE_ID;
|
||||
StatPacket.Packet.Status.Firmware=SOFTWARE_ID;
|
||||
|
||||
ReadStatus(StatPacket);
|
||||
XorShift32(RX_Random);
|
||||
if( ((RX_Random&0x1F)==0) && (RF_TxFIFO.Full()<2) )
|
||||
{ OGN_TxPacket *StatusPacket = RF_TxFIFO.getWrite();
|
||||
*StatusPacket = StatPacket;
|
||||
StatusPacket->Packet.Whiten();
|
||||
StatusPacket->calcFEC();
|
||||
RF_TxFIFO.Write();
|
||||
}
|
||||
|
||||
while(RF_TxFIFO.Full()<2)
|
||||
{ OGN_TxPacket *RelayPacket = RF_TxFIFO.getWrite();
|
||||
if(!GetRelayPacket(RelayPacket)) break;
|
||||
// xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
// Format_String(CONS_UART_Write, "Relayed: ");
|
||||
// Format_Hex(CONS_UART_Write, RelayPacket->Packet.HeaderWord);
|
||||
// CONS_UART_Write('\r'); CONS_UART_Write('\n');
|
||||
// xSemaphoreGive(CONS_Mutex);
|
||||
#ifdef DEBUG_PRINT
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, "TxFIFO: ");
|
||||
Format_Hex(CONS_UART_Write, RelayPacket->Packet.HeaderWord);
|
||||
CONS_UART_Write('\r'); CONS_UART_Write('\n');
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
RF_TxFIFO.Write();
|
||||
}
|
||||
CleanRelayQueue(SlotTime);
|
||||
|
||||
}
|
||||
|
||||
|
||||
}
|
|
@ -0,0 +1,5 @@
|
|||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
#endif
|
||||
void vTaskPROC(void* pvParameters);
|
||||
|
|
@ -0,0 +1,299 @@
|
|||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "freertos/semphr.h"
|
||||
|
||||
#include "hal.h"
|
||||
#include "rf.h"
|
||||
|
||||
#include "timesync.h"
|
||||
#include "lowpass2.h"
|
||||
|
||||
// ===============================================================================================
|
||||
|
||||
// OGN SYNC: 0x0AF3656C encoded in Manchester
|
||||
static const uint8_t OGN_SYNC[8] = { 0xAA, 0x66, 0x55, 0xA5, 0x96, 0x99, 0x96, 0x5A };
|
||||
|
||||
static RFM_TRX TRX; // radio transceiver
|
||||
|
||||
uint8_t RX_AverRSSI; // [-0.5dBm] average RSSI
|
||||
int8_t RF_Temp; // [degC] temperature of the RF chip: uncalibrated
|
||||
|
||||
static uint32_t RF_SlotTime; // [sec] UTC time which belongs to the current time slot (0.3sec late by GPS UTC)
|
||||
FreqPlan RF_FreqPlan; // frequency hopping pattern calculator
|
||||
|
||||
FIFO<RFM_RxPktData, 16> RF_RxFIFO; // buffer for received packets
|
||||
FIFO<OGN_TxPacket, 4> RF_TxFIFO; // buffer for transmitted packets
|
||||
|
||||
uint16_t TX_Credit =0; // counts transmitted packets vs. time to avoid using more than 1% of the time
|
||||
|
||||
uint8_t RX_OGN_Packets=0; // [packets] counts received packets
|
||||
static LowPass2<uint32_t, 4,2,4> RX_RSSI; // low pass filter to average the RX noise
|
||||
|
||||
static Delay<uint8_t, 64> RX_OGN_CountDelay;
|
||||
uint16_t RX_OGN_Count64=0; // counts received packets for the last 64 seconds
|
||||
|
||||
uint32_t RX_Random=0x12345678; // Random number from LSB of RSSI readouts
|
||||
|
||||
void XorShift32(uint32_t &Seed) // simple random number generator
|
||||
{ Seed ^= Seed << 13;
|
||||
Seed ^= Seed >> 17;
|
||||
Seed ^= Seed << 5; }
|
||||
|
||||
static uint8_t RX_Channel=0; // (hopping) channel currently being received
|
||||
|
||||
static void SetTxChannel(uint8_t TxChan=RX_Channel) // default channel to transmit is same as the receive channel
|
||||
{
|
||||
#ifdef WITH_RFM69
|
||||
TRX.WriteTxPower(Parameters.getTxPower(), Parameters.isTxTypeHW()); // set TX for transmission
|
||||
#endif
|
||||
#ifdef WITH_RFM95
|
||||
TRX.WriteTxPower(Parameters.getTxPower()); // set TX for transmission
|
||||
#endif
|
||||
TRX.setChannel(TxChan&0x7F);
|
||||
TRX.WriteSYNC(8, 7, OGN_SYNC); } // Full SYNC for TX
|
||||
|
||||
static void SetRxChannel(uint8_t RxChan=RX_Channel)
|
||||
{ TRX.WriteTxPowerMin(); // setup for RX
|
||||
TRX.setChannel(RxChan&0x7F);
|
||||
TRX.WriteSYNC(7, 7, OGN_SYNC); } // Shorter SYNC for RX
|
||||
|
||||
static uint8_t ReceivePacket(void) // see if a packet has arrived
|
||||
{ if(!TRX.DIO0_isOn()) return 0; // DIO0 line HIGH signals a new packet has arrived
|
||||
uint8_t RxRSSI = TRX.ReadRSSI(); // signal strength for the received packet
|
||||
RX_Random = (RX_Random<<1) | (RxRSSI&1); // use the lowest bit to add entropy
|
||||
|
||||
RFM_RxPktData *RxPkt = RF_RxFIFO.getWrite();
|
||||
RxPkt->Time = RF_SlotTime; // store reception time
|
||||
RxPkt->msTime = TimeSync_msTime(); if(RxPkt->msTime<200) RxPkt->msTime+=1000;
|
||||
RxPkt->Channel = RX_Channel; // store reception channel
|
||||
RxPkt->RSSI = RxRSSI; // store signal strength
|
||||
TRX.ReadPacket(RxPkt->Data, RxPkt->Err); // get the packet data from the FIFO
|
||||
// PktData.Print(); // for debug
|
||||
|
||||
RF_RxFIFO.Write(); // complete the write to the receiver FIFO
|
||||
// TRX.WriteMode(RFM69_OPMODE_RX); // back to receive (but we already have AutoRxRestart)
|
||||
return 1; } // return: 1 packet we have received
|
||||
|
||||
static uint32_t ReceiveUntil(TickType_t End)
|
||||
{ uint32_t Count=0;
|
||||
for( ; ; )
|
||||
{ Count+=ReceivePacket();
|
||||
int32_t Left = End-xTaskGetTickCount();
|
||||
if(Left<=0) break;
|
||||
vTaskDelay(1); }
|
||||
return Count; }
|
||||
|
||||
static uint32_t ReceiveFor(TickType_t Ticks) // keep receiving packets for given period of time
|
||||
{ return ReceiveUntil(xTaskGetTickCount()+Ticks); }
|
||||
|
||||
static uint8_t Transmit(uint8_t TxChan, const uint8_t *PacketByte, uint8_t Thresh, uint8_t MaxWait=7)
|
||||
{
|
||||
if(PacketByte==0) return 0; // if no packet to send: simply return
|
||||
|
||||
if(MaxWait)
|
||||
{ for( ; MaxWait; MaxWait--) // wait for a given maximum time for a free radio channel
|
||||
{
|
||||
#ifdef WITH_RFM69
|
||||
TRX.TriggerRSSI();
|
||||
#endif
|
||||
vTaskDelay(1);
|
||||
uint8_t RxRSSI=TRX.ReadRSSI();
|
||||
RX_Random = (RX_Random<<1) | (RxRSSI&1);
|
||||
if(RxRSSI>=Thresh) break; }
|
||||
if(MaxWait==0) return 0; }
|
||||
|
||||
TRX.WriteMode(RF_OPMODE_STANDBY); // switch to standby
|
||||
// vTaskPrioritySet(0, tskIDLE_PRIORITY+2);
|
||||
vTaskDelay(1);
|
||||
SetTxChannel(TxChan);
|
||||
|
||||
TRX.ClearIrqFlags();
|
||||
TRX.WritePacket(PacketByte); // write packet into FIFO
|
||||
TRX.WriteMode(RF_OPMODE_TRANSMITTER); // transmit
|
||||
vTaskDelay(5); // wait 5ms
|
||||
uint8_t Break=0;
|
||||
for(uint16_t Wait=400; Wait; Wait--) // wait for transmission to end
|
||||
{ // if(!TRX.DIO0_isOn()) break;
|
||||
// uint8_t Mode=TRX.ReadMode();
|
||||
uint16_t Flags=TRX.ReadIrqFlags();
|
||||
// if(Mode!=RF_OPMODE_TRANSMITTER) break;
|
||||
if(Flags&RF_IRQ_PacketSent) Break++;
|
||||
if(Break>=2) break; }
|
||||
TRX.WriteMode(RF_OPMODE_STANDBY); // switch to standy
|
||||
// vTaskPrioritySet(0, tskIDLE_PRIORITY+2);
|
||||
|
||||
SetRxChannel();
|
||||
TRX.WriteMode(RF_OPMODE_RECEIVER); // back to receive mode
|
||||
return 1; }
|
||||
// make a time-slot: listen for packets and transmit given PacketByte$
|
||||
static void TimeSlot(uint8_t TxChan, uint32_t SlotLen, const uint8_t *PacketByte, uint8_t Rx_RSSI, uint8_t MaxWait=8, uint32_t TxTime=0)
|
||||
{ TickType_t Start = xTaskGetTickCount(); // when the slot started
|
||||
TickType_t End = Start + SlotLen; // when should it end
|
||||
uint32_t MaxTxTime = SlotLen-8-MaxWait; // time limit when transmision could start
|
||||
if( (TxTime==0) || (TxTime>=MaxTxTime) ) TxTime = RX_Random%MaxTxTime; // if TxTime out of limits, setup a random TxTime
|
||||
TickType_t Tx = Start + TxTime; // Tx = the moment to start transmission
|
||||
ReceiveUntil(Tx); // listen until this time comes
|
||||
if( (TX_Credit) && (PacketByte) ) // when packet to transmit is given and there is still TX credit left:
|
||||
TX_Credit-=Transmit(TxChan, PacketByte, Rx_RSSI, MaxWait); // attempt to transmit the packet
|
||||
ReceiveUntil(End); // listen till the end of the time-slot
|
||||
}
|
||||
|
||||
static void SetFreqPlan(void)
|
||||
{ TRX.setBaseFrequency(RF_FreqPlan.BaseFreq); // set the base frequency (recalculate to RFM69 internal synth. units)
|
||||
TRX.setChannelSpacing(RF_FreqPlan.ChanSepar); // set the channel separation
|
||||
TRX.setFrequencyCorrection(10*Parameters.RFchipFreqCorr); // set the fine correction (to counter the Xtal error)
|
||||
}
|
||||
|
||||
static uint8_t StartRFchip(void)
|
||||
{ TRX.RESET(1); // RESET active
|
||||
vTaskDelay(10); // wait 10ms
|
||||
TRX.RESET(0); // RESET released
|
||||
vTaskDelay(10); // wait 10ms
|
||||
SetFreqPlan(); // set TRX base frequency and channel separation after the frequency hopp$
|
||||
TRX.Configure(0, OGN_SYNC); // setup RF chip parameters and set to channel #0
|
||||
TRX.WriteMode(RF_OPMODE_STANDBY); // set RF chip mode to STANDBY
|
||||
return TRX.ReadVersion(); } // read the RF chip version and return it
|
||||
|
||||
extern "C"
|
||||
void vTaskRF(void* pvParameters)
|
||||
{
|
||||
RF_RxFIFO.Clear(); // clear receive/transmit packet FIFO's
|
||||
RF_TxFIFO.Clear();
|
||||
|
||||
#ifdef USE_BLOCK_SPI
|
||||
TRX.TransferBlock = RFM_TransferBlock;
|
||||
#else
|
||||
TRX.Select = RFM_Select;
|
||||
TRX.Deselect = RFM_Deselect;
|
||||
TRX.TransferByte = RFM_TransferByte;
|
||||
#endif
|
||||
TRX.DIO0_isOn = RFM_DIO0_isOn;
|
||||
TRX.RESET = RFM_RESET;
|
||||
|
||||
RF_FreqPlan.setPlan(0); // 1 = Europe/Africa, 2 = USA/CA, 3 = Australia and South America
|
||||
|
||||
vTaskDelay(5);
|
||||
|
||||
for( ; ; )
|
||||
{ uint8_t ChipVersion = StartRFchip();
|
||||
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, "TaskRF: ");
|
||||
CONS_UART_Write('v'); Format_Hex(CONS_UART_Write, ChipVersion);
|
||||
CONS_UART_Write('\r'); CONS_UART_Write('\n');
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
|
||||
if( (ChipVersion!=0x00) && (ChipVersion!=0xFF) ) break; // only break the endless loop then an RF chip is detected
|
||||
vTaskDelay(1000);
|
||||
}
|
||||
|
||||
TX_Credit = 0; // count slots and packets transmitted: to keep the rule of 1% transmitter duty cycle
|
||||
RX_OGN_Packets = 0; // count received packets per every second (two time slots)
|
||||
|
||||
RX_OGN_Count64 = 0;
|
||||
RX_OGN_CountDelay.Clear();
|
||||
|
||||
RX_Channel = RF_FreqPlan.getChannel(TimeSync_Time(), 0, 1); // set initial RX channel
|
||||
SetRxChannel();
|
||||
TRX.WriteMode(RF_OPMODE_RECEIVER);
|
||||
|
||||
RX_RSSI.Set(2*112);
|
||||
|
||||
for( ; ; )
|
||||
{
|
||||
|
||||
uint32_t RxRssiSum=0; uint16_t RxRssiCount=0; // measure the average RSSI for lower frequency
|
||||
do
|
||||
{ ReceivePacket(); // keep checking for received packets
|
||||
#ifdef WITH_RFM69
|
||||
TRX.TriggerRSSI();
|
||||
#endif
|
||||
vTaskDelay(1);
|
||||
uint8_t RxRSSI=TRX.ReadRSSI(); // measure the channel noise level
|
||||
RX_Random = (RX_Random<<1) | (RxRSSI&1);
|
||||
RxRssiSum+=RxRSSI; RxRssiCount++;
|
||||
} while(TimeSync_msTime()<270); // until 300ms from the PPS
|
||||
RX_RSSI.Process(RxRssiSum/RxRssiCount); // [-0.5dBm] average noise on channel
|
||||
|
||||
TRX.WriteMode(RF_OPMODE_STANDBY); // switch to standy
|
||||
vTaskDelay(1);
|
||||
SetFreqPlan();
|
||||
|
||||
RX_AverRSSI=RX_RSSI.getOutput();
|
||||
|
||||
RX_OGN_Count64 += RX_OGN_Packets - RX_OGN_CountDelay.Input(RX_OGN_Packets); // add OGN packets received, subtract packets received 64 second$
|
||||
|
||||
RX_OGN_Packets=0; // clear the received packet count
|
||||
|
||||
StartRFchip(); // reset and rewrite the RF chip config
|
||||
|
||||
#ifdef WITH_RFM69
|
||||
TRX.TriggerTemp(); // trigger RF chip temperature readout
|
||||
vTaskDelay(1); // while(TRX.RunningTemp()) taskYIELD(); // wait for conversion to be ready
|
||||
RF_Temp= 165-TRX.ReadTemp(); // [degC] read RF chip temperature
|
||||
#endif
|
||||
#ifdef WITH_RFM95
|
||||
RF_Temp= 15-TRX.ReadTemp(); // [degC] read RF chip temperature
|
||||
#endif
|
||||
RF_Temp+=Parameters.RFchipTempCorr;
|
||||
// Note: on RFM95 temperature sens does not work in STANDBY
|
||||
RF_SlotTime = TimeSync_Time();
|
||||
uint8_t TxChan = RF_FreqPlan.getChannel(RF_SlotTime, 0, 1); // tranmsit channel
|
||||
RX_Channel = TxChan;
|
||||
SetRxChannel();
|
||||
// here we can read the chip temperature
|
||||
TRX.WriteMode(RF_OPMODE_RECEIVER); // switch to receive mode
|
||||
vTaskDelay(1);
|
||||
|
||||
RxRssiSum=0; RxRssiCount=0; // measure the average RSSI for the upper frequency
|
||||
do
|
||||
{ ReceivePacket(); // check for packets being received ?
|
||||
#ifdef WITH_RFM69
|
||||
TRX.TriggerRSSI(); // start RSSI measurement
|
||||
#endif
|
||||
vTaskDelay(1);
|
||||
uint8_t RxRSSI=TRX.ReadRSSI(); // read RSSI
|
||||
RX_Random = (RX_Random<<1) | (RxRSSI&1); // take lower bit for random number generator
|
||||
RxRssiSum+=RxRSSI; RxRssiCount++;
|
||||
} while(TimeSync_msTime()<350); // keep going until 400 ms after PPS
|
||||
RX_RSSI.Process(RxRssiSum/RxRssiCount); // [-0.5dBm] average noise on channel
|
||||
|
||||
TX_Credit+=2; if(TX_Credit>7200) TX_Credit=7200; // count the transmission credit
|
||||
|
||||
XorShift32(RX_Random);
|
||||
uint32_t TxTime = (RX_Random&0x3F)+1; TxTime*=6; TxTime+=50; // random transmission time: (1..64)*6+50 [ms]
|
||||
|
||||
const uint8_t *TxPktData0=0;
|
||||
const uint8_t *TxPktData1=0;
|
||||
const OGN_TxPacket *TxPkt0 = RF_TxFIFO.getRead(0); // get 1st packet from TxFIFO
|
||||
const OGN_TxPacket *TxPkt1 = RF_TxFIFO.getRead(1); // get 2nd packet from TxFIFO
|
||||
if(TxPkt0) TxPktData0=TxPkt0->Byte(); // if 1st is not NULL then get its data
|
||||
if(TxPkt1) TxPktData1=TxPkt1->Byte(); // if 2nd if not NULL then get its data
|
||||
else TxPktData1=TxPktData0; // but if NULL then take copy of the 1st packet
|
||||
|
||||
if(TxPkt0) // if 1st packet is not NULL
|
||||
{ if( (RX_Channel!=TxChan) && (TxPkt0->Packet.Header.RelayCount==0) )
|
||||
{ const uint8_t *Tmp=TxPktData0; TxPktData0=TxPktData1; TxPktData1=Tmp; } // swap 1st and 2nd packet data
|
||||
}
|
||||
TimeSlot(TxChan, 800-TimeSync_msTime(), TxPktData0, RX_AverRSSI, 0, TxTime); // run a Time-Slot till 0.800sec
|
||||
|
||||
TRX.WriteMode(RF_OPMODE_STANDBY); // switch to receive mode
|
||||
TxChan = RF_FreqPlan.getChannel(RF_SlotTime, 1, 1); // transmit channel
|
||||
RX_Channel = TxChan;
|
||||
|
||||
SetRxChannel();
|
||||
TRX.WriteMode(RF_OPMODE_RECEIVER); // switch to receive mode
|
||||
|
||||
XorShift32(RX_Random);
|
||||
TxTime = (RX_Random&0x3F)+1; TxTime*=6;
|
||||
|
||||
TimeSlot(TxChan, 1250-TimeSync_msTime(), TxPktData1, RX_AverRSSI, 0, TxTime);
|
||||
|
||||
if(TxPkt0) RF_TxFIFO.Read();
|
||||
if(TxPkt1) RF_TxFIFO.Read();
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// ======================================================================================
|
|
@ -0,0 +1,30 @@
|
|||
#include <stdint.h>
|
||||
|
||||
#include "hal.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
||||
#include "ogn.h"
|
||||
#include "rfm.h"
|
||||
#include "fifo.h"
|
||||
#include "freqplan.h"
|
||||
|
||||
extern FIFO<RFM_RxPktData, 16> RF_RxFIFO; // buffer for received packets
|
||||
extern FIFO<OGN_TxPacket, 4> RF_TxFIFO; // buffer for transmitted packets
|
||||
|
||||
extern uint8_t RX_OGN_Packets; // [packets] counts received packets
|
||||
extern uint8_t RX_AverRSSI; // [-0.5dBm] average RSSI
|
||||
extern int8_t RF_Temp; // [degC] temperature of the RF chip: uncalibrated
|
||||
extern FreqPlan RF_FreqPlan; // frequency hopping pattern calculator
|
||||
extern uint16_t TX_Credit; // counts transmitted packets vs. time to avoid using more than 1% of the time
|
||||
extern uint16_t RX_OGN_Count64; // counts received packets for the last 64 seconds
|
||||
extern uint32_t RX_Random; // Random number from LSB of RSSI readouts
|
||||
|
||||
void XorShift32(uint32_t &Seed); // simple random number generator
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
#endif
|
||||
void vTaskRF(void* pvParameters);
|
||||
|
|
@ -0,0 +1,483 @@
|
|||
// -----------------------------------------------------------------------------------------------------------------------
|
||||
|
||||
#include "ogn.h"
|
||||
|
||||
class RFM_RxPktData // packet received by the RF chip
|
||||
{ public:
|
||||
static const uint8_t Bytes=26; // [bytes] number of bytes in the packet
|
||||
uint32_t Time; // [sec] Time slot
|
||||
uint16_t msTime; // [ms] reception time since the PPS[Time]
|
||||
uint8_t Channel; // [] channel where the packet has been recieved
|
||||
uint8_t RSSI; // [-0.5dBm]
|
||||
uint8_t Data[Bytes]; // Manchester decoded data bits/bytes
|
||||
uint8_t Err [Bytes]; // Manchester decoding errors
|
||||
|
||||
public:
|
||||
|
||||
void Print(void (*CONS_UART_Write)(char), uint8_t WithData=0) const
|
||||
{ // uint8_t ManchErr = Count1s(RxPktErr, 26);
|
||||
Format_String(CONS_UART_Write, "RxPktData: ");
|
||||
Format_UnsDec(CONS_UART_Write, Time);
|
||||
CONS_UART_Write('+');
|
||||
Format_UnsDec(CONS_UART_Write, msTime, 4, 3);
|
||||
CONS_UART_Write(' '); Format_Hex(CONS_UART_Write, Channel);
|
||||
CONS_UART_Write('/');
|
||||
Format_SignDec(CONS_UART_Write, -5*RSSI, 4, 1);
|
||||
Format_String(CONS_UART_Write, "dBm\n");
|
||||
if(WithData==0) return;
|
||||
for(uint8_t Idx=0; Idx<Bytes; Idx++)
|
||||
{ CONS_UART_Write(' '); Format_Hex(CONS_UART_Write, Data[Idx]); }
|
||||
CONS_UART_Write('\r'); CONS_UART_Write('\n');
|
||||
for(uint8_t Idx=0; Idx<Bytes; Idx++)
|
||||
{ CONS_UART_Write(' '); Format_Hex(CONS_UART_Write, Err[Idx]); }
|
||||
CONS_UART_Write('\r'); CONS_UART_Write('\n');
|
||||
}
|
||||
|
||||
bool NoErr(void) const
|
||||
{ for(uint8_t Idx=0; Idx<Bytes; Idx++)
|
||||
if(Err[Idx]) return 0;
|
||||
return 1; }
|
||||
|
||||
uint8_t ErrCount(void) const // count detected manchester errors
|
||||
{ uint8_t Count=0;
|
||||
for(uint8_t Idx=0; Idx<Bytes; Idx++)
|
||||
Count+=Count1s(Err[Idx]);
|
||||
return Count; }
|
||||
|
||||
uint8_t ErrCount(const uint8_t *Corr) const // count errors compared to data corrected by FEC
|
||||
{ uint8_t Count=0;
|
||||
for(uint8_t Idx=0; Idx<Bytes; Idx++)
|
||||
Count+=Count1s((uint8_t)((Data[Idx]^Corr[Idx])&(~Err[Idx])));
|
||||
return Count; }
|
||||
|
||||
uint8_t Decode(OGN_RxPacket &Packet, LDPC_Decoder &Decoder, uint8_t Iter=32) const
|
||||
{ uint8_t Check=0;
|
||||
uint8_t RxErr = ErrCount(); // conunt Manchester decoding errors
|
||||
Decoder.Input(Data, Err); // put data into the FEC decoder
|
||||
for( ; Iter; Iter--) // more loops is more chance to recover the packet
|
||||
{ Check=Decoder.ProcessChecks(); // do an iteration
|
||||
if(Check==0) break; } // if FEC all fine: break
|
||||
Decoder.Output(Packet.Packet.Byte()); // get corrected bytes into the OGN packet
|
||||
RxErr += ErrCount(Packet.Packet.Byte());
|
||||
if(RxErr>15) RxErr=15;
|
||||
Packet.RxErr = RxErr;
|
||||
Packet.RxChan = Channel;
|
||||
Packet.RxRSSI = RSSI;
|
||||
Packet.Corr = Check==0;
|
||||
return Check; }
|
||||
|
||||
} ;
|
||||
|
||||
// -----------------------------------------------------------------------------------------------------------------------
|
||||
|
||||
// OGN frequencies for Europe: 868.2 and 868.4 MHz
|
||||
// static const uint32_t OGN_BaseFreq = 868200000; // [Hz] base frequency
|
||||
// static const uint32_t OGN_ChanSpace = 0200000; // [Hz] channel spacing
|
||||
|
||||
// OGN frequencies for Australia: 917.0 base channel, with 0.4MHz channel raster and 24 hopping channels
|
||||
// static const uint32_t OGN_BaseFreq = 921400000; // [Hz] base frequency
|
||||
// static const uint32_t OGN_ChanSpace = 400000; // [Hz] channel spacing
|
||||
|
||||
// static const double XtalFreq = 32e6; // [MHz] RF chip crystal frequency
|
||||
//
|
||||
// static const uint32_t BaseFreq = floor(OGN_BaseFreq /(XtalFreq/(1<<19))+0.5); // conversion from RF frequency
|
||||
// static const uint32_t ChanSpace = floor(OGN_ChanSpace/(XtalFreq/(1<<19))+0.5); // to RF chip synthesizer setting
|
||||
|
||||
// integer formula to convert from frequency to the RFM69 scheme: IntFreq = ((Freq<<16)+ 20)/ 40; where Freq is in [100kHz]
|
||||
// or: IntFreq = ((Freq<<14)+ 50)/100; where Freq is in [ 10kHz]
|
||||
// or: IntFreq = ((Freq<<12)+125)/250; where Freq is in [ 1kHz]
|
||||
// or: IntFreq = ((Freq<<11)+ 62)/125; where Freq is in [ 1kHz]
|
||||
// 32-bit arythmetic is enough in the above formulas
|
||||
|
||||
|
||||
#ifdef WITH_RFM69
|
||||
|
||||
#include "sx1231.h" // register addresses and values for SX1231 = RFM69
|
||||
|
||||
#define REG_AFCCTRL 0x0B // AFC method
|
||||
|
||||
#define REG_TESTLNA 0x58 // Sensitivity boost ?
|
||||
#define REG_TESTPA1 0x5A // only present on RFM69HW/SX1231H
|
||||
#define REG_TESTPA2 0x5C // only present on RFM69HW/SX1231H
|
||||
#define REG_TESTDAGC 0x6F // Fading margin improvement ?
|
||||
#define REG_TESTAFC 0x71
|
||||
|
||||
#define RF_IRQ_AutoMode 0x0200
|
||||
|
||||
#endif // of WITH_RFM69
|
||||
|
||||
#ifdef WITH_RFM95
|
||||
|
||||
#include "sx1276.h"
|
||||
|
||||
#define RF_IRQ_PreambleDetect 0x0200
|
||||
|
||||
#endif // of WITH_RFM95
|
||||
|
||||
// bits in IrqFlags1 and IrfFlags2
|
||||
#define RF_IRQ_ModeReady 0x8000 // mode change done (between some modes)
|
||||
#define RF_IRQ_RxReady 0x4000
|
||||
#define RF_IRQ_TxReady 0x2000 //
|
||||
#define RF_IRQ_PllLock 0x1000 //
|
||||
#define RF_IRQ_Rssi 0x0800
|
||||
#define RF_IRQ_Timeout 0x0400
|
||||
//
|
||||
#define RF_IRQ_SyncAddrMatch 0x0100
|
||||
|
||||
#define RF_IRQ_FifoFull 0x0080 //
|
||||
#define RF_IRQ_FifoNotEmpty 0x0040 // at least one byte in the FIFO
|
||||
#define RF_IRQ_FifoLevel 0x0020 // more bytes than FifoThreshold
|
||||
#define RF_IRQ_FifoOverrun 0x0010 // write this bit to clear the FIFO
|
||||
#define RF_IRQ_PacketSent 0x0008 // packet transmission was completed
|
||||
#define RF_IRQ_PayloadReady 0x0004
|
||||
#define RF_IRQ_CrcOk 0x0002
|
||||
#define RF_IRQ_LowBat 0x0001
|
||||
|
||||
#include "manchester.h"
|
||||
|
||||
class RFM_TRX
|
||||
{ public: // hardware access functions
|
||||
|
||||
#ifdef USE_BLOCK_SPI // SPI transfers in blocks, implicit control of the SPI-select
|
||||
void (*TransferBlock)(uint8_t *Data, uint8_t Len);
|
||||
static const size_t MaxBlockLen = 64;
|
||||
uint8_t Block_Buffer[MaxBlockLen];
|
||||
|
||||
uint8_t *Block_Read(uint8_t Len, uint8_t Addr) // read given number of bytes from given Addr
|
||||
{ Block_Buffer[0]=Addr; memset(Block_Buffer+1, 0, Len);
|
||||
(*TransferBlock) (Block_Buffer, Len+1);
|
||||
return Block_Buffer+1; } // return the pointer to the data read from the given Addr
|
||||
|
||||
uint8_t *Block_Write(const uint8_t *Data, uint8_t Len, uint8_t Addr) // write given number of bytes to given Addr
|
||||
{ Block_Buffer[0] = Addr | 0x80; memcpy(Block_Buffer+1, Data, Len);
|
||||
// printf("Block_Write( [0x%02X, .. ], %d, 0x%02X) .. [0x%02X, 0x%02X, ...]\n", Data[0], Len, Addr, Block_Buffer[0], Block_Buffer[1]);
|
||||
(*TransferBlock) (Block_Buffer, Len+1);
|
||||
return Block_Buffer+1; }
|
||||
#else // SPI transfers as single bytes, explicit control of the SPI-select
|
||||
void (*Select)(void); // activate SPI select
|
||||
void (*Deselect)(void); // desactivate SPI select
|
||||
uint8_t (*TransferByte)(uint8_t); // exchange one byte through SPI
|
||||
#endif
|
||||
|
||||
bool (*DIO0_isOn)(void); // read DIO0 = packet is ready
|
||||
// bool (*DIO4_isOn)(void);
|
||||
void (*RESET)(uint8_t On); // activate or desactivate the RF chip reset
|
||||
|
||||
// the following are in units of the synthesizer with 8 extra bits of precision
|
||||
uint32_t BaseFrequency; // [32MHz/2^19/2^8] base frequency = channel #0
|
||||
int32_t FrequencyCorrection; // [32MHz/2^19/2^8] frequency correction (due to Xtal offset)
|
||||
uint32_t ChannelSpacing; // [32MHz/2^19/2^8] spacing between channels
|
||||
int16_t Channel; // [ integer] channel being used
|
||||
|
||||
// private:
|
||||
static uint32_t calcSynthFrequency(uint32_t Frequency) { return (((uint64_t)Frequency<<16)+7812)/15625; }
|
||||
|
||||
public:
|
||||
void setBaseFrequency(uint32_t Frequency=868200000) { BaseFrequency=calcSynthFrequency(Frequency); }
|
||||
void setChannelSpacing(uint32_t Spacing= 200000) { ChannelSpacing=calcSynthFrequency(Spacing); }
|
||||
void setFrequencyCorrection(int32_t Correction=0)
|
||||
{ if(Correction<0) FrequencyCorrection = -calcSynthFrequency(-Correction);
|
||||
else FrequencyCorrection = calcSynthFrequency( Correction); }
|
||||
void setChannel(int16_t newChannel)
|
||||
{ Channel=newChannel; WriteFreq((BaseFrequency+ChannelSpacing*Channel+FrequencyCorrection+128)>>8); }
|
||||
uint8_t getChannel(void) const { return Channel; }
|
||||
|
||||
#ifdef USE_BLOCK_SPI
|
||||
|
||||
static uint16_t SwapBytes(uint16_t Word) { return (Word>>8) | (Word<<8); }
|
||||
|
||||
uint8_t WriteByte(uint8_t Byte, uint8_t Addr=0) // write Byte
|
||||
{ // printf("WriteByte(0x%02X, 0x%02X)\n", Byte, Addr);
|
||||
uint8_t *Ret = Block_Write(&Byte, 1, Addr); return *Ret; }
|
||||
|
||||
void WriteWord(uint16_t Word, uint8_t Addr=0) // write Word => two bytes
|
||||
{ // printf("WriteWord(0x%04X, 0x%02X)\n", Word, Addr);
|
||||
uint16_t Swapped = SwapBytes(Word); Block_Write((uint8_t *)&Swapped, 2, Addr); }
|
||||
|
||||
uint8_t ReadByte (uint8_t Addr=0)
|
||||
{ uint8_t *Ret = Block_Read(1, Addr);
|
||||
// printf("ReadByte(0x%02X) => 0x%02X\n", Addr, *Ret );
|
||||
return *Ret; }
|
||||
|
||||
uint16_t ReadWord (uint8_t Addr=0)
|
||||
{ uint16_t *Ret = (uint16_t *)Block_Read(2, Addr);
|
||||
// printf("ReadWord(0x%02X) => 0x%04X\n", Addr, SwapBytes(*Ret) );
|
||||
return SwapBytes(*Ret); }
|
||||
|
||||
void WriteBytes(const uint8_t *Data, uint8_t Len, uint8_t Addr=0)
|
||||
{ Block_Write(Data, Len, Addr); }
|
||||
|
||||
void WriteFreq(uint32_t Freq) // [32MHz/2^19] Set center frequency in units of RFM69 synth.
|
||||
{ const uint8_t Addr = REG_FRFMSB;
|
||||
uint8_t Buff[4];
|
||||
Buff[0] = Freq>>16;
|
||||
Buff[1] = Freq>> 8;
|
||||
Buff[2] = Freq ;
|
||||
Buff[3] = 0;
|
||||
Block_Write(Buff, 3, Addr); }
|
||||
|
||||
void WritePacket(const uint8_t *Data, uint8_t Len=26) // write the packet data (26 bytes)
|
||||
{ uint8_t Packet[2*Len];
|
||||
uint8_t PktIdx=0;
|
||||
for(uint8_t Idx=0; Idx<Len; Idx++)
|
||||
{ uint8_t Byte=Data[Idx];
|
||||
Packet[PktIdx++]=ManchesterEncode[Byte>>4]; // software manchester encode every byte
|
||||
Packet[PktIdx++]=ManchesterEncode[Byte&0x0F];
|
||||
}
|
||||
Block_Write(Packet, 2*Len, REG_FIFO);
|
||||
}
|
||||
|
||||
void ReadPacket(uint8_t *Data, uint8_t *Err, uint8_t Len=26) // read packet data from FIFO
|
||||
{ uint8_t *Packet = Block_Read(2*Len, REG_FIFO); // read 2x26 bytes from the RF chip RxFIFO
|
||||
uint8_t PktIdx=0;
|
||||
for(uint8_t Idx=0; Idx<Len; Idx++) // loop over packet bytes
|
||||
{ uint8_t ByteH = Packet[PktIdx++];
|
||||
ByteH = ManchesterDecode[ByteH]; uint8_t ErrH=ByteH>>4; ByteH&=0x0F; // decode manchester, detect (some) errors
|
||||
uint8_t ByteL = Packet[PktIdx++];
|
||||
ByteL = ManchesterDecode[ByteL]; uint8_t ErrL=ByteL>>4; ByteL&=0x0F;
|
||||
Data[Idx]=(ByteH<<4) | ByteL;
|
||||
Err [Idx]=(ErrH <<4) | ErrL ;
|
||||
}
|
||||
}
|
||||
|
||||
#else // single Byte transfer SPI
|
||||
|
||||
private:
|
||||
uint8_t WriteByte(uint8_t Byte, uint8_t Addr=0) const // write Byte
|
||||
{ Select();
|
||||
TransferByte(Addr | 0x80);
|
||||
uint8_t Old=TransferByte(Byte);
|
||||
Deselect();
|
||||
return Old; }
|
||||
|
||||
uint16_t WriteWord(uint16_t Word, uint8_t Addr=0) const // write Word => two bytes
|
||||
{ Select();
|
||||
TransferByte(Addr | 0x80);
|
||||
uint16_t Old=TransferByte(Word>>8); // upper byte first
|
||||
Old = (Old<<8) | TransferByte(Word&0xFF); // lower byte second
|
||||
Deselect();
|
||||
return Old; }
|
||||
|
||||
void WriteBytes(const uint8_t *Data, uint8_t Len, uint8_t Addr=0) const
|
||||
{ Select();
|
||||
TransferByte(Addr | 0x80);
|
||||
for(uint8_t Idx=0; Idx<Len; Idx++)
|
||||
{ TransferByte(Data[Idx]); }
|
||||
Deselect(); }
|
||||
|
||||
uint8_t ReadByte (uint8_t Addr=0) const
|
||||
{ Select();
|
||||
TransferByte(Addr);
|
||||
uint8_t Byte=TransferByte(0);
|
||||
Deselect();
|
||||
return Byte; }
|
||||
|
||||
uint16_t ReadWord (uint8_t Addr=0) const
|
||||
{ Select();
|
||||
TransferByte(Addr);
|
||||
uint16_t Word=TransferByte(0);
|
||||
Word = (Word<<8) | TransferByte(0);
|
||||
Deselect();
|
||||
return Word; }
|
||||
|
||||
public:
|
||||
uint32_t WriteFreq(uint32_t Freq) const // [32MHz/2^19] Set center frequency in units of RFM69 synth.
|
||||
{ const uint8_t Addr = REG_FRFMSB;
|
||||
Select();
|
||||
TransferByte(Addr | 0x80);
|
||||
uint32_t Old = TransferByte(Freq>>16);
|
||||
Old = (Old<<8) | TransferByte(Freq>>8);
|
||||
Old = (Old<<8) | TransferByte(Freq); // actual change in the frequency happens only when the LSB is written
|
||||
Deselect();
|
||||
return Old; } // return the previously set frequency
|
||||
|
||||
void WritePacket(const uint8_t *Data, uint8_t Len=26) const // write the packet data (26 bytes)
|
||||
{ const uint8_t Addr=REG_FIFO; // write to FIFO
|
||||
Select();
|
||||
TransferByte(Addr | 0x80);
|
||||
for(uint8_t Idx=0; Idx<Len; Idx++)
|
||||
{ uint8_t Byte=Data[Idx];
|
||||
TransferByte(ManchesterEncode[Byte>>4]); // software manchester encode every byte
|
||||
TransferByte(ManchesterEncode[Byte&0x0F]);
|
||||
}
|
||||
Deselect();
|
||||
}
|
||||
|
||||
void ReadPacket(uint8_t *Data, uint8_t *Err, uint8_t Len=26) const // read packet data from FIFO
|
||||
{ const uint8_t Addr=REG_FIFO;
|
||||
Select(); // select the RF chip: start SPI transfer
|
||||
TransferByte(Addr); // trasnfer the address/read: FIFO
|
||||
for(uint8_t Idx=0; Idx<Len; Idx++) // loop over packet byte
|
||||
{ uint8_t ByteH = 0;
|
||||
ByteH = TransferByte(ByteH);
|
||||
ByteH = ManchesterDecode[ByteH]; uint8_t ErrH=ByteH>>4; ByteH&=0x0F; // decode manchester, detect (some) errors
|
||||
uint8_t ByteL = 0;
|
||||
ByteL = TransferByte(ByteL);
|
||||
ByteL = ManchesterDecode[ByteL]; uint8_t ErrL=ByteL>>4; ByteL&=0x0F;
|
||||
Data[Idx]=(ByteH<<4) | ByteL;
|
||||
Err [Idx]=(ErrH <<4) | ErrL ;
|
||||
}
|
||||
Deselect(); // de-select RF chip: end of SPI transfer
|
||||
}
|
||||
|
||||
#endif // USE_BLOCK_SPI
|
||||
|
||||
#ifdef WITH_RFM69
|
||||
void WriteSYNC(uint8_t WriteSize, uint8_t SyncTol, const uint8_t *SyncData)
|
||||
{ if(SyncTol>7) SyncTol=7; // no more than 7 bit errors can be tolerated on SYNC
|
||||
if(WriteSize>8) WriteSize=8; // up to 8 bytes of SYNC can be programmed
|
||||
WriteBytes(SyncData+(8-WriteSize), WriteSize, REG_SYNCVALUE1); // write the SYNC, skip some initial bytes
|
||||
WriteByte( 0x80 | ((WriteSize-1)<<3) | SyncTol, REG_SYNCCONFIG); // write SYNC length [bytes] and tolerance to errors [bits]
|
||||
WriteWord( 9-WriteSize, REG_PREAMBLEMSB); } // write preamble length [bytes] (page 71)
|
||||
// ^ 8 or 9 ?
|
||||
#endif
|
||||
|
||||
#ifdef WITH_RFM95
|
||||
void WriteSYNC(uint8_t WriteSize, uint8_t SyncTol, const uint8_t *SyncData)
|
||||
{ if(SyncTol>7) SyncTol=7;
|
||||
if(WriteSize>8) WriteSize=8;
|
||||
WriteBytes(SyncData+(8-WriteSize), WriteSize, REG_SYNCVALUE1); // write the SYNC, skip some initial bytes
|
||||
WriteByte( 0x90 | (WriteSize-1), REG_SYNCCONFIG); // write SYNC length [bytes]
|
||||
WriteWord( 9-WriteSize, REG_PREAMBLEMSB); } // write preamble length [bytes] (page 71)
|
||||
// ^ 8 or 9 ?
|
||||
#endif
|
||||
|
||||
void WriteMode(uint8_t Mode=RF_OPMODE_STANDBY) { WriteByte(Mode, REG_OPMODE); } // SLEEP/STDBY/FSYNTH/TX/RX
|
||||
uint8_t ReadMode (void) { return ReadByte(REG_OPMODE); }
|
||||
uint8_t ModeReady(void) { return ReadByte(REG_IRQFLAGS1)&0x80; }
|
||||
|
||||
uint16_t ReadIrqFlags(void) { return ReadWord(REG_IRQFLAGS1); }
|
||||
|
||||
void ClearIrqFlags(void) { WriteWord(RF_IRQ_FifoOverrun | RF_IRQ_Rssi, REG_IRQFLAGS1); }
|
||||
|
||||
#ifdef WITH_RFM69
|
||||
void WriteTxPower_W(int8_t TxPower=10) const // [dBm] for RFM69W: -18..+13dBm
|
||||
{ if(TxPower<(-18)) TxPower=(-18); // check limits
|
||||
if(TxPower> 13 ) TxPower= 13 ;
|
||||
WriteByte( 0x80+(18+TxPower), REG_PALEVEL);
|
||||
WriteByte( 0x1A , REG_OCP);
|
||||
WriteByte( 0x55 , REG_TESTPA1);
|
||||
WriteByte( 0x70 , REG_TESTPA2);
|
||||
}
|
||||
|
||||
void WriteTxPower_HW(int8_t TxPower=10) const // [dBm] // for RFM69HW: -14..+20dBm
|
||||
{ if(TxPower<(-14)) TxPower=(-14); // check limits
|
||||
if(TxPower> 20 ) TxPower= 20 ;
|
||||
if(TxPower<=17)
|
||||
{ WriteByte( 0x60+(14+TxPower), REG_PALEVEL);
|
||||
WriteByte( 0x1A , REG_OCP);
|
||||
WriteByte( 0x55 , REG_TESTPA1);
|
||||
WriteByte( 0x70 , REG_TESTPA2);
|
||||
} else
|
||||
{ WriteByte( 0x60+(11+TxPower), REG_PALEVEL);
|
||||
WriteByte( 0x0F , REG_OCP);
|
||||
WriteByte( 0x5D , REG_TESTPA1);
|
||||
WriteByte( 0x7C , REG_TESTPA2);
|
||||
}
|
||||
}
|
||||
|
||||
void WriteTxPower(int8_t TxPower, uint8_t isHW) const
|
||||
{ WriteByte( 0x09, REG_PARAMP); // Tx ramp up/down time 0x06=100us, 0x09=40us, 0x0C=20us, 0x0F=10us (page 66)
|
||||
if(isHW) WriteTxPower_HW(TxPower);
|
||||
else WriteTxPower_W (TxPower); }
|
||||
|
||||
void WriteTxPowerMin(void) const { WriteTxPower_W(-18); } // set minimal Tx power and setup for reception
|
||||
|
||||
int Configure(int16_t Channel, const uint8_t *Sync)
|
||||
{ WriteMode(RF_OPMODE_STANDBY); // mode = STDBY
|
||||
ClearIrqFlags();
|
||||
WriteByte( 0x02, REG_DATAMODUL); // [0x00] Packet mode, FSK, 0x02: BT=0.5, 0x01: BT=1.0, 0x03: BT=0.3
|
||||
WriteWord(0x0140, REG_BITRATEMSB); // bit rate = 100kbps
|
||||
WriteWord(0x0333, REG_FDEVMSB); // FSK deviation = +/-50kHz
|
||||
setChannel(Channel); // operating channel
|
||||
WriteSYNC(8, 7, Sync); // SYNC pattern (setup for reception)
|
||||
WriteByte( 0x00, REG_PACKETCONFIG1); // [0x10] Fixed size packet, no DC-free encoding, no CRC, no address filtering
|
||||
WriteByte(0x80+51, REG_FIFOTHRESH); // [ ] TxStartCondition=FifoNotEmpty, FIFO threshold = 51 bytes
|
||||
WriteByte( 2*26, REG_PAYLOADLENGTH); // [0x40] Packet size = 26 bytes Manchester encoded into 52 bytes
|
||||
WriteByte( 0x02, REG_PACKETCONFIG2); // [0x02] disable encryption (it is permanent between resets !), AutoRxRestartOn=1
|
||||
WriteByte( 0x00, REG_AUTOMODES); // [0x00] all "none"
|
||||
WriteTxPowerMin(); // TxPower (setup for reception)
|
||||
WriteByte( 0x08, REG_LNA); // [0x08/88] bit #7 = LNA input impedance: 0=50ohm or 1=200ohm ?
|
||||
WriteByte( 2*112, REG_RSSITHRESH); // [0xE4] RSSI threshold = -112dBm
|
||||
WriteByte( 0x42, REG_RXBW); // [0x86/55] +/-125kHz Rx bandwidth => p.27+67 (A=100kHz, 2=125kHz, 9=200kHz, 1=250kHz)
|
||||
WriteByte( 0x82, REG_AFCBW); // [0x8A/8B] +/-125kHz Rx bandwidth while AFC
|
||||
WriteWord(0x4047, REG_DIOMAPPING1); // DIO signals: DIO0=01, DIO4=01, ClkOut=OFF
|
||||
// RX: DIO0 = PayloadReady, DIO4 = Rssi
|
||||
// TX: DIO0 = TxReady, DIO4 = TxReady
|
||||
WriteByte( 0x1B, REG_TESTLNA); // [0x1B] 0x2D = LNA sensitivity up by 3dB, 0x1B = default
|
||||
WriteByte( 0x30, REG_TESTDAGC); // [0x30] 0x20 when AfcLowBetaOn, 0x30 otherwise-> page 25
|
||||
WriteByte( 0x00, REG_AFCFEI); // [0x00] AfcAutoOn=0, AfcAutoclearOn=0
|
||||
WriteByte( 0x00, REG_AFCCTRL); // [0x00] 0x20 = AfcLowBetaOn=1 -> page 64 -> page 33
|
||||
WriteByte( +10, REG_TESTAFC); // [0x00] [488Hz] if AfcLowBetaOn
|
||||
return 0; }
|
||||
#endif
|
||||
|
||||
#ifdef WITH_RFM95
|
||||
|
||||
void WriteTxPower(int8_t TxPower=0)
|
||||
{ if(TxPower<2) TxPower=2;
|
||||
else if(TxPower>17) TxPower=17;
|
||||
// if(TxPower<=14)
|
||||
// { WriteByte(0x70 | TxPower , REG_PACONFIG);
|
||||
// }
|
||||
// else
|
||||
{ WriteByte(0xF0 | (TxPower-2), REG_PACONFIG);
|
||||
}
|
||||
}
|
||||
|
||||
void WriteTxPowerMin(void) { WriteTxPower(0); }
|
||||
|
||||
int Configure(int16_t Channel, const uint8_t *Sync)
|
||||
{ WriteMode(RF_OPMODE_STANDBY); // mode: STDBY, modulation: FSK, no LoRa
|
||||
// usleep(1000);
|
||||
WriteTxPower(0);
|
||||
// ClearIrqFlags();
|
||||
WriteWord(0x0140, REG_BITRATEMSB); // bit rate = 100kbps (32MHz/100000)
|
||||
// ReadWord(REG_BITRATEMSB);
|
||||
WriteWord(0x0333, REG_FDEVMSB); // FSK deviation = +/-50kHz [32MHz/(1<<19)]
|
||||
// ReadWord(REG_FDEVMSB);
|
||||
setChannel(Channel); // operating channel
|
||||
WriteSYNC(8, 7, Sync); // SYNC pattern (setup for reception)
|
||||
WriteByte( 0x8A, REG_PREAMBLEDETECT); // preamble detect: 1 byte, page 92
|
||||
WriteByte( 0x00, REG_PACKETCONFIG1); // Fixed size packet, no DC-free encoding, no CRC, no address filtering
|
||||
WriteByte( 0x40, REG_PACKETCONFIG2); // Packet mode
|
||||
WriteByte( 51, REG_FIFOTHRESH); // TxStartCondition=FifoNotEmpty, FIFO threshold = 51 bytes
|
||||
WriteByte( 2*26, REG_PAYLOADLENGTH); // Packet size = 26 bytes Manchester encoded into 52 bytes
|
||||
WriteWord(0x3030, REG_DIOMAPPING1); // DIO signals: DIO0=00, DIO1=11, DIO2=00, DIO3=00, DIO4=00, DIO5=11, => p.64, 99
|
||||
WriteByte( 0x4A, REG_RXBW); // +/-100kHz Rx bandwidth => p.27+67
|
||||
WriteByte( 0x49, REG_PARAMP); // BT=0.5 shaping, 40us ramp up/down
|
||||
WriteByte( 0x07, REG_RSSICONFIG); // 256 samples for RSSI, p.90
|
||||
|
||||
return 0; }
|
||||
|
||||
uint8_t ReadLowBat(void) { return ReadByte(REG_LOWBAT ); }
|
||||
|
||||
#endif
|
||||
|
||||
uint8_t ReadVersion(void) { return ReadByte(REG_VERSION); } // normally returns: 0x24
|
||||
|
||||
#ifdef WITH_RFM69
|
||||
void TriggerRSSI(void) { WriteByte(0x01, REG_RSSICONFIG); } // trigger measurement
|
||||
uint8_t ReadyRSSI(void) { return ReadByte(REG_RSSICONFIG) & 0x02; } // ready ?
|
||||
#endif
|
||||
uint8_t ReadRSSI(void) { return ReadByte(REG_RSSIVALUE); } // read value: RSS = -Value/2
|
||||
|
||||
#ifdef WITH_RFM69
|
||||
void TriggerTemp(void) { WriteByte(0x08, REG_TEMP1); } // trigger measurement
|
||||
uint8_t RunningTemp(void) { return ReadByte(REG_TEMP1) & 0x04; } // still running ?
|
||||
uint8_t ReadTemp(void) { return ReadByte(REG_TEMP2); } // read value: -1 deg/LSB
|
||||
#endif
|
||||
#ifdef WITH_RFM95
|
||||
uint8_t ReadTemp(void) { return ReadByte(REG_TEMP); } // read value: -1 deg/LSB
|
||||
#endif
|
||||
/*
|
||||
void Dump(uint8_t EndAddr=0x20)
|
||||
{ printf("RFM_TRX[] =");
|
||||
for(uint8_t Addr=1; Addr<=EndAddr; Addr++)
|
||||
{ printf(" %02X", ReadByte(Addr)); }
|
||||
printf("\n");
|
||||
}
|
||||
*/
|
||||
} ;
|
||||
|
||||
|
|
@ -0,0 +1,45 @@
|
|||
#ifndef __SSD1306_H__
|
||||
#define __SSD1306_H__
|
||||
|
||||
// http://robotcantalk.blogspot.com/2015/03/interfacing-arduino-with-ssd1306-driven.html
|
||||
|
||||
// SLA (0x3C) + WRITE_MODE (0x00) = 0x78
|
||||
#define OLED_I2C_ADDRESS 0x3C
|
||||
|
||||
// Control byte
|
||||
#define OLED_CONTROL_BYTE_CMD_SINGLE 0x80
|
||||
#define OLED_CONTROL_BYTE_CMD_STREAM 0x00
|
||||
#define OLED_CONTROL_BYTE_DATA_STREAM 0x40
|
||||
|
||||
// Fundamental commands (pg.28)
|
||||
#define OLED_CMD_SET_CONTRAST 0x81 // follow with 0x7F
|
||||
#define OLED_CMD_DISPLAY_RAM 0xA4
|
||||
#define OLED_CMD_DISPLAY_ALLON 0xA5
|
||||
#define OLED_CMD_DISPLAY_NORMAL 0xA6
|
||||
#define OLED_CMD_DISPLAY_INVERTED 0xA7
|
||||
#define OLED_CMD_DISPLAY_OFF 0xAE
|
||||
#define OLED_CMD_DISPLAY_ON 0xAF
|
||||
|
||||
// Addressing Command Table (pg.30)
|
||||
#define OLED_CMD_SET_MEMORY_ADDR_MODE 0x20 // follow with 0x00 = HORZ mode = Behave like a KS108 graphic LCD
|
||||
#define OLED_CMD_SET_COLUMN_RANGE 0x21 // can be used only in HORZ/VERT mode - follow with 0x00 and 0x7F = COL127
|
||||
#define OLED_CMD_SET_PAGE_RANGE 0x22 // can be used only in HORZ/VERT mode - follow with 0x00 and 0x07 = PAGE7
|
||||
|
||||
// Hardware Config (pg.31)
|
||||
#define OLED_CMD_SET_DISPLAY_START_LINE 0x40
|
||||
#define OLED_CMD_SET_SEGMENT_REMAP 0xA1
|
||||
#define OLED_CMD_SET_MUX_RATIO 0xA8 // follow with 0x3F = 64 MUX
|
||||
#define OLED_CMD_SET_COM_SCAN_MODE 0xC8
|
||||
#define OLED_CMD_SET_DISPLAY_OFFSET 0xD3 // follow with 0x00
|
||||
#define OLED_CMD_SET_COM_PIN_MAP 0xDA // follow with 0x12
|
||||
#define OLED_CMD_NOP 0xE3 // NOP
|
||||
|
||||
// Timing and Driving Scheme (pg.32)
|
||||
#define OLED_CMD_SET_DISPLAY_CLK_DIV 0xD5 // follow with 0x80
|
||||
#define OLED_CMD_SET_PRECHARGE 0xD9 // follow with 0xF1
|
||||
#define OLED_CMD_SET_VCOMH_DESELCT 0xDB // follow with 0x30
|
||||
|
||||
// Charge Pump (pg.62)
|
||||
#define OLED_CMD_SET_CHARGE_PUMP 0x8D // follow with 0x14
|
||||
|
||||
#endif // __SSD1306_H__
|
Plik diff jest za duży
Load Diff
Plik diff jest za duży
Load Diff
|
@ -0,0 +1,44 @@
|
|||
#include "timesync.h"
|
||||
|
||||
static TickType_t TimeSync_RefTick; // reference point on the system tick
|
||||
static uint32_t TimeSync_RefTime; // Time which corresponds to the above reference point
|
||||
|
||||
void TimeSync_HardPPS(TickType_t Tick) // [ms] hardware PPS at the give system tick
|
||||
{ TickType_t Incr = (Tick-TimeSync_RefTick+500)/1000; // [sec] home many full seconds to step forward
|
||||
TimeSync_RefTime += Incr; // [sec] new time ref.
|
||||
TimeSync_RefTick = Tick; } // [ms] new tick ref.
|
||||
|
||||
void TimeSync_HardPPS(void) { TimeSync_HardPPS(xTaskGetTickCount()); } //
|
||||
|
||||
void TimeSync_SoftPPS(TickType_t Tick, uint32_t Time, int32_t msOfs) // [ms], [sec], [ms] software PPS: from GPS burst start or from MAV
|
||||
{ Tick-=msOfs; // [ms]
|
||||
TickType_t Incr=(Tick-TimeSync_RefTick+500)/1000; // [sec]
|
||||
TimeSync_RefTime = Time; // [sec]
|
||||
TimeSync_RefTick += Incr*1000; // [ms]
|
||||
// if(Tick>TimeSync_RefTick) TimeSync_RefTick++;
|
||||
// else if(Tick<TimeSync_RefTick) TimeSync_RefTick--;
|
||||
int32_t Diff = Tick-TimeSync_RefTick;
|
||||
TimeSync_RefTick += (Diff+8)>>4; }
|
||||
|
||||
void TimeSync_CorrRef(int16_t Corr)
|
||||
{ TimeSync_RefTick += Corr; }
|
||||
|
||||
TickType_t TimeSync_msTime(TickType_t Tick) // [ms] get fractional time which corresponds to given system tick
|
||||
{ TickType_t msTime=Tick-TimeSync_RefTick;
|
||||
if(msTime<1000) return msTime;
|
||||
if(msTime<2000) return msTime-1000;
|
||||
return msTime%1000; }
|
||||
|
||||
TickType_t TimeSync_msTime(void) // [msec] get fractional time now
|
||||
{ return TimeSync_msTime(xTaskGetTickCount()); }
|
||||
|
||||
uint32_t TimeSync_Time(TickType_t Tick) // [sec] get Time which corresponds to given system tick
|
||||
{ int32_t Time=Tick-TimeSync_RefTick;
|
||||
// if(Time<0) return TimeSync_RefTime - ();
|
||||
if(Time<1000) return TimeSync_RefTime;
|
||||
if(Time<2000) return TimeSync_RefTime+1;
|
||||
return TimeSync_RefTime + (Time/1000); }
|
||||
|
||||
uint32_t TimeSync_Time(void) // [sec] get Time now
|
||||
{ return TimeSync_Time(xTaskGetTickCount()); }
|
||||
|
|
@ -0,0 +1,22 @@
|
|||
#ifndef __TIMESYNC_H__
|
||||
#define __TIMESYNC_H__
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
|
||||
void TimeSync_HardPPS(TickType_t Tick); // hardware PPS at the give system tick
|
||||
void TimeSync_HardPPS(void);
|
||||
|
||||
void TimeSync_SoftPPS(TickType_t Tick, uint32_t Time, int32_t msOfs=100); // software PPS: from GPS burst start or from MAV
|
||||
|
||||
TickType_t TimeSync_msTime(TickType_t Tick); // [ms] get fractional time which corresponds to given system tick
|
||||
TickType_t TimeSync_msTime(void);
|
||||
|
||||
uint32_t TimeSync_Time(TickType_t Tick); // [sec] get Time which corresponds to given system tick
|
||||
uint32_t TimeSync_Time(void);
|
||||
|
||||
void TimeSync_CorrRef(int16_t Corr); // [ms] correct the time reference [RTOS tick]
|
||||
|
||||
#endif // __TIMESYNC_H__
|
|
@ -0,0 +1,257 @@
|
|||
#ifndef __UBX_H__
|
||||
#define __UBX_H__
|
||||
|
||||
// UBX Class packet numbers
|
||||
const uint8_t UBX_NAV = 0x01; // navigation
|
||||
const uint8_t UBX_ACK = 0x05; // acknoledgement of configuration
|
||||
const uint8_t UBX_CFG = 0x06; // configuration
|
||||
|
||||
class UBX_RxMsg // receiver for the UBX sentences
|
||||
{ public:
|
||||
// most information in the UBX packets is already aligned to 32-bit boundary
|
||||
// thus it makes sense to have the packet so aligned when receiving it.
|
||||
static const uint8_t MaxWords=10; // maximum number of 32-bit words (excl. head and tail)
|
||||
static const uint8_t MaxBytes=4*MaxWords; // max. number of bytes
|
||||
static const uint8_t SyncL=0xB5; // UBX sync bytes
|
||||
static const uint8_t SyncH=0x62;
|
||||
|
||||
union
|
||||
{ uint32_t Word[MaxWords]; // here we store the UBX packet (excl. head and tail)
|
||||
uint8_t Byte[MaxBytes]; } ;
|
||||
uint8_t Class; // Class (01=NAV)
|
||||
uint8_t ID; // ID
|
||||
uint8_t Bytes; // number of bytes in the packet (excl. head and tail)
|
||||
|
||||
private:
|
||||
uint8_t Padding; // just to make the structure size be a multiple of 4-bytes
|
||||
uint8_t State; // bits: 0:loading, 1:complete, 2:locked,
|
||||
uint8_t Idx; // loading index
|
||||
|
||||
uint8_t CheckA; // UBX check sum (two bytes)
|
||||
uint8_t CheckB;
|
||||
void CheckInit(void) { CheckA=0; CheckB=0; } // initialize the checksum
|
||||
void CheckPass(uint8_t Byte) { CheckA+=Byte; CheckB+=CheckA; } // pass a byte through the checksum
|
||||
|
||||
public:
|
||||
void RecalcCheck(void)
|
||||
{ CheckInit();
|
||||
CheckPass(Class); CheckPass(ID); CheckPass(Bytes); CheckPass(0x00);
|
||||
for(uint8_t Idx=0; Idx<Bytes; Idx++) CheckPass(Byte[Idx]); }
|
||||
|
||||
inline void Clear(void) { Idx=0; State=0; CheckInit(); }
|
||||
|
||||
uint8_t isLoading(void) const
|
||||
{ return State&0x01; }
|
||||
|
||||
uint8_t isComplete(void) const
|
||||
{ return State&0x02; }
|
||||
|
||||
void ProcessByte(uint8_t RxByte) // pass all bytes through this call and it will build the frame
|
||||
{
|
||||
if(isComplete()) Clear(); // if already a complete frame, clear it
|
||||
switch(Idx)
|
||||
{ case 0: // expect SyncL
|
||||
if(RxByte!=SyncL) { Clear(); return; }
|
||||
State=0x01; break; // declare "isLoading" state
|
||||
case 1: // expect SyncH
|
||||
if(RxByte!=SyncH) { Clear(); return; }
|
||||
break;
|
||||
case 2: // Class
|
||||
Class=RxByte; CheckPass(RxByte);
|
||||
break;
|
||||
case 3: // ID
|
||||
ID=RxByte; CheckPass(RxByte);
|
||||
break;
|
||||
case 4: // LSB of packet length
|
||||
Bytes=RxByte; CheckPass(RxByte); if(Bytes>MaxBytes) { Clear(); return; }
|
||||
break;
|
||||
case 5: // MSB of packet length (expect zero)
|
||||
CheckPass(RxByte); if(RxByte!=0) { Clear(); return; }
|
||||
break;
|
||||
default: // past the header, now load the packet content
|
||||
uint8_t ByteIdx=Idx-6;
|
||||
if(ByteIdx<Bytes)
|
||||
{ Byte[ByteIdx]=RxByte; CheckPass(RxByte); }
|
||||
else if(ByteIdx==Bytes) // already past the content, now the first checksum byte
|
||||
{ if(RxByte!=CheckA) { Clear(); return; } }
|
||||
else if(ByteIdx==(Bytes+1)) // second checksum byte
|
||||
{ if(RxByte!=CheckB) { Clear(); return; }
|
||||
State=0x02; } // declare "isComplete" state
|
||||
else
|
||||
{ Clear(); return; }
|
||||
break;
|
||||
}
|
||||
Idx++;
|
||||
}
|
||||
|
||||
void Send(void (*SendByte)(char)) const
|
||||
{ (*SendByte)(SyncL);
|
||||
(*SendByte)(SyncH);
|
||||
(*SendByte)(Class);
|
||||
(*SendByte)(ID);
|
||||
(*SendByte)(Bytes);
|
||||
(*SendByte)(0x00);
|
||||
for(uint8_t Idx=0; Idx<Bytes; Idx++)
|
||||
{ (*SendByte)(Byte[Idx]); }
|
||||
(*SendByte)(CheckA);
|
||||
(*SendByte)(CheckB);
|
||||
}
|
||||
|
||||
static void SendPoll(uint8_t Class, uint8_t ID, void (*SendByte)(char))
|
||||
{ (*SendByte)(SyncL);
|
||||
(*SendByte)(SyncH);
|
||||
(*SendByte)(Class);
|
||||
(*SendByte)(ID);
|
||||
(*SendByte)(0x00);
|
||||
(*SendByte)(0x00);
|
||||
uint8_t CheckA = Class; // pass Class through check sum
|
||||
uint8_t CheckB = CheckA;
|
||||
CheckA += ID; // pass ID through check sum
|
||||
CheckB += CheckA;
|
||||
CheckB += CheckA; // pass 0x00
|
||||
CheckB += CheckA; // pass 0x00
|
||||
(*SendByte)(CheckA); // send the check sum
|
||||
(*SendByte)(CheckB);
|
||||
}
|
||||
|
||||
bool isNAV(void) const { return Class==0x01; }
|
||||
bool isACK(void) const { return Class==0x05; }
|
||||
bool isCFG(void) const { return Class==0x06; }
|
||||
|
||||
bool isNAV_POSLLH (void) const { return isNAV() && (ID==0x02); }
|
||||
bool isNAV_STATUS (void) const { return isNAV() && (ID==0x03); }
|
||||
bool isNAV_DOP (void) const { return isNAV() && (ID==0x04); }
|
||||
bool isNAV_VELNED (void) const { return isNAV() && (ID==0x12); }
|
||||
bool isNAV_TIMEGPS(void) const { return isNAV() && (ID==0x20); }
|
||||
bool isNAV_TIMEUTC(void) const { return isNAV() && (ID==0x21); }
|
||||
|
||||
bool isACK_NAK (void) const { return isACK() && (ID==0x00); }
|
||||
bool isACK_ACK (void) const { return isACK() && (ID==0x01); }
|
||||
|
||||
bool isCFG_PRT (void) const { return isCFG() && (ID==0x00); }
|
||||
bool isCFG_NAV5 (void) const { return isCFG() && (ID==0x24); }
|
||||
} ;
|
||||
|
||||
class UBX_NAV_POSLLH // 0x01 0x02
|
||||
{ uint32_t iTOW; // [ms] Time-of-Week
|
||||
int32_t lon; // [1e-7 deg] Longitude
|
||||
int32_t lat; // [1e-7 deg] Latitude
|
||||
int32_t height; // [mm] height above elipsoid (GPS altitude)
|
||||
int32_t hMSL; // [mm] height above Mean Sea Level
|
||||
uint32_t hAcc; // [mm] horizontal accuracy
|
||||
uint32_t vAcc; // [mm] vertical accuracy
|
||||
} ;
|
||||
|
||||
class UBX_NAV_STATUS // 0x01 0x03
|
||||
{ uint32_t iTOW; // [ms] Time-of-Week
|
||||
uint8_t gpsFix; // Fix type: 0:none, 1=dead reckoning, 2:2-D, 3:3-D, 4:GPS+dead reckoning, 5:time-only
|
||||
uint8_t flags; // xxxxTWDF => T:Time-of-Week is valid, W:Week-Number is valid, D:Diff. GPS is used, F:Fix valid
|
||||
uint8_t diffStat; // DD => 00:none, 01:PR+PRR corr., 10: PR+PRR+CP corr., 11: high accuracy PR+PRR+CP
|
||||
uint8_t res; // reserved PR=Pseudo-Range, PRR=Pseudo-Range Rate
|
||||
uint32_t ttff; // [ms] Time To First Fix
|
||||
uint32_t msss; // [ms] Since Startup
|
||||
} ;
|
||||
|
||||
class UBX_NAV_DOP // 0x01 0x04
|
||||
{ uint32_t iTOW; // [ms] Time-of-Week
|
||||
uint16_t gDOP; // [1/100] geometrical
|
||||
uint16_t pDOP; // [1/100] position
|
||||
uint16_t tDOP; // [1/100] time
|
||||
uint16_t vDOP; // [1/100] vertical
|
||||
uint16_t hDOP; // [1/100] horizontal
|
||||
uint16_t nDOP; // [1/100] north-south
|
||||
uint16_t eDOP; // [1/100] east-west
|
||||
uint16_t padding; // padding for round size
|
||||
} ;
|
||||
|
||||
class UBX_NAV_VELNED // 0x01 0x12
|
||||
{ uint32_t iTOW; // [ms] Time-of-Week
|
||||
int32_t velN; // [cm/s] velocity North
|
||||
int32_t velE; // [cm/s] velocity East
|
||||
int32_t velD; // [cm/s] velocity Down
|
||||
uint32_t Speed; // [cm/s] velocity
|
||||
uint32_t gSpeed; // [cm/s] ground speed (horizontal velocity)
|
||||
int32_t heading; // [1e-5 deg] ground heading
|
||||
uint32_t sAcc; // [cm/s] speed accuracy
|
||||
uint32_t cAcc; // [1e-5 deg] heading accuracy
|
||||
} ;
|
||||
|
||||
class UBX_NAV_TIMEGPS // 0x01 0x020
|
||||
{ public:
|
||||
uint32_t iTOW; // [ms] Time-of-Week
|
||||
int32_t fTOW; // [ns] reminder of Time-of-Week
|
||||
uint16_t week;
|
||||
uint8_t leapS;
|
||||
uint8_t valid; // bits: 0:ToW, 1:week, 2:leapS
|
||||
uint32_t tAcc; // [ns]
|
||||
|
||||
public:
|
||||
static const uint32_t SecsPerWeek = 7*24*60*60;
|
||||
uint8_t Valid(void) const
|
||||
{ return (valid&0x03)==0x03; }
|
||||
uint32_t UnixTime() const
|
||||
{ return (iTOW+10)/1000 + week*SecsPerWeek + 315964785; } // http://www.andrews.edu/~tzs/timeconv/timedisplay.php
|
||||
} ;
|
||||
|
||||
class UBX_NAV_TIMEUTC // 0x01 0x21
|
||||
{ public:
|
||||
uint32_t iTOW; // [ms] Time-of-Week
|
||||
uint32_t tAcc; // [ns] accurary estimate
|
||||
int32_t nano; // [ns]
|
||||
uint16_t year; // 1999..2099
|
||||
uint8_t month; // 1..12
|
||||
uint8_t day; // 1..31
|
||||
uint8_t hour;
|
||||
uint8_t min;
|
||||
uint8_t sec;
|
||||
uint8_t valid; // bits: 0:ToW, 1:WN, 2:UTC
|
||||
} ;
|
||||
|
||||
class UBX_CFG_PRT // 0x06 0x00
|
||||
{ public:
|
||||
uint8_t portID; // 1 or 2
|
||||
uint8_t reserved0;
|
||||
uint16_t txReady;
|
||||
int32_t mode; // 00 10x x 11 x 1 xxxx => 0x08D0
|
||||
uint32_t baudRate; // [bps]
|
||||
int16_t inProtoMask; // bit 0:UBX, bit 1:NMEA
|
||||
int16_t outProtoMask; // bit 0:UBX, bit 1:NMEA
|
||||
uint16_t reserved4;
|
||||
uint16_t reserved5;
|
||||
} ;
|
||||
|
||||
class UBX_CFG_MSG // 0x06 0x01
|
||||
{ public:
|
||||
uint8_t msgClass;
|
||||
uint8_t msgID;
|
||||
uint8_t rate; // message send rate
|
||||
} ;
|
||||
|
||||
class UBX_CFG_RATE // 0x06 0x08
|
||||
{ public:
|
||||
uint16_t measRate; // [ms] measurement rate
|
||||
uint16_t navRate; // [cycles] = 1
|
||||
uint16_t timeRef; // 0=UTC, 1=GPS
|
||||
} ;
|
||||
|
||||
class UBX_CFG_NAV5 // 0x06 0x24
|
||||
{ public:
|
||||
uint16_t mask; // bit #0 = apply dynamic mode settings, #1 = apply min. elev. settings, #2 = apply fix mode settings
|
||||
uint8_t dynModel; // 6 = airborne 1g, 7 = 2g, 8 = 4g
|
||||
uint8_t fixMode; // 1=2D only, 2=3D only, 3=auto 2/3D
|
||||
int32_t fixAlt; // [0.01m]
|
||||
uint32_t fixAltVar; // [0.001m]
|
||||
int8_t minElev; // [deg] minimum satelite elevation
|
||||
uint8_t drLimit; // [sec] Dead Reconning time limit
|
||||
uint16_t pDop;
|
||||
uint16_t tDop;
|
||||
uint16_t pAcc; // [m]
|
||||
uint16_t tAcc; // [m]
|
||||
uint8_t staticHoldThres; // [cm/s]
|
||||
uint8_t dgpsTimeout; // [s]
|
||||
uint32_t reserved2;
|
||||
uint32_t reserved3;
|
||||
uint32_t reserved4;
|
||||
} ;
|
||||
|
||||
#endif // __UBX_H__
|
|
@ -0,0 +1,6 @@
|
|||
# Espressif ESP32 Partition Table
|
||||
# Name, Type, SubType, Offset, Size, Flags
|
||||
nvs,data,nvs,0x9000,24K,
|
||||
phy_init,data,phy,0xf000,4K,
|
||||
factory,app,factory,0x10000,1M,
|
||||
files,data,spiffs,,0xF0000,
|
|
|
@ -0,0 +1,544 @@
|
|||
#
|
||||
# Automatically generated file; DO NOT EDIT.
|
||||
# Espressif IoT Development Framework Configuration
|
||||
#
|
||||
|
||||
#
|
||||
# SDK tool configuration
|
||||
#
|
||||
CONFIG_TOOLPREFIX="xtensa-esp32-elf-"
|
||||
CONFIG_PYTHON="python"
|
||||
CONFIG_MAKE_WARN_UNDEFINED_VARIABLES=y
|
||||
|
||||
#
|
||||
# Bootloader config
|
||||
#
|
||||
CONFIG_LOG_BOOTLOADER_LEVEL_NONE=
|
||||
CONFIG_LOG_BOOTLOADER_LEVEL_ERROR=
|
||||
CONFIG_LOG_BOOTLOADER_LEVEL_WARN=y
|
||||
CONFIG_LOG_BOOTLOADER_LEVEL_INFO=
|
||||
CONFIG_LOG_BOOTLOADER_LEVEL_DEBUG=
|
||||
CONFIG_LOG_BOOTLOADER_LEVEL_VERBOSE=
|
||||
CONFIG_LOG_BOOTLOADER_LEVEL=2
|
||||
CONFIG_BOOTLOADER_VDDSDIO_BOOST=y
|
||||
|
||||
#
|
||||
# Security features
|
||||
#
|
||||
CONFIG_SECURE_BOOT_ENABLED=
|
||||
CONFIG_FLASH_ENCRYPTION_ENABLED=
|
||||
|
||||
#
|
||||
# Serial flasher config
|
||||
#
|
||||
CONFIG_ESPTOOLPY_PORT="/dev/ttyUSB1"
|
||||
CONFIG_ESPTOOLPY_BAUD_115200B=y
|
||||
CONFIG_ESPTOOLPY_BAUD_230400B=
|
||||
CONFIG_ESPTOOLPY_BAUD_921600B=
|
||||
CONFIG_ESPTOOLPY_BAUD_2MB=
|
||||
CONFIG_ESPTOOLPY_BAUD_OTHER=
|
||||
CONFIG_ESPTOOLPY_BAUD_OTHER_VAL=115200
|
||||
CONFIG_ESPTOOLPY_BAUD=115200
|
||||
CONFIG_ESPTOOLPY_COMPRESSED=y
|
||||
CONFIG_FLASHMODE_QIO=
|
||||
CONFIG_FLASHMODE_QOUT=
|
||||
CONFIG_FLASHMODE_DIO=y
|
||||
CONFIG_FLASHMODE_DOUT=
|
||||
CONFIG_ESPTOOLPY_FLASHMODE="dio"
|
||||
CONFIG_ESPTOOLPY_FLASHFREQ_80M=
|
||||
CONFIG_ESPTOOLPY_FLASHFREQ_40M=y
|
||||
CONFIG_ESPTOOLPY_FLASHFREQ_26M=
|
||||
CONFIG_ESPTOOLPY_FLASHFREQ_20M=
|
||||
CONFIG_ESPTOOLPY_FLASHFREQ="40m"
|
||||
CONFIG_ESPTOOLPY_FLASHSIZE_1MB=
|
||||
CONFIG_ESPTOOLPY_FLASHSIZE_2MB=y
|
||||
CONFIG_ESPTOOLPY_FLASHSIZE_4MB=
|
||||
CONFIG_ESPTOOLPY_FLASHSIZE_8MB=
|
||||
CONFIG_ESPTOOLPY_FLASHSIZE_16MB=
|
||||
CONFIG_ESPTOOLPY_FLASHSIZE="2MB"
|
||||
CONFIG_ESPTOOLPY_FLASHSIZE_DETECT=y
|
||||
CONFIG_ESPTOOLPY_BEFORE_RESET=y
|
||||
CONFIG_ESPTOOLPY_BEFORE_NORESET=
|
||||
CONFIG_ESPTOOLPY_BEFORE="default_reset"
|
||||
CONFIG_ESPTOOLPY_AFTER_RESET=y
|
||||
CONFIG_ESPTOOLPY_AFTER_NORESET=
|
||||
CONFIG_ESPTOOLPY_AFTER="hard_reset"
|
||||
CONFIG_MONITOR_BAUD_9600B=
|
||||
CONFIG_MONITOR_BAUD_57600B=
|
||||
CONFIG_MONITOR_BAUD_115200B=y
|
||||
CONFIG_MONITOR_BAUD_230400B=
|
||||
CONFIG_MONITOR_BAUD_921600B=
|
||||
CONFIG_MONITOR_BAUD_2MB=
|
||||
CONFIG_MONITOR_BAUD_OTHER=
|
||||
CONFIG_MONITOR_BAUD_OTHER_VAL=115200
|
||||
CONFIG_MONITOR_BAUD=115200
|
||||
|
||||
#
|
||||
# Partition Table
|
||||
#
|
||||
CONFIG_PARTITION_TABLE_SINGLE_APP=
|
||||
CONFIG_PARTITION_TABLE_TWO_OTA=
|
||||
CONFIG_PARTITION_TABLE_CUSTOM=y
|
||||
CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="partitions.csv"
|
||||
CONFIG_PARTITION_TABLE_CUSTOM_APP_BIN_OFFSET=0x10000
|
||||
CONFIG_PARTITION_TABLE_FILENAME="partitions.csv"
|
||||
CONFIG_APP_OFFSET=0x10000
|
||||
|
||||
#
|
||||
# Compiler options
|
||||
#
|
||||
CONFIG_OPTIMIZATION_LEVEL_DEBUG=y
|
||||
CONFIG_OPTIMIZATION_LEVEL_RELEASE=
|
||||
CONFIG_OPTIMIZATION_ASSERTIONS_ENABLED=y
|
||||
CONFIG_OPTIMIZATION_ASSERTIONS_SILENT=
|
||||
CONFIG_OPTIMIZATION_ASSERTIONS_DISABLED=
|
||||
CONFIG_CXX_EXCEPTIONS=
|
||||
CONFIG_STACK_CHECK_NONE=y
|
||||
CONFIG_STACK_CHECK_NORM=
|
||||
CONFIG_STACK_CHECK_STRONG=
|
||||
CONFIG_STACK_CHECK_ALL=
|
||||
CONFIG_STACK_CHECK=
|
||||
|
||||
#
|
||||
# Component config
|
||||
#
|
||||
|
||||
#
|
||||
# Application Level Tracing
|
||||
#
|
||||
CONFIG_ESP32_APPTRACE_DEST_TRAX=
|
||||
CONFIG_ESP32_APPTRACE_DEST_NONE=y
|
||||
CONFIG_ESP32_APPTRACE_ENABLE=
|
||||
CONFIG_ESP32_APPTRACE_LOCK_ENABLE=y
|
||||
|
||||
#
|
||||
# FreeRTOS SystemView Tracing
|
||||
#
|
||||
CONFIG_AWS_IOT_SDK=
|
||||
|
||||
#
|
||||
# Bluetooth
|
||||
#
|
||||
CONFIG_BT_ENABLED=y
|
||||
CONFIG_BTDM_CONTROLLER_PINNED_TO_CORE=0
|
||||
CONFIG_BTDM_CONTROLLER_HCI_MODE_VHCI=y
|
||||
CONFIG_BTDM_CONTROLLER_HCI_MODE_UART_H4=
|
||||
CONFIG_BLUEDROID_ENABLED=y
|
||||
CONFIG_BLUEDROID_PINNED_TO_CORE=0
|
||||
CONFIG_BTC_TASK_STACK_SIZE=3072
|
||||
CONFIG_BLUEDROID_MEM_DEBUG=
|
||||
CONFIG_CLASSIC_BT_ENABLED=y
|
||||
CONFIG_A2DP_ENABLE=
|
||||
CONFIG_BT_SPP_ENABLED=y
|
||||
CONFIG_GATTS_ENABLE=y
|
||||
CONFIG_GATTC_ENABLE=y
|
||||
CONFIG_BLE_SMP_ENABLE=y
|
||||
CONFIG_BT_STACK_NO_LOG=
|
||||
CONFIG_BT_ACL_CONNECTIONS=4
|
||||
CONFIG_SMP_ENABLE=y
|
||||
CONFIG_BT_RESERVE_DRAM=0x10000
|
||||
|
||||
#
|
||||
# ESP32-specific
|
||||
#
|
||||
CONFIG_ESP32_DEFAULT_CPU_FREQ_80=y
|
||||
CONFIG_ESP32_DEFAULT_CPU_FREQ_160=
|
||||
CONFIG_ESP32_DEFAULT_CPU_FREQ_240=
|
||||
CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=80
|
||||
CONFIG_MEMMAP_SMP=y
|
||||
CONFIG_SPIRAM_SUPPORT=
|
||||
CONFIG_MEMMAP_TRACEMEM=
|
||||
CONFIG_MEMMAP_TRACEMEM_TWOBANKS=
|
||||
CONFIG_ESP32_TRAX=
|
||||
CONFIG_TRACEMEM_RESERVE_DRAM=0x0
|
||||
CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH=
|
||||
CONFIG_ESP32_ENABLE_COREDUMP_TO_UART=
|
||||
CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y
|
||||
CONFIG_ESP32_ENABLE_COREDUMP=
|
||||
CONFIG_TWO_UNIVERSAL_MAC_ADDRESS=
|
||||
CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y
|
||||
CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4
|
||||
CONFIG_SYSTEM_EVENT_QUEUE_SIZE=32
|
||||
CONFIG_SYSTEM_EVENT_TASK_STACK_SIZE=2048
|
||||
CONFIG_MAIN_TASK_STACK_SIZE=4096
|
||||
CONFIG_IPC_TASK_STACK_SIZE=1024
|
||||
CONFIG_TIMER_TASK_STACK_SIZE=4096
|
||||
CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y
|
||||
CONFIG_NEWLIB_STDOUT_LINE_ENDING_LF=
|
||||
CONFIG_NEWLIB_STDOUT_LINE_ENDING_CR=
|
||||
CONFIG_NEWLIB_STDIN_LINE_ENDING_CRLF=
|
||||
CONFIG_NEWLIB_STDIN_LINE_ENDING_LF=
|
||||
CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y
|
||||
CONFIG_NEWLIB_NANO_FORMAT=
|
||||
CONFIG_CONSOLE_UART_DEFAULT=y
|
||||
CONFIG_CONSOLE_UART_CUSTOM=
|
||||
CONFIG_CONSOLE_UART_NONE=
|
||||
CONFIG_CONSOLE_UART_NUM=0
|
||||
CONFIG_CONSOLE_UART_BAUDRATE=115200
|
||||
CONFIG_ULP_COPROC_ENABLED=
|
||||
CONFIG_ULP_COPROC_RESERVE_MEM=0
|
||||
CONFIG_ESP32_PANIC_PRINT_HALT=
|
||||
CONFIG_ESP32_PANIC_PRINT_REBOOT=y
|
||||
CONFIG_ESP32_PANIC_SILENT_REBOOT=
|
||||
CONFIG_ESP32_PANIC_GDBSTUB=
|
||||
CONFIG_ESP32_DEBUG_OCDAWARE=y
|
||||
CONFIG_INT_WDT=y
|
||||
CONFIG_INT_WDT_TIMEOUT_MS=300
|
||||
CONFIG_TASK_WDT=y
|
||||
CONFIG_TASK_WDT_PANIC=
|
||||
CONFIG_TASK_WDT_TIMEOUT_S=5
|
||||
CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
||||
CONFIG_BROWNOUT_DET=y
|
||||
CONFIG_BROWNOUT_DET_LVL_SEL_0=y
|
||||
CONFIG_BROWNOUT_DET_LVL_SEL_1=
|
||||
CONFIG_BROWNOUT_DET_LVL_SEL_2=
|
||||
CONFIG_BROWNOUT_DET_LVL_SEL_3=
|
||||
CONFIG_BROWNOUT_DET_LVL_SEL_4=
|
||||
CONFIG_BROWNOUT_DET_LVL_SEL_5=
|
||||
CONFIG_BROWNOUT_DET_LVL_SEL_6=
|
||||
CONFIG_BROWNOUT_DET_LVL_SEL_7=
|
||||
CONFIG_BROWNOUT_DET_LVL=0
|
||||
CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y
|
||||
CONFIG_ESP32_TIME_SYSCALL_USE_RTC=
|
||||
CONFIG_ESP32_TIME_SYSCALL_USE_FRC1=
|
||||
CONFIG_ESP32_TIME_SYSCALL_USE_NONE=
|
||||
CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y
|
||||
CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL=
|
||||
CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024
|
||||
CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000
|
||||
CONFIG_ESP32_XTAL_FREQ_40=
|
||||
CONFIG_ESP32_XTAL_FREQ_26=y
|
||||
CONFIG_ESP32_XTAL_FREQ_AUTO=
|
||||
CONFIG_ESP32_XTAL_FREQ=26
|
||||
CONFIG_DISABLE_BASIC_ROM_CONSOLE=
|
||||
CONFIG_ESP_TIMER_PROFILING=
|
||||
CONFIG_COMPATIBLE_PRE_V2_1_BOOTLOADERS=
|
||||
|
||||
#
|
||||
# Wi-Fi
|
||||
#
|
||||
CONFIG_SW_COEXIST_ENABLE=
|
||||
CONFIG_ESP32_WIFI_STATIC_RX_BUFFER_NUM=10
|
||||
CONFIG_ESP32_WIFI_DYNAMIC_RX_BUFFER_NUM=32
|
||||
CONFIG_ESP32_WIFI_STATIC_TX_BUFFER=
|
||||
CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER=y
|
||||
CONFIG_ESP32_WIFI_TX_BUFFER_TYPE=1
|
||||
CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER_NUM=32
|
||||
CONFIG_ESP32_WIFI_AMPDU_TX_ENABLED=y
|
||||
CONFIG_ESP32_WIFI_TX_BA_WIN=6
|
||||
CONFIG_ESP32_WIFI_AMPDU_RX_ENABLED=y
|
||||
CONFIG_ESP32_WIFI_RX_BA_WIN=6
|
||||
CONFIG_ESP32_WIFI_NVS_ENABLED=y
|
||||
|
||||
#
|
||||
# PHY
|
||||
#
|
||||
CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y
|
||||
CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION=
|
||||
CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20
|
||||
CONFIG_ESP32_PHY_MAX_TX_POWER=20
|
||||
|
||||
#
|
||||
# Power Management
|
||||
#
|
||||
CONFIG_PM_ENABLE=
|
||||
|
||||
#
|
||||
# Ethernet
|
||||
#
|
||||
CONFIG_DMA_RX_BUF_NUM=10
|
||||
CONFIG_DMA_TX_BUF_NUM=10
|
||||
CONFIG_EMAC_L2_TO_L3_RX_BUF_MODE=
|
||||
CONFIG_EMAC_TASK_PRIORITY=20
|
||||
|
||||
#
|
||||
# FAT Filesystem support
|
||||
#
|
||||
CONFIG_FATFS_CODEPAGE_DYNAMIC=
|
||||
CONFIG_FATFS_CODEPAGE_437=y
|
||||
CONFIG_FATFS_CODEPAGE_720=
|
||||
CONFIG_FATFS_CODEPAGE_737=
|
||||
CONFIG_FATFS_CODEPAGE_771=
|
||||
CONFIG_FATFS_CODEPAGE_775=
|
||||
CONFIG_FATFS_CODEPAGE_850=
|
||||
CONFIG_FATFS_CODEPAGE_852=
|
||||
CONFIG_FATFS_CODEPAGE_855=
|
||||
CONFIG_FATFS_CODEPAGE_857=
|
||||
CONFIG_FATFS_CODEPAGE_860=
|
||||
CONFIG_FATFS_CODEPAGE_861=
|
||||
CONFIG_FATFS_CODEPAGE_862=
|
||||
CONFIG_FATFS_CODEPAGE_863=
|
||||
CONFIG_FATFS_CODEPAGE_864=
|
||||
CONFIG_FATFS_CODEPAGE_865=
|
||||
CONFIG_FATFS_CODEPAGE_866=
|
||||
CONFIG_FATFS_CODEPAGE_869=
|
||||
CONFIG_FATFS_CODEPAGE_932=
|
||||
CONFIG_FATFS_CODEPAGE_936=
|
||||
CONFIG_FATFS_CODEPAGE_949=
|
||||
CONFIG_FATFS_CODEPAGE_950=
|
||||
CONFIG_FATFS_CODEPAGE=437
|
||||
CONFIG_FATFS_LFN_NONE=y
|
||||
CONFIG_FATFS_LFN_HEAP=
|
||||
CONFIG_FATFS_LFN_STACK=
|
||||
CONFIG_FATFS_FS_LOCK=0
|
||||
CONFIG_FATFS_TIMEOUT_MS=10000
|
||||
CONFIG_FATFS_PER_FILE_CACHE=y
|
||||
|
||||
#
|
||||
# FreeRTOS
|
||||
#
|
||||
CONFIG_FREERTOS_UNICORE=y
|
||||
CONFIG_FREERTOS_CORETIMER_0=y
|
||||
CONFIG_FREERTOS_CORETIMER_1=
|
||||
CONFIG_FREERTOS_HZ=1000
|
||||
CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y
|
||||
CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE=
|
||||
CONFIG_FREERTOS_CHECK_STACKOVERFLOW_PTRVAL=y
|
||||
CONFIG_FREERTOS_CHECK_STACKOVERFLOW_CANARY=
|
||||
CONFIG_FREERTOS_WATCHPOINT_END_OF_STACK=
|
||||
CONFIG_FREERTOS_INTERRUPT_BACKTRACE=y
|
||||
CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS=3
|
||||
CONFIG_FREERTOS_ASSERT_FAIL_ABORT=y
|
||||
CONFIG_FREERTOS_ASSERT_FAIL_PRINT_CONTINUE=
|
||||
CONFIG_FREERTOS_ASSERT_DISABLE=
|
||||
CONFIG_FREERTOS_IDLE_TASK_STACKSIZE=1024
|
||||
CONFIG_FREERTOS_ISR_STACKSIZE=1536
|
||||
CONFIG_FREERTOS_LEGACY_HOOKS=
|
||||
CONFIG_FREERTOS_MAX_TASK_NAME_LEN=16
|
||||
CONFIG_SUPPORT_STATIC_ALLOCATION=
|
||||
CONFIG_TIMER_TASK_PRIORITY=1
|
||||
CONFIG_TIMER_TASK_STACK_DEPTH=2048
|
||||
CONFIG_TIMER_QUEUE_LENGTH=10
|
||||
CONFIG_FREERTOS_QUEUE_REGISTRY_SIZE=0
|
||||
CONFIG_FREERTOS_USE_TRACE_FACILITY=y
|
||||
CONFIG_FREERTOS_USE_STATS_FORMATTING_FUNCTIONS=y
|
||||
CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS=
|
||||
CONFIG_FREERTOS_DEBUG_INTERNALS=
|
||||
|
||||
#
|
||||
# Heap memory debugging
|
||||
#
|
||||
CONFIG_HEAP_POISONING_DISABLED=y
|
||||
CONFIG_HEAP_POISONING_LIGHT=
|
||||
CONFIG_HEAP_POISONING_COMPREHENSIVE=
|
||||
CONFIG_HEAP_TRACING=
|
||||
|
||||
#
|
||||
# libsodium
|
||||
#
|
||||
CONFIG_LIBSODIUM_USE_MBEDTLS_SHA=y
|
||||
|
||||
#
|
||||
# Log output
|
||||
#
|
||||
CONFIG_LOG_DEFAULT_LEVEL_NONE=
|
||||
CONFIG_LOG_DEFAULT_LEVEL_ERROR=
|
||||
CONFIG_LOG_DEFAULT_LEVEL_WARN=
|
||||
CONFIG_LOG_DEFAULT_LEVEL_INFO=y
|
||||
CONFIG_LOG_DEFAULT_LEVEL_DEBUG=
|
||||
CONFIG_LOG_DEFAULT_LEVEL_VERBOSE=
|
||||
CONFIG_LOG_DEFAULT_LEVEL=3
|
||||
CONFIG_LOG_COLORS=y
|
||||
|
||||
#
|
||||
# LWIP
|
||||
#
|
||||
CONFIG_L2_TO_L3_COPY=
|
||||
CONFIG_LWIP_MAX_SOCKETS=4
|
||||
CONFIG_LWIP_SO_REUSE=
|
||||
CONFIG_LWIP_SO_RCVBUF=
|
||||
CONFIG_LWIP_DHCP_MAX_NTP_SERVERS=1
|
||||
CONFIG_LWIP_IP_FRAG=
|
||||
CONFIG_LWIP_IP_REASSEMBLY=
|
||||
CONFIG_LWIP_STATS=
|
||||
CONFIG_LWIP_ETHARP_TRUST_IP_MAC=y
|
||||
CONFIG_TCPIP_RECVMBOX_SIZE=32
|
||||
CONFIG_LWIP_DHCP_DOES_ARP_CHECK=y
|
||||
|
||||
#
|
||||
# DHCP server
|
||||
#
|
||||
CONFIG_LWIP_DHCPS_LEASE_UNIT=60
|
||||
CONFIG_LWIP_DHCPS_MAX_STATION_NUM=8
|
||||
CONFIG_LWIP_AUTOIP=
|
||||
CONFIG_LWIP_NETIF_LOOPBACK=y
|
||||
CONFIG_LWIP_LOOPBACK_MAX_PBUFS=8
|
||||
|
||||
#
|
||||
# TCP
|
||||
#
|
||||
CONFIG_LWIP_MAX_ACTIVE_TCP=16
|
||||
CONFIG_LWIP_MAX_LISTENING_TCP=16
|
||||
CONFIG_TCP_MAXRTX=12
|
||||
CONFIG_TCP_SYNMAXRTX=6
|
||||
CONFIG_TCP_MSS=1436
|
||||
CONFIG_TCP_MSL=60000
|
||||
CONFIG_TCP_SND_BUF_DEFAULT=5744
|
||||
CONFIG_TCP_WND_DEFAULT=5744
|
||||
CONFIG_TCP_RECVMBOX_SIZE=6
|
||||
CONFIG_TCP_QUEUE_OOSEQ=y
|
||||
CONFIG_TCP_OVERSIZE_MSS=y
|
||||
CONFIG_TCP_OVERSIZE_QUARTER_MSS=
|
||||
CONFIG_TCP_OVERSIZE_DISABLE=
|
||||
|
||||
#
|
||||
# UDP
|
||||
#
|
||||
CONFIG_LWIP_MAX_UDP_PCBS=16
|
||||
CONFIG_UDP_RECVMBOX_SIZE=6
|
||||
CONFIG_TCPIP_TASK_STACK_SIZE=2048
|
||||
CONFIG_PPP_SUPPORT=
|
||||
|
||||
#
|
||||
# ICMP
|
||||
#
|
||||
CONFIG_LWIP_MULTICAST_PING=
|
||||
CONFIG_LWIP_BROADCAST_PING=
|
||||
|
||||
#
|
||||
# LWIP RAW API
|
||||
#
|
||||
CONFIG_LWIP_MAX_RAW_PCBS=16
|
||||
|
||||
#
|
||||
# mbedTLS
|
||||
#
|
||||
CONFIG_MBEDTLS_SSL_MAX_CONTENT_LEN=16384
|
||||
CONFIG_MBEDTLS_DEBUG=
|
||||
CONFIG_MBEDTLS_HARDWARE_AES=y
|
||||
CONFIG_MBEDTLS_HARDWARE_MPI=y
|
||||
CONFIG_MBEDTLS_MPI_USE_INTERRUPT=y
|
||||
CONFIG_MBEDTLS_HARDWARE_SHA=
|
||||
CONFIG_MBEDTLS_HAVE_TIME=y
|
||||
CONFIG_MBEDTLS_HAVE_TIME_DATE=
|
||||
CONFIG_MBEDTLS_TLS_SERVER_AND_CLIENT=y
|
||||
CONFIG_MBEDTLS_TLS_SERVER_ONLY=
|
||||
CONFIG_MBEDTLS_TLS_CLIENT_ONLY=
|
||||
CONFIG_MBEDTLS_TLS_DISABLED=
|
||||
CONFIG_MBEDTLS_TLS_SERVER=y
|
||||
CONFIG_MBEDTLS_TLS_CLIENT=y
|
||||
CONFIG_MBEDTLS_TLS_ENABLED=y
|
||||
|
||||
#
|
||||
# TLS Key Exchange Methods
|
||||
#
|
||||
CONFIG_MBEDTLS_PSK_MODES=
|
||||
CONFIG_MBEDTLS_KEY_EXCHANGE_RSA=y
|
||||
CONFIG_MBEDTLS_KEY_EXCHANGE_DHE_RSA=y
|
||||
CONFIG_MBEDTLS_KEY_EXCHANGE_ELLIPTIC_CURVE=y
|
||||
CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_RSA=y
|
||||
CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_ECDSA=y
|
||||
CONFIG_MBEDTLS_KEY_EXCHANGE_ECDH_ECDSA=y
|
||||
CONFIG_MBEDTLS_KEY_EXCHANGE_ECDH_RSA=y
|
||||
CONFIG_MBEDTLS_SSL_RENEGOTIATION=y
|
||||
CONFIG_MBEDTLS_SSL_PROTO_SSL3=
|
||||
CONFIG_MBEDTLS_SSL_PROTO_TLS1=y
|
||||
CONFIG_MBEDTLS_SSL_PROTO_TLS1_1=y
|
||||
CONFIG_MBEDTLS_SSL_PROTO_TLS1_2=y
|
||||
CONFIG_MBEDTLS_SSL_PROTO_DTLS=
|
||||
CONFIG_MBEDTLS_SSL_ALPN=y
|
||||
CONFIG_MBEDTLS_SSL_SESSION_TICKETS=y
|
||||
|
||||
#
|
||||
# Symmetric Ciphers
|
||||
#
|
||||
CONFIG_MBEDTLS_AES_C=y
|
||||
CONFIG_MBEDTLS_CAMELLIA_C=
|
||||
CONFIG_MBEDTLS_DES_C=
|
||||
CONFIG_MBEDTLS_RC4_DISABLED=y
|
||||
CONFIG_MBEDTLS_RC4_ENABLED_NO_DEFAULT=
|
||||
CONFIG_MBEDTLS_RC4_ENABLED=
|
||||
CONFIG_MBEDTLS_BLOWFISH_C=
|
||||
CONFIG_MBEDTLS_XTEA_C=
|
||||
CONFIG_MBEDTLS_CCM_C=y
|
||||
CONFIG_MBEDTLS_GCM_C=y
|
||||
CONFIG_MBEDTLS_RIPEMD160_C=
|
||||
|
||||
#
|
||||
# Certificates
|
||||
#
|
||||
CONFIG_MBEDTLS_PEM_PARSE_C=y
|
||||
CONFIG_MBEDTLS_PEM_WRITE_C=y
|
||||
CONFIG_MBEDTLS_X509_CRL_PARSE_C=y
|
||||
CONFIG_MBEDTLS_X509_CSR_PARSE_C=y
|
||||
CONFIG_MBEDTLS_ECP_C=y
|
||||
CONFIG_MBEDTLS_ECDH_C=y
|
||||
CONFIG_MBEDTLS_ECDSA_C=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP192R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP224R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP256R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP384R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP521R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP192K1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP224K1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP256K1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_BP256R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_BP384R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_BP512R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_CURVE25519_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_NIST_OPTIM=y
|
||||
|
||||
#
|
||||
# OpenSSL
|
||||
#
|
||||
CONFIG_OPENSSL_DEBUG=
|
||||
CONFIG_OPENSSL_ASSERT_DO_NOTHING=y
|
||||
CONFIG_OPENSSL_ASSERT_EXIT=
|
||||
|
||||
#
|
||||
# PThreads
|
||||
#
|
||||
CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5
|
||||
CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072
|
||||
|
||||
#
|
||||
# SPI Flash driver
|
||||
#
|
||||
CONFIG_SPI_FLASH_VERIFY_WRITE=
|
||||
CONFIG_SPI_FLASH_ENABLE_COUNTERS=
|
||||
CONFIG_SPI_FLASH_ROM_DRIVER_PATCH=y
|
||||
CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y
|
||||
CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_FAILS=
|
||||
CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ALLOWED=
|
||||
|
||||
#
|
||||
# SPIFFS Configuration
|
||||
#
|
||||
CONFIG_SPIFFS_MAX_PARTITIONS=3
|
||||
|
||||
#
|
||||
# SPIFFS Cache Configuration
|
||||
#
|
||||
CONFIG_SPIFFS_CACHE=y
|
||||
CONFIG_SPIFFS_CACHE_WR=y
|
||||
CONFIG_SPIFFS_CACHE_STATS=
|
||||
CONFIG_SPIFFS_PAGE_CHECK=y
|
||||
CONFIG_SPIFFS_GC_MAX_RUNS=10
|
||||
CONFIG_SPIFFS_GC_STATS=
|
||||
CONFIG_SPIFFS_OBJ_NAME_LEN=32
|
||||
CONFIG_SPIFFS_USE_MAGIC=y
|
||||
CONFIG_SPIFFS_USE_MAGIC_LENGTH=y
|
||||
CONFIG_SPIFFS_META_LENGTH=4
|
||||
CONFIG_SPIFFS_USE_MTIME=y
|
||||
|
||||
#
|
||||
# Debug Configuration
|
||||
#
|
||||
CONFIG_SPIFFS_DBG=
|
||||
CONFIG_SPIFFS_API_DBG=
|
||||
CONFIG_SPIFFS_GC_DBG=
|
||||
CONFIG_SPIFFS_CACHE_DBG=
|
||||
CONFIG_SPIFFS_CHECK_DBG=
|
||||
CONFIG_SPIFFS_TEST_VISUALISATION=
|
||||
|
||||
#
|
||||
# tcpip adapter
|
||||
#
|
||||
CONFIG_IP_LOST_TIMER_INTERVAL=120
|
||||
|
||||
#
|
||||
# Wear Levelling
|
||||
#
|
||||
CONFIG_WL_SECTOR_SIZE_512=
|
||||
CONFIG_WL_SECTOR_SIZE_4096=y
|
||||
CONFIG_WL_SECTOR_SIZE=4096
|
Ładowanie…
Reference in New Issue