diff --git a/README.md b/README.md index 2bcd4851..8f793552 100644 --- a/README.md +++ b/README.md @@ -44,7 +44,7 @@ Depending on board hardware following features are supported: - Button - Silicon unique ID - Battery voltage monitoring -- GPS +- GPS (Generic serial NMEA, or Quectel L76 I2C) Target platform must be selected in [platformio.ini](https://github.com/cyberman54/ESP32-Paxcounter/blob/master/platformio.ini).
Hardware dependent settings (pinout etc.) are stored in board files in /hal directory. If you want to use a ESP32 board which is not yet supported, use hal file generic.h and tailor pin mappings to your needs. Pull requests for new boards welcome.
diff --git a/platformio.ini b/platformio.ini index 89b44400..98e23235 100644 --- a/platformio.ini +++ b/platformio.ini @@ -26,7 +26,7 @@ description = Paxcounter is a proof-of-concept ESP32 device for metering passeng [common] ; for release_version use max. 10 chars total, use any decimal format like "a.b.c" -release_version = 1.4.35 +release_version = 1.5.1 ; DEBUG LEVEL: For production run set to 0, otherwise device will leak RAM while running! ; 0=None, 1=Error, 2=Warn, 3=Info, 4=Debug, 5=Verbose debug_level = 0 @@ -76,7 +76,7 @@ platform = ${common.platform_espressif32} framework = arduino board = heltec_wifi_lora_32 board_build.partitions = ${common.board_build.partitions} -upload_speed = 115200 +upload_speed = 921600 lib_deps = ${common.lib_deps_all} ${common.lib_deps_display} diff --git a/src/cyclic.cpp b/src/cyclic.cpp index 72b2284c..95185a98 100644 --- a/src/cyclic.cpp +++ b/src/cyclic.cpp @@ -10,7 +10,11 @@ static const char TAG[] = "main"; // do all housekeeping -void doHomework() { +void doHousekeeping() { + + portENTER_CRITICAL(&timerMux); + HomeCycleIRQ = 0; + portEXIT_CRITICAL(&timerMux); // update uptime counter uptime(); @@ -49,16 +53,7 @@ void doHomework() { if (esp_get_minimum_free_heap_size() <= MEM_LOW) // check again esp_restart(); // memory leak, reset device } -} // doHomework() - -void checkHousekeeping() { - if (HomeCycleIRQ) { - portENTER_CRITICAL(&timerMux); - HomeCycleIRQ = 0; - portEXIT_CRITICAL(&timerMux); - doHomework(); - } -} +} // doHousekeeping() void IRAM_ATTR homeCycleIRQ() { portENTER_CRITICAL(&timerMux); diff --git a/src/cyclic.h b/src/cyclic.h index fbe1309a..0a169e4e 100644 --- a/src/cyclic.h +++ b/src/cyclic.h @@ -1,8 +1,7 @@ #ifndef _CYCLIC_H #define _CYCLIC_H -void doHomework(void); -void checkHousekeeping(void); +void doHousekeeping(void); void homeCycleIRQ(void); uint64_t uptime(void); void reset_counters(void); diff --git a/src/globals.h b/src/globals.h index fd057b5d..2d8d692f 100644 --- a/src/globals.h +++ b/src/globals.h @@ -55,6 +55,7 @@ extern std::array::iterator it; extern std::array beacons; #ifdef HAS_GPS +extern TaskHandle_t GpsTask; #include "gps.h" #endif diff --git a/src/gps.cpp b/src/gps.cpp index 10d05c14..849ca30e 100644 --- a/src/gps.cpp +++ b/src/gps.cpp @@ -5,7 +5,7 @@ // Local logging tag static const char TAG[] = "main"; -TinyGPSPlus gps; +TinyGPSPlus gps; gpsStatus_t gps_status; // read GPS data and cast to global struct @@ -25,49 +25,45 @@ void gps_loop(void *pvParameters) { // initialize and, if needed, configure, GPS #if defined GPS_SERIAL HardwareSerial GPS_Serial(1); + GPS_Serial.begin(GPS_SERIAL); + #elif defined GPS_QUECTEL_L76 + uint8_t ret; Wire.begin(GPS_QUECTEL_L76, 400000); // I2C connect to GPS device with 400 KHz + Wire.beginTransmission(GPS_ADDR); + Wire.write(0x00); // dummy write + ret = Wire.endTransmission(); // check if chip is seen on i2c bus + + if (ret) { + ESP_LOGE(TAG, + "Quectel L76 GPS chip not found on i2c bus, bus error %d. " + "Stopping GPS-Task.", + ret); + vTaskDelete(GpsTask); + } else { + ESP_LOGI(TAG, "Quectel L76 GPS chip found."); + } + #endif while (1) { if (cfg.gpsmode) { #if defined GPS_SERIAL - - // serial connect to GPS device - GPS_Serial.begin(GPS_SERIAL); - - while (cfg.gpsmode) { - // feed GPS decoder with serial NMEA data from GPS device - while (GPS_Serial.available()) { - gps.encode(GPS_Serial.read()); - } - vTaskDelay(2 / portTICK_PERIOD_MS); // reset watchdog + // feed GPS decoder with serial NMEA data from GPS device + while (GPS_Serial.available()) { + gps.encode(GPS_Serial.read()); } - // after GPS function was disabled, close connect to GPS device - GPS_Serial.end(); - #elif defined GPS_QUECTEL_L76 - - Wire.beginTransmission(GPS_ADDR); - Wire.write(0x00); // dummy write to start read - Wire.endTransmission(); - - Wire.beginTransmission(GPS_ADDR); - while (cfg.gpsmode) { - Wire.requestFrom(GPS_ADDR | 0x01, 32); - while (Wire.available()) { - gps.encode(Wire.read()); - vTaskDelay(2 / portTICK_PERIOD_MS); // polling mode: 500ms sleep - } + Wire.requestFrom(GPS_ADDR, 32); // caution: this is a blocking call + while (Wire.available()) { + gps.encode(Wire.read()); + vTaskDelay(2 / portTICK_PERIOD_MS); // 2ms delay according L76 datasheet } - // after GPS function was disabled, close connect to GPS device - Wire.endTransmission(); +#endif + } // if (cfg.gpsmode) -#endif // GPS Type - } - - vTaskDelay(2 / portTICK_PERIOD_MS); // reset watchdog + vTaskDelay(2 / portTICK_PERIOD_MS); // yield to CPU } // end of infinite loop diff --git a/src/gps.h b/src/gps.h index 45406ff7..5121528e 100644 --- a/src/gps.h +++ b/src/gps.h @@ -1,9 +1,13 @@ #ifndef _GPS_H #define _GPS_H -#include // library for parsing NMEA data +#include // library for parsing NMEA data #include +#ifdef GPS_QUECTEL_L76 // Needed for reading from I2C Bus +#include +#endif + typedef struct { uint32_t latitude; uint32_t longitude; @@ -12,8 +16,9 @@ typedef struct { uint16_t altitude; } gpsStatus_t; -extern TinyGPSPlus gps; // Make TinyGPS++ instance globally availabe -extern gpsStatus_t gps_status; // Make struct for storing gps data globally available +extern TinyGPSPlus gps; // Make TinyGPS++ instance globally availabe +extern gpsStatus_t + gps_status; // Make struct for storing gps data globally available void gps_read(void); void gps_loop(void *pvParameters); diff --git a/src/hal/generic.h b/src/hal/generic.h index d5863038..f25a8219 100644 --- a/src/hal/generic.h +++ b/src/hal/generic.h @@ -35,4 +35,8 @@ // pin definitions for I2C interface of OLED Display #define OLED_RST GPIO_NUM_16 // SSD1306 RST #define I2C_SDA GPIO_NUM_4 // SD1306 D1+D2 -#define I2C_SCL GPIO_NUM_15 // SD1306 D0 \ No newline at end of file +#define I2C_SCL GPIO_NUM_15 // SD1306 D0 + +// I2C config for Microchip 24AA02E64 DEVEUI unique address +#define MCP_24AA02E64_I2C_ADDRESS 0x50 // I2C address for the 24AA02E64 +#define MCP_24AA02E64_MAC_ADDRESS 0xF8 // Memory adress of unique deveui 64 bits \ No newline at end of file diff --git a/src/hal/lopy.h b/src/hal/lopy.h index 0e414326..2caeb308 100644 --- a/src/hal/lopy.h +++ b/src/hal/lopy.h @@ -20,14 +20,10 @@ #define HAS_ANTENNA_SWITCH 16 // pin for switching wifi antenna #define WIFI_ANTENNA 0 // 0 = internal, 1 = external -// !!EXPERIMENTAL - not tested yet!! // uncomment this only if your LoPy runs on a Pytrack expansion board with GPS -// see http://www.quectel.com/UploadImage/Downlad/Quectel_L76-L_I2C_Application_Note_V1.0.pdf -//#define HAS_GPS 1 -//#define GPS_QUECTEL_L76 GPIO_NUM_25, GPIO_NUM_26 // SDA (P22), SCL (P21) -//#define GPS_ADDR 0x10 -//#define HAS_BUTTON GPIO_NUM_37 // (P14) -//#define BUTTON_PULLUP 1 // Button need pullup instead of default pulldown +#define HAS_GPS 1 +#define GPS_QUECTEL_L76 GPIO_NUM_25, GPIO_NUM_26 // SDA (P22), SCL (P21) +#define GPS_ADDR 0x10 // uncomment this only if your LoPy runs on a expansion board 3.0 //#define HAS_BATTERY_PROBE ADC1_GPIO39_CHANNEL // battery probe GPIO pin -> ADC1_CHANNEL_7 diff --git a/src/hal/lopy4.h b/src/hal/lopy4.h index 9e1169ab..cf988324 100644 --- a/src/hal/lopy4.h +++ b/src/hal/lopy4.h @@ -21,14 +21,10 @@ #define HAS_ANTENNA_SWITCH 21 // pin for switching wifi antenna #define WIFI_ANTENNA 0 // 0 = internal, 1 = external -// !!EXPERIMENTAL - not tested yet!! // uncomment this only if your LoPy runs on a Pytrack expansion board with GPS -// see http://www.quectel.com/UploadImage/Downlad/Quectel_L76-L_I2C_Application_Note_V1.0.pdf //#define HAS_GPS 1 //#define GPS_QUECTEL_L76 GPIO_NUM_25, GPIO_NUM_26 // SDA (P22), SCL (P21) //#define GPS_ADDR 0x10 -//#define HAS_BUTTON GPIO_NUM_37 // (P14) -//#define BUTTON_PULLUP 1 // Button need pullup instead of default pulldown // uncomment this only if your LoPy runs on a expansion board 3.0 #define HAS_BATTERY_PROBE ADC1_GPIO39_CHANNEL // battery probe GPIO pin -> ADC1_CHANNEL_7 diff --git a/src/lorawan.cpp b/src/lorawan.cpp index 5ffed2cb..95babc37 100644 --- a/src/lorawan.cpp +++ b/src/lorawan.cpp @@ -1,12 +1,7 @@ #ifdef HAS_LORA // Basic Config -#include "globals.h" -#include "rcommand.h" - -#ifdef MCP_24AA02E64_I2C_ADDRESS -#include // Needed for 24AA02E64, does not hurt anything if included and not used -#endif +#include "lorawan.h" // Local logging Tag static const char TAG[] = "lora"; @@ -37,13 +32,13 @@ void gen_lora_deveui(uint8_t *pdeveui) { } } -/* The above function should be changed to this one, but this would be a breaking change - +/* new version, does it with well formed mac according IEEE spec, but is +breaking change // DevEUI generator using devices's MAC address void gen_lora_deveui(uint8_t *pdeveui) { uint8_t *p = pdeveui, dmac[6]; ESP_ERROR_CHECK(esp_efuse_mac_get_default(dmac)); - // deveui is LSB, we reverse it so TTN DEVEUI display + // deveui is LSB, we reverse it so TTN DEVEUI display // will remain the same as MAC address // MAC is 6 bytes, devEUI 8, set middle 2 ones // to an arbitrary value @@ -98,29 +93,34 @@ void os_getDevEui(u1_t *buf) { void get_hard_deveui(uint8_t *pdeveui) { // read DEVEUI from Microchip 24AA02E64 2Kb serial eeprom if present #ifdef MCP_24AA02E64_I2C_ADDRESS + uint8_t i2c_ret; + // Init this just in case, no more to 100KHz Wire.begin(I2C_SDA, I2C_SCL, 100000); Wire.beginTransmission(MCP_24AA02E64_I2C_ADDRESS); Wire.write(MCP_24AA02E64_MAC_ADDRESS); i2c_ret = Wire.endTransmission(); - // check if device seen on i2c bus + + // check if device was seen on i2c bus if (i2c_ret == 0) { char deveui[32] = ""; uint8_t data; + Wire.beginTransmission(MCP_24AA02E64_I2C_ADDRESS); Wire.write(MCP_24AA02E64_MAC_ADDRESS); + Wire.endTransmission(); + Wire.requestFrom(MCP_24AA02E64_I2C_ADDRESS, 8); while (Wire.available()) { data = Wire.read(); sprintf(deveui + strlen(deveui), "%02X ", data); *pdeveui++ = data; } - i2c_ret = Wire.endTransmission(); - ESP_LOGI(TAG, "Serial EEPROM 24AA02E64 found, read DEVEUI %s", deveui); - } else { - ESP_LOGI(TAG, "Serial EEPROM 24AA02E64 not found ret=%d", i2c_ret); - } + ESP_LOGI(TAG, "Serial EEPROM found, read DEVEUI %s", deveui); + } else + ESP_LOGI(TAG, "Could not read DEVEUI from serial EEPROM"); + // Set back to 400KHz to speed up OLED Wire.setClock(400000); #endif // MCP 24AA02E64 @@ -248,7 +248,7 @@ void lorawan_loop(void *pvParameters) { while (1) { os_runloop_once(); // execute LMIC jobs - vTaskDelay(2 / portTICK_PERIOD_MS); // reset watchdog + vTaskDelay(2 / portTICK_PERIOD_MS); // yield to CPU } } diff --git a/src/lorawan.h b/src/lorawan.h index d88062e7..32220496 100644 --- a/src/lorawan.h +++ b/src/lorawan.h @@ -1,11 +1,19 @@ #ifndef _LORAWAN_H #define _LORAWAN_H +#include "globals.h" +#include "rcommand.h" + // LMIC-Arduino LoRaWAN Stack #include #include #include "loraconf.h" +// Needed for 24AA02E64, does not hurt anything if included and not used +#ifdef MCP_24AA02E64_I2C_ADDRESS +#include +#endif + void onEvent(ev_t ev); void gen_lora_deveui(uint8_t *pdeveui); void RevBytes(unsigned char *b, size_t c); diff --git a/src/main.cpp b/src/main.cpp index d84deb18..7f0d1ada 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -33,14 +33,14 @@ uint16_t macs_total = 0, macs_wifi = 0, macs_ble = 0, batt_voltage = 0; // globals for display // hardware timer for cyclic tasks -hw_timer_t *channelSwitch = NULL, *displaytimer = NULL, *sendCycle = NULL, - *homeCycle = NULL; +hw_timer_t *channelSwitch, *displaytimer, *sendCycle, *homeCycle; // this variables will be changed in the ISR, and read in main loop volatile int ButtonPressedIRQ = 0, ChannelTimerIRQ = 0, SendCycleTimerIRQ = 0, DisplayTimerIRQ = 0, HomeCycleIRQ = 0; TaskHandle_t WifiLoopTask = NULL; +TaskHandle_t StateTask = NULL; // RTos send queues for payload transmit #ifdef HAS_LORA @@ -52,6 +52,10 @@ TaskHandle_t LoraTask = NULL; QueueHandle_t SPISendQueue; #endif +#ifdef HAS_GPS +TaskHandle_t GpsTask = NULL; +#endif + portMUX_TYPE timerMux = portMUX_INITIALIZER_UNLOCKED; // sync main loop and ISR when modifying IRQ // handler shared variables @@ -64,9 +68,6 @@ PayloadConvert payload(PAYLOAD_BUFFER_SIZE); // local Tag for logging static const char TAG[] = "main"; -/* begin Aruino SETUP - * ------------------------------------------------------------ */ - void setup() { // disable the default wifi logging @@ -215,6 +216,16 @@ void setup() { DisplayState = cfg.screenon; init_display(PRODUCTNAME, PROGVERSION); + /* + Usage of ESP32 hardware timers + ============================== + + 0 Display-Refresh + 1 Wifi Channel Switch + 2 Send Cycle + 3 Housekeeping + */ + // setup display refresh trigger IRQ using esp32 hardware timer // https://techtutorialsx.com/2017/10/07/esp32-arduino-timer-interrupts/ @@ -225,6 +236,7 @@ void setup() { // reload interrupt after each trigger of display refresh cycle timerAlarmWrite(displaytimer, DISPLAYREFRESH_MS * 1000, true); // enable display interrupt + yield(); timerAlarmEnable(displaytimer); #endif @@ -232,19 +244,25 @@ void setup() { channelSwitch = timerBegin(1, 800, true); timerAttachInterrupt(channelSwitch, &ChannelSwitchIRQ, true); timerAlarmWrite(channelSwitch, cfg.wifichancycle * 1000, true); - timerAlarmEnable(channelSwitch); // setup send cycle trigger IRQ using esp32 hardware timer 2 sendCycle = timerBegin(2, 8000, true); timerAttachInterrupt(sendCycle, &SendCycleIRQ, true); timerAlarmWrite(sendCycle, cfg.sendcycle * 2 * 10000, true); - timerAlarmEnable(sendCycle); // setup house keeping cycle trigger IRQ using esp32 hardware timer 3 homeCycle = timerBegin(3, 8000, true); timerAttachInterrupt(homeCycle, &homeCycleIRQ, true); timerAlarmWrite(homeCycle, HOMECYCLE * 10000, true); + + // enable timers + // caution, see: https://github.com/espressif/arduino-esp32/issues/1313 + yield(); timerAlarmEnable(homeCycle); + yield(); + timerAlarmEnable(sendCycle); + yield(); + timerAlarmEnable(channelSwitch); // show payload encoder #if PAYLOAD_ENCODER == 1 @@ -276,59 +294,63 @@ void setup() { // join network LMIC_startJoining(); + /* + + Task Core Prio Purpose + ==================================================================== + IDLE 0 0 ESP32 arduino scheduler + gpsloop 0 2 read data from GPS over serial or i2c + IDLE 1 0 Arduino loop() -> used for LED switching + loraloop 1 1 runs the LMIC stack + statemachine 1 3 switches application process logic + + */ + // start lmic runloop in rtos task on core 1 // (note: arduino main loop runs on core 1, too) // https://techtutorialsx.com/2017/05/09/esp32-get-task-execution-core/ - ESP_LOGI(TAG, "Starting Lora task on core 1"); - xTaskCreatePinnedToCore(lorawan_loop, "loraloop", 2048, (void *)1, - (5 | portPRIVILEGE_BIT), &LoraTask, 1); + ESP_LOGI(TAG, "Starting Lora..."); + xTaskCreatePinnedToCore(lorawan_loop, "loraloop", 2048, (void *)1, 1, + &LoraTask, 1); #endif // if device has GPS and it is enabled, start GPS reader task on core 0 with // higher priority than wifi channel rotation task since we process serial // streaming NMEA data #ifdef HAS_GPS - if (cfg.gpsmode) { - ESP_LOGI(TAG, "Starting GPS task on core 0"); - xTaskCreatePinnedToCore(gps_loop, "gpsloop", 2048, (void *)1, 2, NULL, 0); - } + ESP_LOGI(TAG, "Starting GPS..."); + xTaskCreatePinnedToCore(gps_loop, "gpsloop", 2048, (void *)1, 2, &GpsTask, 0); #endif // start BLE scan callback if BLE function is enabled in NVRAM configuration #ifdef BLECOUNTER if (cfg.blescan) { - ESP_LOGI(TAG, "Starting BLE task on core 1"); + ESP_LOGI(TAG, "Starting Bluetooth..."); start_BLEscan(); } #endif // start wifi in monitor mode and start channel rotation task on core 0 - ESP_LOGI(TAG, "Starting Wifi task on core 0"); + ESP_LOGI(TAG, "Starting Wifi..."); wifi_sniffer_init(); // initialize salt value using esp_random() called by random() in // arduino-esp32 core. Note: do this *after* wifi has started, since // function gets it's seed from RF noise reset_salt(); // get new 16bit for salting hashes - xTaskCreatePinnedToCore(wifi_channel_loop, "wifiloop", 2048, (void *)1, 1, - &WifiLoopTask, 0); + + // start state machine + ESP_LOGI(TAG, "Starting Statemachine..."); + xTaskCreatePinnedToCore(stateMachine, "stateloop", 2048, (void *)1, 3, + &StateTask, 1); + } // setup() -/* end Arduino SETUP - * ------------------------------------------------------------ */ +void stateMachine(void *pvParameters) { -/* begin Arduino main loop - * ------------------------------------------------------ */ - -void loop() { + configASSERT(((uint32_t)pvParameters) == 1); // FreeRTOS check while (1) { - // state machine for switching display, LED, button, housekeeping, - // senddata - -#if (HAS_LED != NOT_A_PIN) || defined(HAS_RGB_LED) - led_loop(); -#endif #ifdef HAS_BUTTON readButton(); @@ -338,17 +360,30 @@ void loop() { updateDisplay(); #endif - // check housekeeping cycle and if expired do homework - checkHousekeeping(); + // check wifi scan cycle and if due rotate channel + if (ChannelTimerIRQ) + switchWifiChannel(channel); + // check housekeeping cycle and if due do the work + if (HomeCycleIRQ) + doHousekeeping(); // check send queue and process it - processSendBuffer(); - // check send cycle and enqueue payload if cycle is expired - sendPayload(); - // reset watchdog - vTaskDelay(2 / portTICK_PERIOD_MS); + enqueuePayload(); + // check send cycle and if due enqueue payload to send + if (SendCycleTimerIRQ) + sendPayload(); - } // loop() + // give yield to CPU + vTaskDelay(2 / portTICK_PERIOD_MS); + } } -/* end Arduino main loop - * ------------------------------------------------------------ */ +void loop() { + +// switch LED states if device has a LED +#if (HAS_LED != NOT_A_PIN) || defined(HAS_RGB_LED) + led_loop(); +#endif + + // give yield to CPU + vTaskDelay(2 / portTICK_PERIOD_MS); +} diff --git a/src/main.h b/src/main.h index 4b77439a..e1d8b775 100644 --- a/src/main.h +++ b/src/main.h @@ -13,5 +13,8 @@ #include // needed for reading ESP32 chip attributes #include // needed for Wifi event handler +#include // needed for timers + +void stateMachine(void *pvParameters); #endif \ No newline at end of file diff --git a/src/ota.cpp b/src/ota.cpp index dbdcc30d..93a94e6c 100644 --- a/src/ota.cpp +++ b/src/ota.cpp @@ -15,7 +15,7 @@ limitations under the License. */ -#include "OTA.h" +#include "ota.h" const BintrayClient bintray(BINTRAY_USER, BINTRAY_REPO, BINTRAY_PACKAGE); @@ -246,7 +246,7 @@ int version_compare(const String v1, const String v2) { // vnum stores each numeric part of version int vnum1 = 0, vnum2 = 0; - // loop untill both string are processed + // loop until both string are processed for (int i = 0, j = 0; (i < v1.length() || j < v2.length());) { // storing numeric part of version 1 in vnum1 while (i < v1.length() && v1[i] != '.') { diff --git a/src/ota.h b/src/ota.h index 4b9e92d1..27c1b748 100644 --- a/src/ota.h +++ b/src/ota.h @@ -6,6 +6,7 @@ #include #include #include +#include void checkFirmwareUpdates(); void processOTAUpdate(const String &version); diff --git a/src/senddata.cpp b/src/senddata.cpp index f7e3824c..ad647233 100644 --- a/src/senddata.cpp +++ b/src/senddata.cpp @@ -34,39 +34,36 @@ void SendData(uint8_t port) { } } // SendData -// cyclic called function to prepare payload to send +// interrupt triggered function to prepare payload to send void sendPayload() { - if (SendCycleTimerIRQ) { - portENTER_CRITICAL(&timerMux); - SendCycleTimerIRQ = 0; - portEXIT_CRITICAL(&timerMux); + portENTER_CRITICAL(&timerMux); + SendCycleTimerIRQ = 0; + portEXIT_CRITICAL(&timerMux); - // append counter data to payload - payload.reset(); - payload.addCount(macs_wifi, cfg.blescan ? macs_ble : 0); - // append GPS data, if present + // append counter data to payload + payload.reset(); + payload.addCount(macs_wifi, cfg.blescan ? macs_ble : 0); + // append GPS data, if present #ifdef HAS_GPS - // show NMEA data in debug mode, useful for debugging GPS on board - // connection - ESP_LOGD(TAG, "GPS NMEA data: passed %d / failed: %d / with fix: %d", - gps.passedChecksum(), gps.failedChecksum(), - gps.sentencesWithFix()); - // log GPS position if we have a fix and gps data mode is enabled - if ((cfg.gpsmode) && (gps.location.isValid())) { - gps_read(); - payload.addGPS(gps_status); - ESP_LOGD(TAG, "lat=%.6f | lon=%.6f | %u Sats | HDOP=%.1f | Altitude=%um", - gps_status.latitude / (float)1e6, - gps_status.longitude / (float)1e6, gps_status.satellites, - gps_status.hdop / (float)100, gps_status.altitude); - } else { - ESP_LOGD(TAG, "No valid GPS position or GPS data mode disabled"); - } -#endif - SendData(COUNTERPORT); + // show NMEA data in debug mode, useful for debugging GPS on board + // connection + ESP_LOGD(TAG, "GPS NMEA data: passed %d / failed: %d / with fix: %d", + gps.passedChecksum(), gps.failedChecksum(), gps.sentencesWithFix()); + // log GPS position if we have a fix and gps data mode is enabled + if ((cfg.gpsmode) && (gps.location.isValid())) { + gps_read(); + payload.addGPS(gps_status); + ESP_LOGD(TAG, "lat=%.6f | lon=%.6f | %u Sats | HDOP=%.1f | Altitude=%um", + gps_status.latitude / (float)1e6, + gps_status.longitude / (float)1e6, gps_status.satellites, + gps_status.hdop / (float)100, gps_status.altitude); + } else { + ESP_LOGD(TAG, "No valid GPS position or GPS data mode disabled"); } +#endif + SendData(COUNTERPORT); } // sendpayload() // interrupt handler used for payload send cycle timer @@ -76,9 +73,8 @@ void IRAM_ATTR SendCycleIRQ() { portEXIT_CRITICAL(&timerMux); } -// cyclic called function to eat data from RTos send queues and transmit it -void processSendBuffer() { - +// interrupt triggered function to eat data from RTos send queues and transmit it +void enqueuePayload() { MessageBuffer_t SendBuffer; #ifdef HAS_LORA @@ -102,7 +98,7 @@ void processSendBuffer() { } #endif -} // processSendBuffer +} // enqueuePayload void flushQueues() { #ifdef HAS_LORA diff --git a/src/senddata.h b/src/senddata.h index 806899d6..eba9d8bd 100644 --- a/src/senddata.h +++ b/src/senddata.h @@ -4,7 +4,7 @@ void SendData(uint8_t port); void sendPayload(void); void SendCycleIRQ(void); -void processSendBuffer(void); +void enqueuePayload(void); void flushQueues(); #endif // _SENDDATA_H_ \ No newline at end of file diff --git a/src/vendor_array.h b/src/vendor_array.h index fd555495..4ab56cfc 100644 --- a/src/vendor_array.h +++ b/src/vendor_array.h @@ -1,4 +1,4 @@ -std::array vendors = { +std::array vendors = { 0x38f23e, 0x807abf, 0x90e7c4, 0x7c6193, 0x485073, 0x74e28c, 0x8463d6, 0xd48f33, 0x2c8a72, 0x980d2e, 0xa826d9, 0xd4206d, 0x00155d, 0x806c1b, 0xa470d6, 0x985fd3, 0x1c69a5, 0x382de8, 0xd087e2, 0x205531, 0x5440ad, @@ -14,193 +14,210 @@ std::array vendors = { 0xd0dfc7, 0x1c62b8, 0x18e2c2, 0x001a8a, 0x002567, 0xa8f274, 0x001599, 0x0012fb, 0x7cf854, 0x8cc8cd, 0xe81132, 0xa02195, 0x8c71f8, 0x04180f, 0x9463d1, 0x0cdfa4, 0xcc051b, 0x68ebae, 0x60d0a9, 0x60a10a, 0xa07591, - 0x001fcc, 0xec107b, 0xa01081, 0xf4f524, 0x9c99a0, 0x185936, 0x98fae3, - 0x640980, 0x8cbebe, 0xf8a45f, 0xbc8385, 0x900628, 0xd4ae05, 0x3c0518, - 0xc40bcb, 0xe8bba8, 0xbc3aea, 0x8c0ee3, 0x6c5c14, 0x78abbb, 0x1816c9, + 0x001fcc, 0xec107b, 0xa01081, 0xf4f524, 0xbc8385, 0x900628, 0xd4ae05, + 0x3c0518, 0xe8bba8, 0xbc3aea, 0x8c0ee3, 0x6c5c14, 0x78abbb, 0x1816c9, 0xfc8f90, 0x244b03, 0x988389, 0x14bb6e, 0x1c3ade, 0xf83f51, 0xd8e0e1, - 0xecf342, 0x5092b9, 0xb4bff6, 0xc8d7b0, 0x982d68, 0xecd09f, 0xe446da, - 0xf4f5db, 0xd80831, 0xdc5583, 0x2c54cf, 0x001fe3, 0x0026e2, 0x001e75, - 0x6cd68a, 0x2021a5, 0x0c4885, 0xdc0b34, 0xac0d1b, 0x60e3ac, 0xf895c7, - 0xc4438f, 0xa816b2, 0xe892a4, 0x700514, 0x88c9d0, 0x2c598a, 0x18f0e4, - 0xec8350, 0x4cdd31, 0x703eac, 0x6c94f8, 0x84788b, 0x2cf0ee, 0x68d93c, - 0x24e314, 0x28f076, 0x285aeb, 0x087402, 0xccc760, 0x705aac, 0xfc643a, - 0xd4e6b7, 0x2802d8, 0x9c2ea1, 0x68967b, 0xbc6778, 0xa82066, 0xb065bd, - 0xf0dce2, 0x7cd1c3, 0x705681, 0x2cbe08, 0x783a84, 0x84b153, 0x6476ba, - 0x54ae27, 0xf437b7, 0xf0d1a9, 0x34c059, 0x04f7e4, 0x10ddb1, 0xb4f0ab, - 0x848506, 0x7831c1, 0x8c7c92, 0xd0e140, 0xacfdec, 0xf82793, 0x40a6d9, - 0x109add, 0xf0b479, 0x58b035, 0x34159e, 0x286aba, 0xec852f, 0x44d884, - 0x003ee1, 0x7c11be, 0x04e536, 0x881fa1, 0x04db56, 0x9cfc01, 0xc81ee7, - 0x34363b, 0xc01ada, 0xacbc32, 0x70700d, 0x7c5049, 0x503237, 0xd4619d, - 0xb0481a, 0x989e63, 0xdca904, 0x48a195, 0x6cab31, 0x6c96cf, 0x3035ad, - 0xa8be27, 0xb8634d, 0x9ce33f, 0xf0989d, 0xace4b5, 0xe42b34, 0x1c36bb, - 0x3c2eff, 0xf0766f, 0x40cbc0, 0x4098ad, 0x6c4d73, 0xc48466, 0xd02b20, - 0x3010e4, 0x380f4a, 0x685b35, 0xc86f1d, 0x701124, 0x38484c, 0x041552, - 0x786c1c, 0xbc3baf, 0x00a040, 0x60fec5, 0xcc4463, 0x6c72e7, 0x18af61, - 0x00cdfe, 0xac61ea, 0x38b54d, 0x60c547, 0x28e02c, 0x50ead6, 0x4860bc, - 0x403004, 0x0c74c2, 0xa4b197, 0x7cf05f, 0xa4f1e8, 0x70a2b3, 0x4c57ca, - 0x68fb7e, 0x90c1c6, 0x9cf48e, 0xfcd848, 0x64b9e8, 0x001cb3, 0x000d93, - 0x30d9d9, 0x6030d4, 0x94bf2d, 0xc49880, 0xe0338e, 0x68fef7, 0xbce143, - 0x645aed, 0xc0b658, 0x881908, 0xfc2a9c, 0x48605f, 0x188796, 0x002376, - 0x84100d, 0x04c23e, 0x5c5188, 0xe89120, 0x9c6c15, 0x4886e8, 0x2c2997, - 0x102f6b, 0x00eebd, 0x281878, 0x6045bd, 0x7ced8d, 0xe85b5b, 0x000d3a, - 0xe09861, 0xf4f1e1, 0x60beb5, 0xb4e1c4, 0x70aab2, 0x0026ff, 0x406f2a, - 0x002557, 0xf05a09, 0x503275, 0x28cc01, 0xb46293, 0x04fe31, 0x845181, - 0xd831cf, 0xf8d0bd, 0xfcc734, 0xe4b021, 0xb0ec71, 0x3cbbfd, 0x2cae2b, - 0xc488e5, 0x7c9122, 0xe8b4c8, 0x18895b, 0xe0db10, 0xe09971, 0x6077e2, - 0x680571, 0x6c2f2c, 0x300d43, 0x6c2779, 0x607edd, 0x9c2a83, 0xe45d75, - 0xe4faed, 0xc83f26, 0x54f201, 0xa06090, 0xac3743, 0x141f78, 0x006f64, - 0xdc6672, 0x001e7d, 0x3c6200, 0x0024e9, 0x002399, 0xe4e0c5, 0xe8039a, - 0xc4731e, 0x8c7712, 0x2013e0, 0x0007ab, 0x0021d2, 0xbc4760, 0xd0176a, - 0x2cbaba, 0x24920e, 0x40d3ae, 0xf01dbc, 0x24dbed, 0xac3613, 0x1449e0, - 0xc0bdd1, 0xe8508b, 0xf025b7, 0xc8ba94, 0xec1f72, 0x9852b1, 0x1489fd, - 0xccfe3c, 0x789ed0, 0xe440e2, 0x1caf05, 0xe492fb, 0x0073e0, 0xbc4486, - 0x380b40, 0x002490, 0x0023d7, 0xfca13e, 0xa00798, 0x945103, 0xc819f7, - 0x2c4401, 0x28e31f, 0x0c1daf, 0x14f65a, 0x742344, 0xf0b429, 0xec51bc, - 0xf079e8, 0x887598, 0xd0b128, 0xd00401, 0xf06d78, 0x10683f, 0x74a722, - 0x58a2b5, 0x64899a, 0x88074b, 0x64bc0c, 0xa039f7, 0x041b6d, 0x001f6b, - 0x30b4b8, 0x503cea, 0x0c9838, 0x54fcf0, 0x08aed6, 0xa816d0, 0x88bd45, - 0x544e90, 0xd03311, 0x70e72c, 0xc0cecd, 0x98e0d9, 0xe0accb, 0x78d75f, - 0x2078f0, 0x985aeb, 0xa45e60, 0x006d52, 0x5cadcf, 0xb8e856, 0x90b21f, - 0xa8bbcf, 0xc8b5b7, 0x18af8f, 0xf4f951, 0xf0c1f1, 0xec3586, 0x88cb87, - 0xac3c0b, 0xcc785f, 0xe88d28, 0x3ce072, 0xf41ba1, 0xa85b78, 0x9cf387, - 0x34a395, 0x48437c, 0xac87a3, 0x00f76f, 0xc0f2fb, 0x1caba7, 0x60facd, - 0x680927, 0x78a3e4, 0x68a86d, 0xb817c2, 0xb88d12, 0x5c8d4e, 0xe06678, - 0x1c1ac0, 0xc8f650, 0x60d9c7, 0x44fb42, 0x64a3cb, 0xd8d1cb, 0x542696, - 0x14109f, 0xbc52b7, 0xe0c97a, 0x5c95ae, 0x8cfaba, 0x0cbc9f, 0xbc4cc4, - 0x0c1539, 0x908d6c, 0x80006e, 0xb418d1, 0x1499e2, 0xe0c767, 0xa860b6, - 0x24f094, 0x90b0ed, 0xc4b301, 0xe05f45, 0x483b38, 0x88e87f, 0xb853ac, - 0x2c3361, 0x784f43, 0x404d7f, 0xbc926b, 0x0452f3, 0x241eeb, 0xf431c3, - 0x64a5c3, 0x606944, 0xe498d6, 0x0cd746, 0x440010, 0x1c9e46, 0x7c04d0, - 0xbc9fef, 0x8866a5, 0x70f087, 0x886b6e, 0x4c74bf, 0x844167, 0xb4f61c, - 0xe49adc, 0xb8c111, 0x3408bc, 0xd0817a, 0xc4618b, 0x68ab1e, 0x2c61f6, - 0x0026bb, 0x00254b, 0x002436, 0x002332, 0x002312, 0x0019e3, 0x001451, - 0x000a27, 0x003065, 0x0050e4, 0xd023db, 0xe0b9ba, 0x3451c9, 0x8c5877, - 0x9803d8, 0xc82a14, 0x88c663, 0x8c7b9d, 0x5855ca, 0xcc08e0, 0xe80688, + 0xecf342, 0x5092b9, 0xb4bff6, 0xc8d7b0, 0x982d68, 0xd80831, 0xdc5583, + 0x2c54cf, 0x001fe3, 0x0026e2, 0x001e75, 0x6cd68a, 0x2021a5, 0x0c4885, + 0xdc0b34, 0xac0d1b, 0x60e3ac, 0xf895c7, 0xc4438f, 0xa816b2, 0xe892a4, + 0x700514, 0x88c9d0, 0x2c598a, 0xec8350, 0x4cdd31, 0x705aac, 0xfc643a, + 0xd4e6b7, 0x2802d8, 0x48605f, 0xf0766f, 0x40cbc0, 0x4098ad, 0x6c4d73, + 0xc48466, 0xb8634d, 0x503237, 0xd4619d, 0xb0481a, 0x989e63, 0xdca904, + 0x48a195, 0x6cab31, 0x7c5049, 0xe42b34, 0x1c36bb, 0x3c2eff, 0x6c96cf, + 0x3035ad, 0xa8be27, 0x70a2b3, 0x4c57ca, 0x68fb7e, 0x90c1c6, 0xa4f1e8, + 0xac61ea, 0x38b54d, 0x00cdfe, 0x18af61, 0xcc4463, 0x34159e, 0x58b035, + 0xf0b479, 0x109add, 0x40a6d9, 0x7cf05f, 0xa4b197, 0x0c74c2, 0x403004, + 0x4860bc, 0xd02b20, 0x9ce33f, 0xf0989d, 0xace4b5, 0x6c72e7, 0x60fec5, + 0x00a040, 0x000d93, 0xacbc32, 0x30d9d9, 0x6030d4, 0x94bf2d, 0xc49880, + 0xe0338e, 0x68fef7, 0xbce143, 0x645aed, 0xc0b658, 0x881908, 0xfc2a9c, + 0x44d884, 0xec852f, 0x286aba, 0x705681, 0x7cd1c3, 0xf0dce2, 0xb065bd, + 0xa82066, 0xbc6778, 0x68967b, 0x848506, 0x54ae27, 0x6476ba, 0x84b153, + 0x783a84, 0x2cbe08, 0x24e314, 0x68d93c, 0x2cf0ee, 0x84788b, 0x6c94f8, + 0x703eac, 0xb4f0ab, 0x10ddb1, 0x04f7e4, 0x34c059, 0xf0d1a9, 0xbc3baf, + 0x786c1c, 0x041552, 0x38484c, 0x701124, 0xc86f1d, 0x685b35, 0x380f4a, + 0x3010e4, 0x04db56, 0x881fa1, 0x04e536, 0xf82793, 0xacfdec, 0xd0e140, + 0x8c7c92, 0x7831c1, 0xf437b7, 0x50ead6, 0x28e02c, 0x60c547, 0x7c11be, + 0x003ee1, 0xc01ada, 0x34363b, 0xc81ee7, 0x9cfc01, 0xccc760, 0x087402, + 0x285aeb, 0x28f076, 0x70700d, 0x9cf48e, 0xfcd848, 0x001cb3, 0x64b9e8, + 0x108ee0, 0x68e7c2, 0x3c576c, 0x0ce0dc, 0x702ad5, 0x889f6f, 0x1c427d, + 0x5029f5, 0x4c569d, 0x14c213, 0x38539c, 0x58e6ba, 0xb831b5, 0x90633b, + 0x782327, 0xf8a45f, 0x8cbebe, 0x640980, 0x98fae3, 0x185936, 0x9c99a0, + 0xc40bcb, 0xecd09f, 0xf4f5db, 0xe446da, 0x18f0e4, 0x9c2ea1, 0x50a009, + 0x20a60c, 0xf8e94e, 0xf40616, 0xbcb863, 0x188796, 0x002376, 0x84100d, + 0x04c23e, 0x5c5188, 0xe89120, 0x9c6c15, 0x4886e8, 0x2c2997, 0x102f6b, + 0x00eebd, 0x281878, 0x6045bd, 0x7ced8d, 0xe85b5b, 0x000d3a, 0xe09861, + 0xf4f1e1, 0x60beb5, 0xb4e1c4, 0x70aab2, 0x0026ff, 0x406f2a, 0x002557, + 0xf05a09, 0x503275, 0x28cc01, 0xb46293, 0x04fe31, 0x845181, 0xd831cf, + 0xf8d0bd, 0xfcc734, 0xe4b021, 0xb0ec71, 0x3cbbfd, 0x2cae2b, 0xc488e5, + 0x7c9122, 0xe8b4c8, 0x18895b, 0xe0db10, 0xe09971, 0x6077e2, 0x680571, + 0x6c2f2c, 0x300d43, 0x6c2779, 0x607edd, 0x9c2a83, 0xe45d75, 0xe4faed, + 0xc83f26, 0x54f201, 0xa06090, 0xac3743, 0x141f78, 0x006f64, 0xdc6672, + 0x001e7d, 0x3c6200, 0x0024e9, 0x002399, 0xe4e0c5, 0xe8039a, 0xc4731e, + 0x8c7712, 0x2013e0, 0x0007ab, 0x0021d2, 0xbc4760, 0xd0176a, 0x2cbaba, + 0x24920e, 0x40d3ae, 0xf01dbc, 0x24dbed, 0xac3613, 0x1449e0, 0xc0bdd1, + 0xe8508b, 0xf025b7, 0xc8ba94, 0xec1f72, 0x9852b1, 0x1489fd, 0xccfe3c, + 0x789ed0, 0xe440e2, 0x1caf05, 0xe492fb, 0x0073e0, 0xbc4486, 0x380b40, + 0x002490, 0x0023d7, 0xfca13e, 0xa00798, 0x945103, 0xc819f7, 0x2c4401, + 0xec51bc, 0xf079e8, 0x887598, 0xd0b128, 0xd00401, 0xf06d78, 0x10683f, + 0x74a722, 0x58a2b5, 0x64899a, 0x88074b, 0x64bc0c, 0xa039f7, 0x041b6d, + 0x001f6b, 0x30b4b8, 0x503cea, 0x54fcf0, 0x08aed6, 0xa816d0, 0x88bd45, 0x641cb0, 0x3cdcbc, 0xf47190, 0x587a6a, 0xe4c483, 0x8cf5a3, 0x14568e, 0x8058f8, 0xf0d7aa, 0xc49ded, 0xb0aa36, 0x2c5bb8, 0x1c48ce, 0x24f5aa, 0xf877b8, 0x682737, 0x5056bf, 0x9097f3, 0x58c5cb, 0xacafb9, 0x30074d, 0x5c5181, 0x389af6, 0xe0aa96, 0x507705, 0x2c4053, 0x084acf, 0x1cddea, - 0x08152f, 0xd461da, 0xc8d083, 0x88e9fe, 0x88ae07, 0x5c0947, 0x38892c, - 0x40831d, 0x50bc96, 0x9ce65e, 0x90dd5d, 0x08f69c, 0x00092d, 0xf8db7f, - 0xe899c4, 0x24da9b, 0x1c56fe, 0xe4907e, 0x80c5e6, 0x800184, 0xf8cfc5, - 0xc808e9, 0x206274, 0x30d587, 0xc0eefb, 0x502e5c, 0x847a88, 0x0025ae, - 0x002538, 0x0022a1, 0x00125a, 0x9cd917, 0x9068c3, 0x408805, 0xf8f1b6, - 0x001ccc, 0x94ebcd, 0xa4e4b8, 0x389496, 0x0cb319, 0x08ee8b, 0xa89fba, - 0xfc1910, 0x083d88, 0x5c2e59, 0x646cb2, 0xf884f2, 0x14b484, 0x608f5c, - 0x4cbca5, 0x78595e, 0xb0d09c, 0x4ca56d, 0xa48431, 0xe4f8ef, 0x1432d1, - 0xe458e7, 0x8cbfa6, 0x7840e4, 0x9000db, 0x183a2d, 0x08373d, 0x50f520, - 0xa4ebd3, 0x28987b, 0xf40e22, 0x9c3aaf, 0x0821ef, 0xa0cbfd, 0x34145f, - 0x6c8fb5, 0xac5f3e, 0x509ea7, 0xdccf96, 0x6c2483, 0xc09727, 0xd85b2a, - 0xacc33a, 0x88797e, 0x00e091, 0x6cd032, 0xc041f6, 0x0017d5, 0x001247, - 0xe4121d, 0x684898, 0xf409d8, 0xb479a7, 0x002339, 0xd487d8, 0x184617, - 0x5001bb, 0x380a94, 0xd857ef, 0x1c66aa, 0x58c38b, 0x001ee2, 0x001c43, - 0x001d25, 0x3c5a37, 0x549b12, 0x3c8bfe, 0x00265d, 0xd4e8b2, 0x0808c2, - 0xb0c4e7, 0xd890e8, 0x34aa8b, 0x24c696, 0x181eb0, 0x20d390, 0x343111, - 0x34be00, 0x78521a, 0x7825ad, 0xf4d9fb, 0x0017c9, 0x00166b, 0x00166c, - 0xe47cf9, 0x002454, 0x20d5bf, 0x30cda7, 0xc87e75, 0x00233a, 0x60a4d0, - 0x2c0e3d, 0xd4970b, 0x64cc2e, 0xb0e235, 0x38a4ed, 0xf48b32, 0x7c787e, - 0xc0d3c0, 0x440444, 0xc09f05, 0xcc2d83, 0x38295a, 0x4c1a3d, 0xa81b5a, - 0xdc6dcd, 0x54fa3e, 0x0c8910, 0xfcf136, 0x981dfa, 0x84a466, 0x1867b0, - 0xccb11a, 0xb8bbaf, 0x60c5ad, 0x28395e, 0xc4ae12, 0xdc74a8, 0xc087eb, - 0x74f61c, 0x986f60, 0x4c189a, 0x3cf591, 0x602101, 0xa89675, 0x608e08, - 0x7c2edd, 0x3cf7a4, 0x342d0d, 0x94d029, 0x308454, 0x4c49e3, 0x087808, - 0xd03169, 0xbc5451, 0x00bf61, 0xf80cf3, 0x30766f, 0x8c3ae3, 0x78f882, - 0xb4f1da, 0x0021fb, 0xd013fd, 0xa8b86e, 0x04b167, 0xd86375, 0xdcbfe9, - 0x306a85, 0x2047da, 0x8035c1, 0xd02598, 0xa8667f, 0x7014a6, 0x10417f, - 0xac293a, 0x94e96a, 0x0c4de9, 0x907240, 0xa88808, 0xc8e0eb, 0x54e43a, - 0x28e14c, 0x848e0c, 0xb03495, 0xf0f61c, 0x0c3021, 0xd89695, 0x649abe, - 0x5cf5da, 0x20a2e4, 0xf02475, 0x24a074, 0x8863df, 0x609217, 0x34e2fd, - 0x0c3e9f, 0x6c709f, 0x6c4008, 0x5c97f3, 0x90fd61, 0x006171, 0x80e650, - 0xdc2b2a, 0xb844d9, 0xe0f5c6, 0x949426, 0xcc29f5, 0x58404e, 0xdc0c5c, - 0x2c200b, 0xdca4ca, 0x8c8fe9, 0x9810e8, 0xb49cdf, 0xa4e975, 0xc0a53e, - 0x9800c6, 0x787b8a, 0x3866f0, 0x20ee28, 0x08f4ab, 0x8c8590, 0xb48b19, - 0xe49a79, 0x28a02b, 0xb44bd2, 0x2cf0a2, 0xecadb8, 0x9801a7, 0x609ac1, - 0xf07960, 0x9c8ba0, 0x4c3275, 0xe4e4ab, 0xc8334b, 0x00f4b9, 0x0c771a, - 0x74e1b6, 0x64200c, 0xc0847a, 0x183451, 0xfc253f, 0x1040f3, 0x6cc26b, - 0x182032, 0x70dee2, 0x00c610, 0x101c0c, 0x7cfadf, 0x5cf938, 0x3871de, - 0xbc5436, 0x9c4fda, 0x1c5cf2, 0x60fb42, 0x002500, 0x00236c, 0x0021e9, - 0x001ff3, 0x001f5b, 0x001e52, 0x001d4f, 0x001124, 0xa8fad8, 0x5c969d, - 0xe48b7f, 0x84fcfe, 0x444c0c, 0x8c2daa, 0x6c3e6d, 0x189efc, 0xc09f42, - 0xb8f6b1, 0x406c8f, 0xa4d1d2, 0x040cce, 0xd89e3f, 0x28e7cf, 0xc8bcc8, - 0xd8a25e, 0x90840d, 0xf81edf, 0xb0ca68, 0x98ca33, 0x68ef43, 0xcc2db7, - 0xd4a33d, 0xe4e0a6, 0x70ef00, 0x80ad16, 0x641cae, 0x14205e, 0x5c1dd9, - 0x18f1d8, 0xf86fc1, 0xf099b6, 0xdcd3a2, 0x38e7d8, 0xd8b377, 0xb4cef6, - 0xd40b1a, 0x5882a8, 0xb4ae2b, 0x0c413e, 0xd0929e, 0x4480eb, 0xb84fd5, - 0xec59e7, 0x3059b7, 0x501ac5, 0x1cb094, 0xa0f450, 0x002248, 0xec8892, - 0xb07994, 0x141aa3, 0xccc3ea, 0x34bb26, 0x40786a, 0xf40b93, 0x68ed43, - 0x34bb1f, 0x489d24, 0x000f86, 0xacee9e, 0xc08997, 0x2827bf, 0xf05b7b, - 0x7cf90e, 0xac5a14, 0xb0c559, 0xbcd11f, 0xa0b4a5, 0x80656d, 0x48137e, - 0xe83a12, 0x9c0298, 0x6c8336, 0xb8c68e, 0x74458a, 0xa49a58, 0xb4ef39, - 0x14a364, 0x3ca10d, 0x206e9c, 0x183f47, 0x0c715d, 0x0c1420, 0xa80600, - 0x6cf373, 0x78c3e9, 0xc83870, 0x288335, 0x44783e, 0x202d07, 0x98398e, - 0x348a7b, 0xbc765e, 0x78009e, 0x68c44d, 0xf8e61a, 0x888322, 0x84b541, - 0x0015b9, 0x001df6, 0xece09b, 0x606bbd, 0x0000f0, 0x4844f7, 0x1c5a3e, - 0xf47b5e, 0x008701, 0xfc4203, 0x1c232c, 0xcc61e5, 0x404e36, 0x009ec8, - 0xacf7f3, 0x102ab3, 0x584498, 0xa086c6, 0x7c1dd9, 0x9893cc, 0x3ccd93, - 0xf06bca, 0x3423ba, 0xd022be, 0xd02544, 0xbc20a4, 0x14f42a, 0xbc851f, - 0xb85e7b, 0xc462ea, 0x0023d6, 0x002491, 0x001b98, 0x44f459, 0x34c3ac, - 0x94d771, 0x4c3c16, 0x9401c2, 0xb43a28, 0xd0c1b1, 0xf008f1, 0x78471d, - 0x3816d1, 0xd48890, 0x002566, 0x00265f, 0xacc1ee, 0x5cba37, 0x7802f8, - 0x3096fb, 0xf0ee10, 0xa43d78, 0xec01ee, 0xb83765, 0xc4576e, 0x90f1aa, - 0x78bdbc, 0xd47ae2, 0x84c0ef, 0x7c1c68, 0xd463c6, 0x508f4c, 0x7c6456, - 0x448f17, 0x04d6aa, 0x9ce063, 0xf06e0b, 0x5c865c, 0xf0b0e7, 0x209bcd, - 0xcc20e8, 0x04d13a, 0x0cf346, 0x003de8, 0x485929, 0x34fcef, 0x002483, - 0x001c62, 0x583f54, 0x40b0fa, 0xa8922c, 0x98d6f7, 0x505527, 0x0034da, - 0xa09169, 0x88365f, 0x9c8c6e, 0xbcffeb, 0x685acf, 0x48746e, 0x54724f, - 0x04f13e, 0x600308, 0x80ea96, 0x24a2e1, 0x90b931, 0x280b5c, 0xa8968a, - 0x9c04eb, 0x885395, 0x80929f, 0x98b8e3, 0xd8004d, 0x98fe94, 0x68644b, - 0xf099bf, 0xfce998, 0x48e9f1, 0x4c7c5f, 0x60f81d, 0x689c70, 0x2cb43a, - 0x042665, 0xf4f15a, 0x207d74, 0x4c8d79, 0xfcfc48, 0x38c986, 0x70ece4, - 0xd81d72, 0x94f6a3, 0x78fd94, 0x48d705, 0x7c6df8, 0x3cab8e, 0x787e61, - 0xd4f46f, 0xc88550, 0xac7f3e, 0xa4c361, 0x087045, 0x40331a, 0xdc3714, - 0x789f70, 0x64b0a6, 0x84fcac, 0x6c19c0, 0x20ab37, 0xc0d012, 0xd4dccd, - 0x484baa, 0xf80377, 0x14bd61, 0x78886d, 0xa85c2c, 0x00db70, 0xbcec5d, - 0xdc415f, 0x30636b, 0x0c5101, 0x086d41, 0x04d3cf, 0x203cae, 0x748d08, - 0xa03be3, 0x186590, 0x0010fa, 0x000502, 0xb8782e, 0xa4d18c, 0xcc25ef, - 0x68dbca, 0x044bed, 0x6c8dc1, 0x38cada, 0xf45c89, 0x581faa, 0x24ab81, - 0x70cd60, 0x7cc537, 0xc42c03, 0xd83062, 0x40d32d, 0x7c6d62, 0x286ab8, - 0x403cfc, 0xb8c75d, 0xe8040b, 0xe4ce8f, 0x3c0754, 0xa46706, 0x80b03d, - 0xc83c85, 0xa04ea7, 0x409c28, 0x08e689, 0x4cb199, 0x98d6bb, 0x3cd0f8, - 0x7cc3a1, 0x002608, 0x001ec2, 0x001b63, 0x0017f2, 0x0016cb, 0x000393, - 0x804971, 0x64e682, 0xb4f7a1, 0x785dc8, 0x48c796, 0x804e70, 0x3880df, - 0x1094bb, 0xf01898, 0x48a91c, 0xa056f3, 0x549963, 0x28ff3c, 0x902155, - 0x64a769, 0xbccfcc, 0xa4516f, 0x3c8375, 0x149a10, 0x0ce725, 0xc0335e, - 0x20a99b, 0x4c0bbe, 0x7c1e52, 0xdcb4c4, 0x001dd8, 0x0017fa, 0x0003ff, - 0xf8e079, 0x1430c6, 0xe0757d, 0x9cd35b, 0x60af6d, 0xb85a73, 0x103047, - 0x109266, 0xb047bf, 0x7c0bc6, 0x804e81, 0x244b81, 0x50a4c8, 0x8425db, - 0xd8c4e9, 0x50c8e5, 0x446d6c, 0x38d40b, 0x647791, 0x781fdb, 0x08fc88, - 0x30c7ae, 0x18227e, 0x00f46f, 0x9ce6e7, 0xe498d1, 0x5cca1a, 0x70288b, - 0x4849c7, 0x205ef7, 0x182666, 0xc06599, 0xcc07ab, 0xe84e84, 0x50fc9f, - 0xe432cb, 0x889b39, 0xbcb1f3, 0x38ece4, 0xccf9e8, 0xf0e77e, 0x5ce8eb, - 0xb8d9ce, 0x70f927, 0x301966, 0x28bab5, 0x103b59, 0x6cb7f4, 0x001ee1, - 0x0018af, 0xbc72b1, 0x78f7be, 0xf49f54, 0x00214c, 0x001632, 0xd0667b, - 0x001377, 0x50b7c3, 0x8018a7, 0x444e1a, 0xe8e5d6, 0x5492be, 0x101dc0, - 0x0021d1, 0x68dfdd, 0xc46ab7, 0xfc64ba, 0x2082c0, 0x3480b3, 0x7451ba, - 0x64b473, 0xcc2d8c, 0x949aa9, 0x20dbab, 0x5c9960, 0x948bc1, 0x4827ea, - 0x388c50, 0xa09347, 0xc8f230, 0x1c77f6, 0xe44790, 0xd4503f, 0x40163b, - 0x5c497d, 0xe47dbd, 0x503da1, 0x508569, 0x1077b1, 0x5cf6dc, 0x380195, - 0xbc1485, 0x88d50c, 0x947be7, 0x00ec0a, 0x54bd79, 0xdc44b6, 0x1007b6, - 0xc0174d, 0xa407b6, 0x149f3c, 0x88b4a6, 0x2c5491, 0x5c70a3, 0x10f96f, - 0xf01c13, 0x00aa70, 0xbcf5ac, 0xccfa00, 0xf8a9d0, 0x805a04, 0x5caf06, - 0xb81daa, 0x10f1f2, 0x0025e5, 0x0022a9, 0xc49a02, 0x344df7, 0xd41a3f, - 0xcc6ea4, 0xa46cf1, 0x0ca8a7, 0x54b802, 0x0469f8, 0xbc6c21, 0xc869cd, - 0x80d605, 0x587f57, 0xa4b805, 0x70480f, 0x18f643, 0x748114, 0x18ee69, - 0xf0dbe2, 0xb8098a, 0x549f13, 0x2c1f23, 0x507a55, 0x9c35eb, 0xa43135, - 0xd0034b, 0xa01828, 0xd0a637, 0xd04f7e, 0xd8bb2c, 0x80be05, 0xe0b52d, - 0x68ae20, 0xe8802e, 0x7c0191, 0x9c293f, 0x341298, 0x903c92, 0x24240e, - 0xa0999b, 0xe0f847, 0x442a60, 0x1093e9, 0xdc2b61, 0xb8ff61, 0x18e7f4, - 0x78ca39, 0x5c5948, 0x60334b, 0x9027e4, 0xd49a20, 0xb09fba, 0x8c006d, - 0xc06394, 0x843835, 0xe4c63d, 0x54eaa8, 0xa886dd, 0xaccf5c, 0xf0dbf8, - 0x98f0ab, 0xdc9b9c, 0x8c2937, 0xdc86d8, 0xa88e24, 0xd8cf9c, 0x04489a, - 0x3c15c2, 0x20c9d0, 0x74e2f5, 0x842999, 0x9c207b, 0x283737, 0x148fc6, - 0x28cfda, 0x145a05, 0xa0edcd, 0x1ce62b, 0x3090ab, 0x7073cb, 0xf0cba1, - 0x045453, 0x40b395, 0x008865, 0x30f7c5, 0x20768f, 0xc0ccf8, 0x80ed2c, - 0xe8b2ac, 0x8489ad, 0x8c8ef2, 0xf40f24, 0x84a134, 0x1c9148, 0x5cf7e6, - 0xa0d795, 0xcc088d, 0x00b362, 0xf86214, 0xb0702d, 0xd0c5f3, 0x60f445, - 0x5082d5, 0x9c84bf, 0x48bf6b, 0x245ba7, 0xbca920, 0xb019c6, 0x58e28f, - 0xac1f74, 0x080007, 0xe425e7, 0x28cfe9, 0x9060f1, 0x741bb2, 0x28ed6a, - 0x34ab37, 0x60a37d, 0x0056cd, 0x7081eb, 0x086698, 0x24f677, 0x7867d7, - 0x5433cb, 0xd0d2b0, 0xd88f76, 0x3c2ef9, 0xdc56e7, 0x347c25, 0xd4909c, - 0x041e64, 0x0026b0, 0x00264a, 0x0025bc, 0x0023df, 0x002241, 0x000a95, - 0x38e60a, 0x24181d, 0xf4c248, 0xa8515b, 0xc048e6, 0xd07714, 0x749eaf, - 0xb841a4, 0xf895ea, 0x50a67f, 0x647033, 0x846878}; + 0x08152f, 0xb8c111, 0x3408bc, 0x844167, 0xb4f61c, 0x68ab1e, 0x2c61f6, + 0xe49adc, 0xd0817a, 0xc4618b, 0x3451c9, 0xe0b9ba, 0xd023db, 0xb88d12, + 0xb817c2, 0x68a86d, 0x78a3e4, 0x680927, 0x60facd, 0x1caba7, 0x784f43, + 0x404d7f, 0x7c04d0, 0xbc9fef, 0x8866a5, 0x88e87f, 0xb853ac, 0x2c3361, + 0xa860b6, 0x24f094, 0x90b0ed, 0xc4b301, 0xe05f45, 0x483b38, 0xe0c767, + 0x1c9e46, 0x0cd746, 0x440010, 0xe498d6, 0x606944, 0x0452f3, 0x241eeb, + 0xf431c3, 0x64a5c3, 0xbc926b, 0x0050e4, 0x003065, 0x000a27, 0x001451, + 0x8c7b9d, 0x88c663, 0xc82a14, 0x9803d8, 0x8c5877, 0x0019e3, 0x002312, + 0x002332, 0x002436, 0x00254b, 0x0026bb, 0x70f087, 0x886b6e, 0x4c74bf, + 0xe80688, 0xcc08e0, 0x5855ca, 0x5c0947, 0x38892c, 0x40831d, 0x50bc96, + 0x985aeb, 0x2078f0, 0x78d75f, 0xe0accb, 0x98e0d9, 0xc0cecd, 0x70e72c, + 0xd03311, 0x5cadcf, 0x006d52, 0x48437c, 0x34a395, 0x9cf387, 0xa85b78, + 0x908d6c, 0x0c1539, 0xbc4cc4, 0x0cbc9f, 0xa45e60, 0x544e90, 0x9ce65e, + 0x90dd5d, 0x08f69c, 0xd461da, 0xc8d083, 0x88e9fe, 0x88ae07, 0x18af8f, + 0xc8b5b7, 0xa8bbcf, 0x90b21f, 0xb8e856, 0x1499e2, 0xb418d1, 0x80006e, + 0x60d9c7, 0xc8f650, 0x1c1ac0, 0xe06678, 0x5c8d4e, 0xc0f2fb, 0x00f76f, + 0xac87a3, 0x542696, 0xd8d1cb, 0x64a3cb, 0x44fb42, 0xf41ba1, 0x3ce072, + 0xe88d28, 0xcc785f, 0xac3c0b, 0x88cb87, 0xec3586, 0xf0c1f1, 0xf4f951, + 0x8cfaba, 0x5c95ae, 0xe0c97a, 0xbc52b7, 0x14109f, 0x00c3f4, 0x74eb80, + 0xa82bb9, 0x7c6b9c, 0x1cc3eb, 0xbca58b, 0x70fd46, 0xd07fa0, 0x9caa1b, + 0x18d717, 0xb4cb57, 0x74b587, 0xd81c79, 0x8cfe57, 0xc0a600, 0xa823fe, + 0xfcaab6, 0xc0bdc8, 0xa887b3, 0x742344, 0xd832e3, 0xe06267, 0x482ca0, + 0x1801f1, 0x70bbe9, 0xf0b429, 0x0c9838, 0x0c1daf, 0x28e31f, 0x14f65a, + 0xd4c94b, 0x703a51, 0xdc080f, 0xf82d7c, 0x9c648b, 0x14d00d, 0x00092d, + 0xf8db7f, 0xe899c4, 0x24da9b, 0x1c56fe, 0xe4907e, 0x80c5e6, 0x800184, + 0xf8cfc5, 0xc808e9, 0x206274, 0x30d587, 0xc0eefb, 0x502e5c, 0x847a88, + 0x0025ae, 0x002538, 0x0022a1, 0x00125a, 0x9cd917, 0x9068c3, 0x408805, + 0xf8f1b6, 0x001ccc, 0x94ebcd, 0xa4e4b8, 0x389496, 0x0cb319, 0x08ee8b, + 0xa89fba, 0xfc1910, 0x083d88, 0x5c2e59, 0x646cb2, 0xf884f2, 0x14b484, + 0x608f5c, 0x4cbca5, 0x78595e, 0xb0d09c, 0x4ca56d, 0xa48431, 0xe4f8ef, + 0x1432d1, 0xe458e7, 0x8cbfa6, 0x7840e4, 0x9000db, 0x183a2d, 0x08373d, + 0x50f520, 0xa4ebd3, 0x28987b, 0xf40e22, 0x9c3aaf, 0x0821ef, 0xa0cbfd, + 0x34145f, 0x6c8fb5, 0xac5f3e, 0x509ea7, 0xdccf96, 0x6c2483, 0xc09727, + 0xd85b2a, 0xacc33a, 0x88797e, 0x00e091, 0x6cd032, 0xc041f6, 0x0017d5, + 0x001247, 0xe4121d, 0x684898, 0xf409d8, 0xb479a7, 0x002339, 0xd487d8, + 0x184617, 0x5001bb, 0x380a94, 0xd857ef, 0x1c66aa, 0x58c38b, 0x001ee2, + 0x001c43, 0x001d25, 0x3c5a37, 0x549b12, 0x3c8bfe, 0x00265d, 0xd4e8b2, + 0x0808c2, 0xb0c4e7, 0xd890e8, 0x34aa8b, 0x24c696, 0x181eb0, 0x20d390, + 0x343111, 0x34be00, 0x78521a, 0x7825ad, 0xf4d9fb, 0x0017c9, 0x00166b, + 0x00166c, 0xe47cf9, 0x002454, 0x20d5bf, 0x30cda7, 0xc87e75, 0x00233a, + 0x60a4d0, 0x2c0e3d, 0x7c787e, 0xc0d3c0, 0x440444, 0xc09f05, 0xcc2d83, + 0x38295a, 0x4c1a3d, 0xa81b5a, 0xdc6dcd, 0x54fa3e, 0x0c8910, 0xfcf136, + 0x981dfa, 0x84a466, 0x1867b0, 0xccb11a, 0xb8bbaf, 0x60c5ad, 0x28395e, + 0xc4ae12, 0xdc74a8, 0xc087eb, 0x74f61c, 0x986f60, 0x4c189a, 0x3cf591, + 0x602101, 0xa89675, 0x608e08, 0x7c2edd, 0x3cf7a4, 0x342d0d, 0x94d029, + 0x308454, 0x087808, 0xd03169, 0xbc5451, 0x641cae, 0xa4e975, 0xc0a53e, + 0x9800c6, 0x787b8a, 0x3866f0, 0x20ee28, 0x08f4ab, 0x8c8590, 0x68ef43, + 0xcc2db7, 0xd4a33d, 0xe4e0a6, 0x70ef00, 0xb0ca68, 0x9810e8, 0xb49cdf, + 0xdca4ca, 0x8c8fe9, 0x98ca33, 0xfc253f, 0x183451, 0xc0847a, 0x64200c, + 0x74e1b6, 0x0c771a, 0x00f4b9, 0xc8334b, 0xb8f6b1, 0xc09f42, 0x189efc, + 0x6c3e6d, 0x8c2daa, 0xe4e4ab, 0x58404e, 0xdc0c5c, 0x2c200b, 0x609ac1, + 0xf07960, 0x9c8ba0, 0x28a02b, 0xb44bd2, 0x9c4fda, 0x1c5cf2, 0x3871de, + 0xbc5436, 0x5cf938, 0x4c3275, 0x2cf0a2, 0xecadb8, 0x9801a7, 0xb48b19, + 0xe49a79, 0x406c8f, 0x00c610, 0x70dee2, 0x182032, 0x6cc26b, 0x1040f3, + 0x001d4f, 0x001e52, 0x001f5b, 0x001ff3, 0x0021e9, 0x00236c, 0x002500, + 0x60fb42, 0xf81edf, 0x90840d, 0xd8a25e, 0xc8bcc8, 0x28e7cf, 0xd89e3f, + 0x040cce, 0xa4d1d2, 0x7cfadf, 0x101c0c, 0x001124, 0x6c709f, 0x0c3e9f, + 0x34e2fd, 0x609217, 0x8863df, 0x80e650, 0x006171, 0x90fd61, 0x5c97f3, + 0x6c4008, 0x24a074, 0xf02475, 0x20a2e4, 0x5cf5da, 0x649abe, 0x94e96a, + 0xac293a, 0x10417f, 0xb844d9, 0xdc2b2a, 0x14205e, 0x5c1dd9, 0x18f1d8, + 0xf86fc1, 0xf099b6, 0x907240, 0x0c4de9, 0xd89695, 0x0c3021, 0xf0f61c, + 0xb03495, 0x848e0c, 0x949426, 0xe0f5c6, 0x28e14c, 0x54e43a, 0xc8e0eb, + 0xa88808, 0x444c0c, 0x84fcfe, 0xe48b7f, 0x5c969d, 0xa8fad8, 0x7014a6, + 0xa8667f, 0xd02598, 0xcc29f5, 0xdcd3a2, 0x08c5e1, 0x00bf61, 0xf80cf3, + 0x30766f, 0x8c3ae3, 0x78f882, 0xb4f1da, 0x0021fb, 0xd013fd, 0xa8b86e, + 0xdcbfe9, 0x306a85, 0x4466fc, 0xfca621, 0x0ccb85, 0xa4d990, 0xd003df, + 0x24fce5, 0xe4b2fb, 0xf83880, 0x241b7a, 0x402619, 0xbcfed9, 0x808223, + 0x3830f9, 0x6c006b, 0x38a4ed, 0xb0e235, 0x64cc2e, 0xd86375, 0x80ad16, + 0x2047da, 0x8035c1, 0x9487e0, 0x7c03ab, 0xd4970b, 0xf48b32, 0x4c49e3, + 0x04b167, 0xd8ce3a, 0xb8c74a, 0xfc183c, 0xc0e862, 0xec2ce2, 0x64c753, + 0x38e7d8, 0xd8b377, 0xb4cef6, 0xd40b1a, 0x5882a8, 0xb4ae2b, 0x0c413e, + 0xd0929e, 0x4480eb, 0xb84fd5, 0xec59e7, 0x3059b7, 0x501ac5, 0x1cb094, + 0xa0f450, 0x002248, 0xec8892, 0xb07994, 0x141aa3, 0xccc3ea, 0x34bb26, + 0x40786a, 0xf40b93, 0x68ed43, 0x34bb1f, 0x489d24, 0x000f86, 0xacee9e, + 0xc08997, 0x2827bf, 0xf05b7b, 0x7cf90e, 0xac5a14, 0xb0c559, 0xbcd11f, + 0xa0b4a5, 0x80656d, 0x48137e, 0xe83a12, 0x9c0298, 0x6c8336, 0xb8c68e, + 0x74458a, 0xa49a58, 0xb4ef39, 0x14a364, 0x3ca10d, 0x206e9c, 0x183f47, + 0x0c715d, 0x0c1420, 0xa80600, 0x6cf373, 0x78c3e9, 0xc83870, 0x288335, + 0x44783e, 0x202d07, 0x98398e, 0x348a7b, 0xbc765e, 0x78009e, 0x68c44d, + 0xf8e61a, 0x888322, 0x84b541, 0x0015b9, 0x001df6, 0xece09b, 0x606bbd, + 0x0000f0, 0x4844f7, 0x1c5a3e, 0xf47b5e, 0x008701, 0xfc4203, 0x1c232c, + 0xcc61e5, 0x404e36, 0x9893cc, 0x3ccd93, 0xf06bca, 0x3423ba, 0xd022be, + 0xd02544, 0xbc20a4, 0x14f42a, 0xbc851f, 0xb85e7b, 0xc462ea, 0x0023d6, + 0x002491, 0x001b98, 0x44f459, 0x34c3ac, 0x94d771, 0x4c3c16, 0x9401c2, + 0xb43a28, 0xd0c1b1, 0xf008f1, 0x78471d, 0x3816d1, 0xd48890, 0x002566, + 0x00265f, 0x5cba37, 0x3096fb, 0xf0ee10, 0xa43d78, 0xec01ee, 0xb83765, + 0xc4576e, 0x90f1aa, 0x78bdbc, 0xd47ae2, 0x84c0ef, 0x7c1c68, 0xd463c6, + 0x7c6456, 0x448f17, 0x04d6aa, 0x9ce063, 0xf06e0b, 0x5c865c, 0x003de8, + 0x08e689, 0x7836cc, 0x08d46a, 0x485929, 0x34fcef, 0x002483, 0x001c62, + 0x583f54, 0x40b0fa, 0xa8922c, 0x98d6f7, 0x505527, 0x0034da, 0xa09169, + 0x88365f, 0x9c8c6e, 0xbcffeb, 0x685acf, 0xb4f7a1, 0x785dc8, 0x48c796, + 0x804e70, 0x3880df, 0xdc415f, 0x30636b, 0xf45c89, 0x68dbca, 0x044bed, + 0x6c8dc1, 0x38cada, 0xa4d18c, 0x186590, 0x64b0a6, 0x84fcac, 0x6c19c0, + 0x20ab37, 0x203cae, 0x748d08, 0xa03be3, 0x7c6d62, 0x40d32d, 0xd83062, + 0xc42c03, 0x7cc537, 0x70cd60, 0xc0d012, 0xd4dccd, 0x484baa, 0xf80377, + 0x14bd61, 0xcc25ef, 0xb8782e, 0x000502, 0x0010fa, 0x000393, 0x0016cb, + 0x409c28, 0x78886d, 0xa85c2c, 0x00db70, 0x0c5101, 0x086d41, 0x04d3cf, + 0xbcec5d, 0x80b03d, 0xc83c85, 0xa04ea7, 0x0017f2, 0x001b63, 0x001ec2, + 0x002608, 0xa4c361, 0xac7f3e, 0x280b5c, 0x90b931, 0x24a2e1, 0x80ea96, + 0x600308, 0x04f13e, 0x54724f, 0x48746e, 0xd4f46f, 0x787e61, 0x60f81d, + 0x4c7c5f, 0x48e9f1, 0xfce998, 0xf099bf, 0x68644b, 0x789f70, 0x24ab81, + 0x581faa, 0xa46706, 0x3c0754, 0xe4ce8f, 0xe8040b, 0xb8c75d, 0x403cfc, + 0x98fe94, 0xd8004d, 0x98b8e3, 0x80929f, 0x885395, 0x9c04eb, 0xa8968a, + 0xdc3714, 0x40331a, 0x94f6a3, 0xd81d72, 0x70ece4, 0x38c986, 0xfcfc48, + 0x4c8d79, 0x207d74, 0xf4f15a, 0x042665, 0x2cb43a, 0x689c70, 0x087045, + 0x3cab8e, 0x7c6df8, 0x48d705, 0x78fd94, 0xc88550, 0x286ab8, 0x7cc3a1, + 0x3cd0f8, 0x98d6bb, 0x4cb199, 0x64e682, 0x804971, 0xcc20e8, 0x209bcd, + 0xf0b0e7, 0xa056f3, 0x549963, 0x28ff3c, 0x1094bb, 0xf01898, 0x48a91c, + 0x58b10f, 0x304b07, 0x1496e5, 0x80ceb9, 0xcc2119, 0x0057c1, 0x14c697, + 0xfc039f, 0x9c0cdf, 0x007204, 0x90e17b, 0x18810e, 0x608c4a, 0xa4d931, + 0x6cc7ec, 0x647bce, 0x584498, 0xacc1ee, 0x7802f8, 0x508f4c, 0x04d13a, + 0x0cf346, 0x082525, 0xf460e2, 0xa45046, 0x009ec8, 0x7c1dd9, 0xa086c6, + 0x102ab3, 0xacf7f3, 0x601d91, 0x38f9d3, 0x44e66e, 0xe83617, 0x344262, + 0xc09ad0, 0x902155, 0x64a769, 0xbccfcc, 0xa4516f, 0x3c8375, 0x149a10, + 0x0ce725, 0xc0335e, 0x20a99b, 0x4c0bbe, 0x7c1e52, 0xdcb4c4, 0x7c6f06, + 0x001dd8, 0x0017fa, 0x000a75, 0x0003ff, 0xf8e079, 0x1430c6, 0xe0757d, + 0x9cd35b, 0x60af6d, 0xb85a73, 0x103047, 0x109266, 0xb047bf, 0x7c0bc6, + 0x804e81, 0x244b81, 0x50a4c8, 0x8425db, 0xd8c4e9, 0x50c8e5, 0x446d6c, + 0x38d40b, 0x647791, 0x781fdb, 0x08fc88, 0x30c7ae, 0x18227e, 0x00f46f, + 0x9ce6e7, 0xe498d1, 0x5cca1a, 0x70288b, 0x4849c7, 0x205ef7, 0x182666, + 0xc06599, 0xcc07ab, 0xe84e84, 0x50fc9f, 0xe432cb, 0x889b39, 0xbcb1f3, + 0x38ece4, 0xccf9e8, 0xf0e77e, 0x5ce8eb, 0xb8d9ce, 0x70f927, 0x301966, + 0x28bab5, 0x103b59, 0x6cb7f4, 0x001ee1, 0x0018af, 0xbc72b1, 0x78f7be, + 0xf49f54, 0x00214c, 0x001632, 0xd0667b, 0x001377, 0x50b7c3, 0x8018a7, + 0x444e1a, 0xe8e5d6, 0x5492be, 0x101dc0, 0x0021d1, 0xcc2d8c, 0x949aa9, + 0x20dbab, 0x5c9960, 0x88b4a6, 0x2c5491, 0x5c70a3, 0x10f96f, 0xf01c13, + 0x00aa70, 0xbcf5ac, 0xccfa00, 0xf8a9d0, 0x805a04, 0x5caf06, 0xb81daa, + 0x10f1f2, 0x0025e5, 0x0022a9, 0xc49a02, 0x344df7, 0xd41a3f, 0xcc6ea4, + 0xa46cf1, 0x0ca8a7, 0x54b802, 0x24181d, 0xf4c248, 0xa8515b, 0xc048e6, + 0xd07714, 0x2816a8, 0x84a134, 0x1c9148, 0xc0ccf8, 0x80ed2c, 0xe8b2ac, + 0x8489ad, 0x20768f, 0x28ed6a, 0x34ab37, 0x60a37d, 0x0056cd, 0xbca920, + 0x5082d5, 0x9c84bf, 0x00b362, 0xf86214, 0xb0702d, 0xd0c5f3, 0x0023df, + 0x0025bc, 0x00264a, 0x0026b0, 0x041e64, 0xd49a20, 0x9027e4, 0x60334b, + 0x5c5948, 0x60f445, 0x5cf7e6, 0xa0d795, 0xcc088d, 0x8c8ef2, 0xf40f24, + 0x24f677, 0x7867d7, 0x5433cb, 0xd0d2b0, 0xd88f76, 0x3c2ef9, 0x7081eb, + 0x086698, 0x9060f1, 0x741bb2, 0x28cfe9, 0xe425e7, 0xb019c6, 0x58e28f, + 0xac1f74, 0x48bf6b, 0x245ba7, 0xdc56e7, 0x347c25, 0xd4909c, 0x080007, + 0x000a95, 0x002241, 0x18ee69, 0x748114, 0x18f643, 0xd0a637, 0xa01828, + 0xd0034b, 0xa43135, 0x9c35eb, 0x507a55, 0xa0999b, 0x24240e, 0x903c92, + 0xa88e24, 0xe8802e, 0x68ae20, 0xe0b52d, 0x80be05, 0xd8bb2c, 0xd04f7e, + 0x2c1f23, 0x549f13, 0xb8098a, 0xf0dbe2, 0x8c2937, 0xdc9b9c, 0x98f0ab, + 0xf0dbf8, 0xaccf5c, 0x3c15c2, 0x04489a, 0xd8cf9c, 0xa886dd, 0x54eaa8, + 0xe4c63d, 0x843835, 0xc06394, 0x8c006d, 0xb09fba, 0xdc86d8, 0x78ca39, + 0x18e7f4, 0xb8ff61, 0xdc2b61, 0x1093e9, 0x442a60, 0xe0f847, 0x145a05, + 0x28cfda, 0x148fc6, 0x283737, 0x045453, 0xf0cba1, 0x30f7c5, 0x008865, + 0x40b395, 0x3090ab, 0x1ce62b, 0xa0edcd, 0x842999, 0x74e2f5, 0x20c9d0, + 0x7073cb, 0x9c207b, 0x341298, 0x9c293f, 0x7c0191, 0x70480f, 0xa4b805, + 0x587f57, 0x80d605, 0xc869cd, 0xbc6c21, 0x0469f8, 0x749eaf, 0xb841a4, + 0xf895ea, 0x50a67f, 0x647033, 0x846878, 0x948bc1, 0x4827ea, 0x388c50, + 0xa09347, 0xc8f230, 0x1c77f6, 0xe44790, 0xd4503f, 0x40163b, 0x5c497d, + 0xe47dbd, 0x503da1, 0x508569, 0x1077b1, 0x5cf6dc, 0x380195, 0xbc1485, + 0x88d50c, 0x947be7, 0x54bd79, 0xdc44b6, 0x1007b6, 0xc0174d, 0xa407b6, + 0x149f3c, 0xd868c3, 0xc493d9, 0x00b5d0, 0x8c83e1, 0xfcb6d8, 0x6ce85c, + 0x007c2d, 0xf47def, 0x7c8bb5, 0xdcf756, 0x68dfdd, 0x64b473, 0x7451ba, + 0x3480b3, 0x2082c0, 0xfc64ba, 0xc46ab7, 0x00ec0a, 0x38e60a, 0x04e598, + 0x2ca9f0, 0x586b14, 0x94b01f, 0x94f6d6, 0x40bc60}; diff --git a/src/wifiscan.cpp b/src/wifiscan.cpp index ed3a84ee..55c690ff 100644 --- a/src/wifiscan.cpp +++ b/src/wifiscan.cpp @@ -43,28 +43,17 @@ void wifi_sniffer_init(void) { ESP_ERROR_CHECK(esp_wifi_set_promiscuous(true)); // now switch on monitor mode } -// Wifi channel rotation task -void wifi_channel_loop(void *pvParameters) { - - configASSERT(((uint32_t)pvParameters) == 1); // FreeRTOS check - - while (1) { - - if (ChannelTimerIRQ) { +// Wifi channel rotation +void switchWifiChannel(uint8_t &ch) { portENTER_CRITICAL(&timerMux); ChannelTimerIRQ = 0; portEXIT_CRITICAL(&timerMux); // rotates variable channel 1..WIFI_CHANNEL_MAX - channel = (channel % WIFI_CHANNEL_MAX) + 1; - esp_wifi_set_channel(channel, WIFI_SECOND_CHAN_NONE); - ESP_LOGD(TAG, "Wifi set channel %d", channel); - - vTaskDelay(2 / portTICK_PERIOD_MS); // reset watchdog + ch = (ch % WIFI_CHANNEL_MAX) + 1; + esp_wifi_set_channel(ch, WIFI_SECOND_CHAN_NONE); + ESP_LOGD(TAG, "Wifi set channel %d", &ch); } - } // end of infinite wifi channel rotation loop -} - // IRQ handler void IRAM_ATTR ChannelSwitchIRQ() { portENTER_CRITICAL(&timerMux); diff --git a/src/wifiscan.h b/src/wifiscan.h index afd5700e..5e8aae9a 100644 --- a/src/wifiscan.h +++ b/src/wifiscan.h @@ -28,6 +28,6 @@ typedef struct { void wifi_sniffer_init(void); void wifi_sniffer_packet_handler(void *buff, wifi_promiscuous_pkt_type_t type); void ChannelSwitchIRQ(void); -void wifi_channel_loop(void *pvParameters); +void switchWifiChannel(uint8_t &ch); #endif \ No newline at end of file