#include #include #include #include "hal.h" #include "driver/gpio.h" #include "driver/uart.h" #include "esp_vfs_dev.h" #include "driver/spi_master.h" #include "driver/i2c.h" #include "driver/adc.h" #include "esp_adc_cal.h" #if ESP_IDF_VERSION_MINOR>=3 #include "soc/adc_channel.h" // v4.3 #endif #include "esp_system.h" #include "esp_freertos_hooks.h" #if defined(WITH_BT_SPP) || defined(WITH_BLE_SPP) #include "bt.h" #endif #ifdef WITH_LORAWAN #include "lorawan.h" #endif #ifdef WITH_SLEEP #include "esp_sleep.h" #endif #include "nvs.h" #include "nvs_flash.h" #ifdef WITH_SPIFFS #include "esp_vfs_fat.h" #include "esp_spiffs.h" #endif #ifdef WITH_SD #include "esp_vfs_fat.h" #include "driver/sdmmc_host.h" #include "driver/spi_common.h" #include "driver/sdspi_host.h" #include "sdmmc_cmd.h" #endif #ifdef WITH_AP #include "ap.h" #endif #ifdef WITH_STRATUX #include "stratux.h" #endif #ifdef WITH_BEEPER #include "driver/ledc.h" #include "fifo.h" #endif #ifdef WITH_SOUND #include "intmath.h" #include "driver/i2s.h" #endif #ifdef WITH_OLED #include "ssd1306.h" #include "font8x8_basic.h" #endif #ifdef WITH_U8G2_OLED #include "u8g2.h" #endif #ifdef WITH_TFT_LCD extern "C" { #include "tftspi.h" #include "tft.h" } #endif #if defined(WITH_ST7789) || defined(WITH_ILI9341) #include "st7789.h" #endif #ifdef WITH_AXP #include "axp192.h" #endif #ifdef WITH_BQ #include "bq24295.h" #endif uint8_t PowerMode = 2; // 0=sleep/minimal power, 1=comprimize, 2=full power // ====================================================================================================== /* The HELTEC AUtomation board WiFi LoRa 32 with sx1278 (RFM95) 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 T-Beam board pinout and docs: http://tinymicros.com/wiki/TTGO_T-Beam HPD13A = RF chip ? 23 = RST (?) 5 = SCK 18 = NSS = CS 19 = MISO 27 = MOSI 26 = IO0 = IRQ 24AA32A = 32K I2C EEPROM => GPS I2C GPS 12 = GPIO12 = RXD1 15 = GPIO15 = TXD1 PSRM32 = SDIO ? 16 = CS 21 = GPIO21 = green LED */ /* https://randomnerdtutorials.com/esp32-pinout-reference-gpios/ GPIO HELTEC TTGO JACEK M5_JACEK T-Beam T-Beamv10 FollowMe OGN_AKR Restrictions 0 Button Button . LCD/DC LCD/DC . Can lock the boot, better not pull it down 1 CONS/TxD CONS/TxD CONS/TxD CONS/TxD CONS/TxD CONS/TxD CONS/TxD Console/Program 2 SD/MISO . LCD/MOSI LCD/MOSI LED/DBG LED/DBG Bootstrap: LOW to enter UART download mode 3 CONS/RxD CONS/RxD CONS/RxD CONS/RxD CONS/RxD CONS/RxD CONS/RxD Console/Program 4 OLED/SDA OLED/SDA ADC/CS LCD/BCKL LCD/BCKL PERF/RST RF_RST 5 RF/SCK RF/SCK RF/SCK GPS/ANT RF/SCK RF/SCK RF/CS RF/CS PWM at boot 6 SD/CLK SD/CLK SD/CLK SPI flash 7 SD/DATA0 SD/DATA0 SPI flash 8 SD/DATA1 SD/DATA1 SPI flash 9 SD/DATA2 SD/DATA2 SPI flash 10 SD/DATA3 SD/DATA3 SPI flash 11 SD/CMD SD/CMD SD/CMD SPI flash 12 GPS/RxD GPS/RxD SD/CS GPS/RxD GPS/TxD SD/MISO SD/MISO HSPI/MISO JTAG/TDI Bootstrap: select output voltage to power the flash chip 13 GPS/Ena GPS/Ena SD/SCK LCD/SCL LCD/CLK LCD/CLK SD/MOSI SD/MOSI HSPI/MOSI JTAG/TCK 14 RF/RST RF/RST Beeper ? LED/PCB . SD/CLK SD/SCK HSPI/CLK JTAG/TMS PWM at boot 15 OLED/SCL OLED/SCL SD/MOSI GPS/TxD . HSPI/CS0 SD/CS JTAG/TDO PWM at boot 16 OLED/RST OLED/RST RF/IRQ GPS/Tx RAM/CS GPS/TX GPS/TX U2_RXD 17 Beeper Beeper RF/RST GPS/Rx Beeper GPS/RX GPS/RX U2_TXD 18 RF/CS RF/CS RF/MISO RF/CS RF/SCK RF/CS RF/SCK VSPI/CLK 19 RF/MISO RF/MISO RF/MOSI RF/MISO RF/MISO RF/MISO RF/MISO RF/MISO VSPI/MISO 20 not listed 21 LED? RF/CS I2C/SCL I2C/SDA I2C/SDA I2C/SDA I2C/SDA VSPI/QUADHP 22 . PWR/ON I2C/SDA I2C/CLK I2C/SCL I2C/SCL VSPI/QUADWP 23 . PWR/LDO RF/RST RF/MOSI RF/RST RF/MOSI RF/MOSI VSPI/MOSI 24 not listed 25 LED Speaker . Speaker Speaker Speaker TT/RX Speaker 26 RF/IRQ RF/IRQ SCL RF/IRQ RF/IRQ RF/IRQ PWR/Good EncoderA 27 RF/MOSI RF/MOSI SDA RF/MOSI RF/MOSI TT/TX EncoderB 28 not listed 29 not listed 30 not listed 31 not listed 32 . . GPS/TxD ? . TT/RST GPS/PPS XTAL 33 . . OLED/RST ? . GPS/EN RF/IRQ XTAL 34 GPS/PPS GPS/PPS GPS/RxD KNOB/Sense GPS/TxD GPS/PPS Button 35 GPS/TxD GPS/TxD GPS/PPS BAT/Sense AXP/IRQ RF/IRQ Vbat/Sense 36 . . BAT/Sense BAT/Ext. . Vbat/Sense LED/TX 37 . . GPS/PPS 38 . . Button Button 39 . . Button Button Button */ #ifdef WITH_TTGO #define PIN_LED_PCB GPIO_NUM_2 // status LED on the PCB #endif #if defined(WITH_HELTEC) || defined(WITH_HELTEC_V2) #define PIN_LED_PCB GPIO_NUM_25 // status LED on the PCB: 25, GPIO25 is DAC2 #endif #if defined(WITH_TBEAM) // || defined(WITH_TBEAM_V10) #define PIN_LED_PCB GPIO_NUM_14 // blue LED on the PCB: 14 // #define PIN_LED_PCB_INV #endif #ifdef WITH_FollowMe #define PIN_LED_PCB GPIO_NUM_2 // debug LED #define PIN_LED_TX GPIO_NUM_15 #ifdef WITH_BQ #define PIN_POWER_GOOD GPIO_NUM_26 #endif #endif #ifdef WITH_OGN_AKR #define PIN_LED_PCB GPIO_NUM_2 // debug LED #define PIN_LED_TX GPIO_NUM_36 // debug LED #endif // #define PIN_LED_TX GPIO_NUM_?? // #define PIN_LED_RX GPIO_NUM_?? #ifdef WITH_JACEK #define PIN_RFM_RST GPIO_NUM_17 // Reset #define PIN_RFM_IRQ GPIO_NUM_16 // packet done on receive or transmit #define PIN_RFM_SS GPIO_NUM_21 // SPI chip-select #define PIN_RFM_SCK GPIO_NUM_5 // SPI clock #define PIN_RFM_MISO GPIO_NUM_18 // SPI MISO #define PIN_RFM_MOSI GPIO_NUM_19 // SPI MOSI #endif // JACEK #ifdef WITH_M5_JACEK #define PIN_RFM_RST GPIO_NUM_13 // Reset #define PIN_RFM_IRQ GPIO_NUM_35 // Packet done on receive or transmit #define PIN_RFM_SS GPIO_NUM_12 // SPI chip-select #define PIN_RFM_SCK GPIO_NUM_18 // SPI clock (same as LCD) #define PIN_RFM_MISO GPIO_NUM_19 // SPI MISO (save as LCD) #define PIN_RFM_MOSI GPIO_NUM_23 // SPI MOSI (save as LCD) #endif // M5_JACEK #if defined(WITH_HELTEC) || defined(WITH_HELTEC_V2) || defined(WITH_TTGO) #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 #endif // HELTEC TTGO #if defined(WITH_TBEAM) || defined(WITH_TBEAM_V10) || defined(WITH_LORA32) #define PIN_RFM_RST GPIO_NUM_23 // Reset - not clear if T-Beam is using it, or maybe only the older version #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 #endif // TBEAM #ifdef WITH_TBEAM_V10 #ifdef WITH_SX1262 #define PIN_RFM_BUSY GPIO_NUM_32 // for the T-Beam with SX1262 (watch for conflict with the LCD) #endif #endif #ifdef WITH_FollowMe // #define PIN_RFM_RST GPIO_NUM_32 // Reset #define PIN_RFM_IRQ GPIO_NUM_35 // 39 // packet done on receive or transmit #define PIN_RFM_SS GPIO_NUM_5 // SPI chip-select #define PIN_RFM_SCK GPIO_NUM_18 // SPI clock #define PIN_RFM_MISO GPIO_NUM_19 // SPI MISO #define PIN_RFM_MOSI GPIO_NUM_23 // SPI MOSI #endif // FollowMe #ifdef WITH_OGN_AKR #define PIN_RFM_IRQ GPIO_NUM_33 // 39 // packet done on receive or transmit #define PIN_RFM_SS GPIO_NUM_5 // SPI chip-select #define PIN_RFM_SCK GPIO_NUM_18 // SPI clock #define PIN_RFM_MISO GPIO_NUM_19 // SPI MISO #define PIN_RFM_MOSI GPIO_NUM_23 // SPI MOSI #define PIN_RFM_RST GPIO_NUM_4 // RFM RESET #endif #ifdef WITH_CUBE_BOARD #define PIN_RFM_IRQ GPIO_NUM_34 // packet done on receive or transmit #define PIN_RFM_SS GPIO_NUM_15 // SPI chip-select #define PIN_RFM_SCK GPIO_NUM_14 // SPI clock #define PIN_RFM_MISO GPIO_NUM_12 // SPI MISO #define PIN_RFM_MOSI GPIO_NUM_13 // SPI MOSI // #define PIN_RFM_RST GPIO_NUM_4 // RFM RESET #endif #define RFM_SPI_HOST VSPI_HOST // or H or VSPI_HOST ? #define RFM_SPI_DMA 1 // DMA channel #define RFM_SPI_SPEED 4000000 // [Hz] 2MHz SPI clock rate for RF chip #ifdef WITH_ST7789 #ifdef WITH_TBEAM // old T-Beam #define LCD_PIN_MOSI GPIO_NUM_2 // SDA #define LCD_PIN_MISO GPIO_NUM_NC // MISO not connected #define LCD_PIN_CLK GPIO_NUM_13 // SCL #endif // TBEAM #ifdef WITH_TBEAM_V10 // new T-Beam #define LCD_PIN_MOSI GPIO_NUM_14 // 13 // SDA #define LCD_PIN_MISO GPIO_NUM_NC // MISO not connected #define LCD_PIN_CLK GPIO_NUM_13 // 2 // SCL // #define LCD_PIN_MOSI GPIO_NUM_2 // 13 // SDA // #define LCD_PIN_MISO GPIO_NUM_NC // MISO not connected // #define LCD_PIN_CLK GPIO_NUM_13 // 14 // SCL // #define LCD_PIN_RST GPIO_NUM_15 // NC // RST #endif // TBEAM v1.0 #define LCD_SPI_SPEED 10000000 // [Hz] #define LCD_SPI_HOST HSPI_HOST // VSPI_HOST or HSPI_HOST #define LCD_SPI_DMA 2 // DMA channel #define LCD_SPI_MODE 3 // for ST7789 with CS tied to LOW #endif #ifdef WITH_JACEK #define PIN_GPS_TXD GPIO_NUM_32 #define PIN_GPS_RXD GPIO_NUM_34 #define PIN_GPS_PPS GPIO_NUM_35 #endif // JACEK #ifdef WITH_M5_JACEK #define PIN_GPS_TXD GPIO_NUM_17 #define PIN_GPS_RXD GPIO_NUM_16 #define PIN_GPS_PPS GPIO_NUM_26 #endif // M5_JACEK #ifdef WITH_LORA32 #define PIN_GPS_TXD GPIO_NUM_12 #define PIN_GPS_RXD GPIO_NUM_35 #define PIN_GPS_PPS GPIO_NUM_34 #define PIN_GPS_ENA GPIO_NUM_13 #endif // LORA32 #ifdef WITH_TBEAM_V10 #define PIN_AXP_IRQ GPIO_NUM_35 #endif #if defined(WITH_HELTEC) || defined(WITH_TTGO) // VK2828U GN-801 MAVlink #define PIN_GPS_TXD GPIO_NUM_13 // green green green #define PIN_GPS_RXD GPIO_NUM_35 // blue yellow yellow #define PIN_GPS_PPS GPIO_NUM_34 // white blue // #define PIN_GPS_RXD GPIO_NUM_38 // for a new HELTEC // #define PIN_GPS_PPS GPIO_NUM_37 // for a new HELTEC // #define PIN_GPS_ENA GPIO_NUM_13 // yellow white #endif // HELTEC || TTGO #if defined(WITH_HELTEC_V2) // VK2828U GN-801 MAVlink #define PIN_GPS_TXD GPIO_NUM_13 // green green green #define PIN_GPS_RXD GPIO_NUM_39 // blue yellow yellow #define PIN_GPS_PPS GPIO_NUM_38 // white blue #endif // Note: I had a problem with GPS ENABLE on GPIO13, thus I tied the enable wire to 3.3V for the time being. #ifdef WITH_TBEAM #define PIN_GPS_TXD GPIO_NUM_15 #define PIN_GPS_RXD GPIO_NUM_12 #endif // TBEAM #ifdef WITH_TBEAM_V10 #define PIN_GPS_TXD GPIO_NUM_12 #define PIN_GPS_RXD GPIO_NUM_34 #define PIN_GPS_PPS GPIO_NUM_37 #endif // TBEAM v1.0 #ifdef WITH_FollowMe // L80 GPS with PPS, Enable and Reset #define PIN_GPS_TXD GPIO_NUM_17 #define PIN_GPS_RXD GPIO_NUM_16 #define PIN_GPS_PPS GPIO_NUM_34 // high active #define PIN_GPS_ENA GPIO_NUM_33 // Enable: high-active #define PIN_PERIPH_RST GPIO_NUM_4 // Reset: high-active #endif #ifdef WITH_OGN_AKR // L86-M33 GPS with PPS #define PIN_GPS_TXD GPIO_NUM_17 #define PIN_GPS_RXD GPIO_NUM_16 #define PIN_GPS_PPS GPIO_NUM_32 // high active #endif #ifdef WITH_CUBE_BOARD #define PIN_GPS_TXD GPIO_NUM_32 #define PIN_GPS_RXD GPIO_NUM_35 #endif #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 #ifdef WITH_FollowMe #define AERO_UART UART_NUM_2 // UART2 #define PIN_AERO_TXD GPIO_NUM_25 #define PIN_AERO_RXD GPIO_NUM_27 #endif uint8_t BARO_I2C = (uint8_t)I2C_BUS; #ifdef WITH_JACEK #define PIN_I2C_SCL GPIO_NUM_26 // SCL pin #define PIN_I2C_SDA GPIO_NUM_27 // SDA pin #endif // JACEK #if defined(WITH_M5_JACEK) || defined(WITH_OGN_AKR) || defined(WITH_CUBE_BOARD) #define PIN_I2C_SCL GPIO_NUM_22 // SCL pin #define PIN_I2C_SDA GPIO_NUM_21 // SDA pin #endif // M5_JACEK || WITH_OGN_AKR #if defined(WITH_HELTEC) || defined(WITH_HELTEC_V2) || defined(WITH_TTGO) #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: low-active #endif // HELTEC || TTGO #if defined(WITH_TBEAM) || defined(WITH_TBEAM_V10) || defined(WITH_LORA32) // T-Beam #define PIN_I2C_SCL GPIO_NUM_22 // SCL pin => this way the pin pattern fits the BMP280 module #define PIN_I2C_SDA GPIO_NUM_21 // SDA pin #define OLED_I2C_ADDR 0x3C // I2C address of the OLED display #endif // TBEAM #ifdef WITH_FollowMe // #define PIN_I2C_SCL GPIO_NUM_22 // SCL pin #define PIN_I2C_SDA GPIO_NUM_21 // SDA pin #define OLED_I2C_ADDR 0x3C // I2C address of the OLED display // #define PIN_OLED_RST GPIO_NUM_15 // OLED RESET: low-active #endif // #if defined(WITH_HELTEC) || defined(WITH_TTGO) // #define PIN_OLED_RST GPIO_NUM_16 // OLED RESET: low-active // #endif #ifdef WITH_LORA32 #define PIN_SD_CS GPIO_NUM_13 // SD card interface in SPI mode #define PIN_SD_SCK GPIO_NUM_14 #define PIN_SD_MISO GPIO_NUM_2 #define PIN_SD_MOSI GPIO_NUM_15 #define SD_SPI_DMA 2 #endif #ifdef WITH_JACEK #define PIN_OLED_RST GPIO_NUM_33 // OLED RESET: low-active #define OLED_I2C_ADDR 0x3C // I2C address of the OLED display #define PIN_POWER GPIO_NUM_22 // power to GPS, RF, ... #define PIN_POWER_LDO GPIO_NUM_23 // LOW=low power LDO, HIGH=higher power LDO #define PIN_SD_CS GPIO_NUM_12 // SD card interface in SPI mode #define PIN_SD_SCK GPIO_NUM_13 #define PIN_SD_MISO GPIO_NUM_2 #define PIN_SD_MOSI GPIO_NUM_15 #define SD_SPI_DMA 2 #define PIN_BEEPER GPIO_NUM_14 #endif // JACEK #if defined(WITH_TBEAM) || defined(WITH_TBEAM_V10) #define PIN_BEEPER GPIO_NUM_25 // same as DAC #endif // TBEAM #if defined(WITH_HELTEC) || defined(WITH_HELTEC_V2) || defined(WITH_TTGO) #define PIN_BEEPER GPIO_NUM_17 #endif // HELTEC || TTGO #ifdef WITH_OGN_AKR #define PIN_BEEPER GPIO_NUM_25 #endif #ifdef WITH_M5_JACEK #define PIN_GPS_ANT GPIO_NUM_5 // internal(H) or external(L) GPS antenna #define PIN_SD_CS GPIO_NUM_11 // SD card interface in SPI mode #define PIN_SD_SCK GPIO_NUM_6 #define PIN_SD_MISO GPIO_NUM_7 #define PIN_SD_MOSI GPIO_NUM_8 #define SD_SPI_DMA 2 #define PIN_BEEPER GPIO_NUM_25 // DAC #endif // M5_JACEK #if !defined(WITH_AXP) && !defined(WITH_BQ) && !defined(WITH_OLED) && !defined(WITH_U8G2_OLED) && !defined(WITH_BMP180) && !defined(WITH_BMP280) && !defined(WITH_BME280) #undef PIN_I2C_SCL #undef PIN_I2C_SDA #endif #if defined(WITH_FollowMe) || defined(WITH_OGN_AKR) #define PIN_SD_MISO GPIO_NUM_12 // SD card in simple SPI mode, using HSPI IOMUX pins #define PIN_SD_MOSI GPIO_NUM_13 #define PIN_SD_SCK GPIO_NUM_14 #define PIN_SD_CS GPIO_NUM_15 #define SD_SPI_DMA 2 #endif // FollowMe || WITH_OGN_AKR #ifdef WITH_M5_JACEK // the three buttons below the LCD #define PIN_BUTTON_L GPIO_NUM_37 // Left #define PIN_BUTTON GPIO_NUM_38 // Center #define PIN_BUTTON_R GPIO_NUM_39 // Right #endif #if defined(WITH_FollowMe) // || defined(WITH_TBEAM) || defined(WITH_TBEAM_V10) #define PIN_BUTTON GPIO_NUM_39 // or 38 ? #endif #if defined(WITH_TBEAM_V10) #define PIN_BUTTON GPIO_NUM_38 #endif #ifdef WITH_JACEK #define PIN_BUTTON GPIO_NUM_38 #endif #ifdef WITH_OGN_AKR #define PIN_BUTTON GPIO_NUM_34 #endif #if defined(WITH_TTGO) || defined(WITH_HELTEC) || defined(WITH_HELTEC_V2) #define PIN_BUTTON GPIO_NUM_0 #endif #ifndef PIN_BUTTON #define PIN_BUTTON GPIO_NUM_39 #endif // ====================================================================================================== FIFO KeyBuffer; // ====================================================================================================== // 48-bit unique ID of the chip uint64_t getUniqueID(void) { uint8_t MAC[6]; esp_efuse_mac_get_default(MAC); uint64_t ID=MAC[0]; for(int Idx=1; Idx<6; Idx++) { ID<<=8; ID|=MAC[Idx]; } return ID; } uint32_t getUniqueAddress(void) { return getUniqueID()&0x00FFFFFF; } /* uint64_t getUniqueID(void) { uint64_t ID=0; esp_err_t ret=esp_efuse_mac_get_default((uint8_t *)&ID); return ID; } uint32_t getUniqueAddress(void) { uint32_t ID = getUniqueID()>>24; ID &= 0x00FFFFFF; ID = (ID>>16) | (ID&0x00FF00) | (ID<<16); ID &= 0x00FFFFFF; return ID; } */ // ====================================================================================================== #ifdef WITH_MAVLINK uint8_t MAV_Seq=0; // sequence number for MAVlink message sent out #endif // ====================================================================================================== // system_get_time() - return s 32-bit time in microseconds since the system start // gettimeofday() // xthal_get_ccount() - gets Xtal or master clock counts ? // ====================================================================================================== FlashParameters Parameters; #ifdef WITH_LORAWAN LoRaWANnode WANdev; #endif //-------------------------------------------------------------------------------------------------------- // Power control #ifdef WITH_JACEK void POWER_Dir (void) { gpio_set_direction(PIN_POWER, GPIO_MODE_OUTPUT); } void POWER_On (void) { gpio_set_level(PIN_POWER, 0); } // void POWER_Off (void) { gpio_set_level(PIN_POWER, 1); } void POWER_LDO_Dir(void) { gpio_set_direction(PIN_POWER_LDO, GPIO_MODE_OUTPUT); } void POWER_LDO_On (void) { gpio_set_level(PIN_POWER_LDO, 1); } // void POWER_LDO_Off(void) { gpio_set_level(PIN_POWER_LDO, 0); } #endif #ifdef WITH_M5_JACEK void GPS_ANT_Dir (void) { gpio_set_direction(PIN_GPS_ANT, GPIO_MODE_OUTPUT); } void GPS_ANT_Sel (uint8_t Antenna=1) { gpio_set_level(PIN_GPS_ANT, Antenna); } // 1=internal, 0=external #endif #ifdef PIN_POWER_GOOD bool Power_isGood(void) { return gpio_get_level(PIN_POWER_GOOD); } #endif //-------------------------------------------------------------------------------------------------------- // Status LED on the PCB #ifdef PIN_LED_PCB void LED_PCB_Dir (void) { gpio_set_direction(PIN_LED_PCB, GPIO_MODE_OUTPUT); } #ifdef PIN_LED_PCB_INV void LED_PCB_On (void) { gpio_set_level(PIN_LED_PCB, 0); } void LED_PCB_Off (void) { gpio_set_level(PIN_LED_PCB, 1); } #else void LED_PCB_On (void) { gpio_set_level(PIN_LED_PCB, 1); } void LED_PCB_Off (void) { gpio_set_level(PIN_LED_PCB, 0); } #endif #else // if LED on the PCB is absent, just make dummy calls void LED_PCB_Dir (void) { } #ifdef WITH_AXP // but with the T-Beam v1.0 and AXP chip we have an LED to control void LED_PCB_On (void) { AXP.setLED_ON(); } void LED_PCB_Off (void) { AXP.setLED_OFF(); } #else void LED_PCB_On (void) { } void LED_PCB_Off (void) { } #endif #endif #ifdef WITH_LED_TX void LED_TX_Dir (void) { gpio_set_direction(PIN_LED_TX, GPIO_MODE_OUTPUT); } void LED_TX_On (void) { gpio_set_level(PIN_LED_TX, 0); } void LED_TX_Off (void) { gpio_set_level(PIN_LED_TX, 1); } #endif #ifdef PIN_BUTTON void Button_Dir (void) { gpio_set_direction(PIN_BUTTON, GPIO_MODE_INPUT); } bool Button_isPressed(void) { return !gpio_get_level(PIN_BUTTON); } #endif // ======================================================================================================== // Console UART SemaphoreHandle_t CONS_Mutex; void CONS_UART_Init(void) { setvbuf(stdin, NULL, _IONBF, 0); // Disable buffering on stdin esp_vfs_dev_uart_set_rx_line_endings(ESP_LINE_ENDINGS_CR); esp_vfs_dev_uart_set_tx_line_endings(ESP_LINE_ENDINGS_CRLF); const uart_config_t UARTconfig = { .baud_rate = DEFAULT_CONbaud, .data_bits = UART_DATA_8_BITS, .parity = UART_PARITY_DISABLE, .stop_bits = UART_STOP_BITS_1, .use_ref_tick = true }; uart_param_config(CONS_UART, &UARTconfig); uart_driver_install(CONS_UART, 1024, 0, 0, NULL, 0); esp_vfs_dev_uart_use_driver(CONS_UART); } /* bool CONS_InpReady(void) { struct timeval tv = { tv_sec:0, tv_usec:0} ; fd_set fds; FD_ZERO(&fds); FD_SET(STDIN_FILENO, &fds); select(STDIN_FILENO+1, &fds, NULL, NULL, &tv); return (FD_ISSET(0, &fds)); } */ // 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) { uart_write_bytes (CONS_UART, &Byte, 1); // putchar(Byte); #if defined(WITH_BT_SPP) || defined(WITH_BLE_SPP) BT_SPP_Write(Byte); #endif #ifdef WITH_AP AP_Write(Byte); #endif #ifdef WITH_STRATUX Stratux_Write(Byte); #endif } // it appears the NL is translated into CR+NL int CONS_UART_Read (uint8_t &Byte) { int Ret=uart_read_bytes (CONS_UART, &Byte, 1, 0); if(Ret==1) return 1; // int Ret=getchar(); if(Ret>=0) { Byte=Ret; return 1; } #if defined(WITH_BT_SPP) || defined(WITH_BLE_SPP) Ret=BT_SPP_Read(Byte); if(Ret>0) { return 1; } #endif #ifdef WITH_STRATUX Ret=Stratux_Read(Byte); if(Ret>0) { return 1; } #endif return Ret; } // int CONS_UART_Free (void) { return UART2_Free(); } // int CONS_UART_Full (void) { return UART2_Full(); } void CONS_UART_SetBaudrate(int BaudRate) { uart_set_baudrate(CONS_UART, BaudRate); } //-------------------------------------------------------------------------------------------------------- // ADS-B UART #ifdef AERO_UART int AERO_UART_Read (uint8_t &Byte) { return uart_read_bytes (AERO_UART, &Byte, 1, 0); } // should be buffered and non-blocking void AERO_UART_Write (char Byte) { uart_write_bytes (AERO_UART, &Byte, 1); } // should be buffered and blocking void AERO_UART_SetBaudrate(int BaudRate) { uart_set_baudrate(AERO_UART, BaudRate); } #endif //-------------------------------------------------------------------------------------------------------- // GPS UART #ifdef 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_Flush (int MaxWait ) { uart_wait_tx_done(GPS_UART, MaxWait); } void GPS_UART_SetBaudrate(int BaudRate ) { uart_set_baudrate(GPS_UART, BaudRate); } #endif #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 #ifdef PIN_GPS_PPS bool GPS_PPS_isOn(void) { return gpio_get_level(PIN_GPS_PPS); } #endif //-------------------------------------------------------------------------------------------------------- // RF chip #ifdef PIN_RFM_RST // if reset pin declared for the RF chip void RFM_RESET_SetInput (void) { gpio_set_direction(PIN_RFM_RST, GPIO_MODE_INPUT); } void RFM_RESET_SetOutput (void) { gpio_set_direction(PIN_RFM_RST, GPIO_MODE_OUTPUT); } void RFM_RESET_SetLevel (uint8_t High) { gpio_set_level(PIN_RFM_RST, High&1); } #if defined(WITH_RFM95) || defined(WITH_SX1272) || defined(WITH_SX1262) // for RFM95 reset is low-active void RFM_RESET(uint8_t On) { if(On&1) { RFM_RESET_SetOutput(); RFM_RESET_SetLevel(0); } else { RFM_RESET_SetOutput(); RFM_RESET_SetLevel(1); } } #endif #ifdef WITH_RFM69 // for RFM69 reset is high-active void RFM_RESET(uint8_t On) { RFM_RESET_SetLevel(On); } #endif #else // if no reset pin declared for the RF chip, then make an empty call inline void RFM_RESET_SetOutput (void) { } void RFM_RESET(uint8_t On) { } #endif // PIN_RFM_RST void RFM_IRQ_SetInput(void) { gpio_set_direction(PIN_RFM_IRQ, GPIO_MODE_INPUT); } bool RFM_IRQ_isOn(void) { return gpio_get_level(PIN_RFM_IRQ); } #ifdef WITH_SX1262 void RFM_Busy_SetInput(void) { gpio_set_direction(PIN_RFM_BUSY, GPIO_MODE_INPUT); } bool RFM_Busy_isOn(void) { return gpio_get_level(PIN_RFM_BUSY); } #endif void RFM_Delay(int ms) { vTaskDelay(ms); } 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_polling_transmit(RFM_SPI, &Trans); } esp_err_t ret = spi_device_transmit(RFM_SPI, &Trans); } //-------------------------------------------------------------------------------------------------------- #ifdef WITH_TFT_LCD static void TFT_LCD_Init(void) { TFT_PinsInit(); spi_lobo_device_handle_t spi; spi_lobo_bus_config_t buscfg = { .mosi_io_num=PIN_NUM_MOSI, // set SPI MOSI pin #ifdef PIN_NUM_MISO .miso_io_num = PIN_NUM_MISO, // set SPI MISO pin #else .miso_io_num = -1, #endif .sclk_io_num = PIN_NUM_CLK, // set SPI CLK pin .quadwp_io_num = -1, .quadhd_io_num = -1, .max_transfer_sz = 6*1024 }; spi_lobo_device_interface_config_t devcfg = { .command_bits = 0, .address_bits = 0, .dummy_bits = 0, #ifdef PIN_NUM_CS .mode = 0, #else .mode = 3, #endif .duty_cycle_pos = 0, .cs_ena_pretrans = 0, .cs_ena_posttrans = 0, .clock_speed_hz = 8000000, // Initial clock out at 8 MHz .spics_io_num = -1, // we will use external CS pin #ifdef PIN_NUM_CS .spics_ext_io_num = PIN_NUM_CS, // external CS pin #else .spics_ext_io_num = -1, #endif .flags=LB_SPI_DEVICE_HALFDUPLEX, // ALWAYS SET to HALF DUPLEX MODE!! for display spi .pre_cb = 0, .post_cb = 0, .selected = 0, }; max_rdclock = 4000000; vTaskDelay(100); #ifdef WITH_M5_JACEK esp_err_t ret=spi_lobo_bus_add_device(TFT_VSPI_HOST, &buscfg, &devcfg, &spi); #endif #ifdef WITH_TBEAM esp_err_t ret=spi_lobo_bus_add_device(TFT_VSPI_HOST, &buscfg, &devcfg, &spi); #endif // assert(ret==ESP_OK); // printf("SPI: display device added to spi bus (%d)\r\n", SPI_BUS); disp_spi = spi; // ret = spi_lobo_device_select(spi, 1); // assert(ret==ESP_OK); // ret = spi_lobo_device_deselect(spi); // assert(ret==ESP_OK); TFT_display_init(); // max_rdclock = find_rd_speed(); font_rotate = 0; text_wrap = 0; font_transparent = 0; font_forceFixed = 0; gray_scale = 0; // disp_select(); // spi_lobo_device_select(spi, 1); TFT_invertDisplay(INVERT_ON); TFT_setGammaCurve(DEFAULT_GAMMA_CURVE); // spi_lobo_device_deselect(spi); // disp_deselect(); // TFT_setRotation(LANDSCAPE); TFT_setRotation(PORTRAIT); TFT_setFont(DEFAULT_FONT, NULL); TFT_resetclipwin(); TFT_fillScreen(TFT_GREEN); // TFT_fillScreen(TFT_WHITE); // TFT_fillScreen(TFT_BLACK); TFT_resetclipwin(); TFT_drawRect(20, 20, 200, 200, TFT_CYAN); TFT_print("OGN-Tracker", CENTER, CENTER); } #endif // WITH_TFT_LCD //-------------------------------------------------------------------------------------------------------- // BEEPER #ifdef WITH_BEEPER static ledc_timer_config_t LEDC_Timer = { speed_mode : LEDC_HIGH_SPEED_MODE, // timer mode duty_resolution : LEDC_TIMER_8_BIT, // resolution of PWM duty: 0..255 // { duty_resolution : LEDC_TIMER_8_BIT, } // resolution of PWM duty: 0..255 timer_num : LEDC_TIMER_0, // timer index freq_hz : 880 // frequency of PWM signal } ; static ledc_channel_config_t LEDC_Channel = { gpio_num : PIN_BEEPER, speed_mode : LEDC_HIGH_SPEED_MODE, channel : LEDC_CHANNEL_0, intr_type : LEDC_INTR_DISABLE, timer_sel : LEDC_TIMER_0, duty : 0, hpoint : 0 } ; esp_err_t Beep_Init(void) { ledc_timer_config(&LEDC_Timer); // Set configuration of timer0 for high speed channels ledc_channel_config(&LEDC_Channel); return ESP_OK; } void Beep(uint16_t Freq, uint8_t Duty, uint8_t DoubleAmpl) // [Hz, 1/256] play sound with given frequency and duty (=volume) { ledc_set_freq(LEDC_Timer.speed_mode, LEDC_Timer.timer_num, Freq); ledc_set_duty(LEDC_Channel.speed_mode, LEDC_Channel.channel, Duty); ledc_update_duty(LEDC_Channel.speed_mode, LEDC_Channel.channel); } // Frequencies for notes of the highest octave: C, C#, D, D#, E, F, F#, G, G#, A, A#, B // Freq[i] = 32*523.25*2**(i/12) i = 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, A, B static const uint16_t NoteFreq[12] = { 16744, 17740, 18795, 19912, 21096, 22351, 23680, 25088, 26579, 28160, 29834, 31608 } ; void Beep_Note(uint8_t Note) // Note = VVOONNNN: VV = Volume, OO=Octave, NNNN=Note { uint8_t Volume = Note>>6; // [0..3] uint8_t Octave = (Note>>4)&0x03; // [0..3] Note &= 0x0F; if(Note>=12) { Note-=12; Octave+=1; } // [0..11] [0..4] uint8_t Duty = 0; uint8_t DoubleAmpl=0; if(Volume) { Duty=0x10; Duty<<=Volume; } // Duty = 0x00, 0x20, 0x40, 0x80 if(Volume>2) { DoubleAmpl=1; } // DoubleAmpl = 0, 0, 1, 1 uint16_t Freq = NoteFreq[Note]; if(Octave) { Freq += 1<<(Octave-1); Freq >>= (4-Octave); } Beep(Freq, Duty, DoubleAmpl); } uint8_t Vario_Note=0x00; // 0x40; uint16_t Vario_Period=800; uint16_t Vario_Fill=50; static volatile uint16_t Vario_Time=0; static volatile uint8_t Play_Note=0; // Note being played static volatile uint8_t Play_Counter=0; // [ms] time counter static FIFO Play_FIFO; // queue of notes to play void Play(uint8_t Note, uint8_t Len) // [Note] [ms] put a new not to play in the queue { uint16_t Word = Note; Word<<=8; Word|=Len; Play_FIFO.Write(Word); } uint8_t Play_Busy(void) { return Play_Counter; } // is a note being played right now ? void Play_TimerCheck(uint8_t Ticks) // every ms serve the note playing { uint8_t Counter=Play_Counter; if(Counter) // if counter non-zero { if(Counter>Ticks) Counter-=Ticks; // decrement it else Counter=0; if(!Counter) Beep_Note(Play_Note=0x00); // if reached zero, stop playing the note } if(!Counter) // if counter reached zero { if(!Play_FIFO.isEmpty()) // check for notes in the queue { uint16_t Word=0; Play_FIFO.Read(Word); // get the next note Beep_Note(Play_Note=Word>>8); Counter=Word&0xFF; } // start playing it, load counter with the note duration } Play_Counter=Counter; uint16_t Time=Vario_Time; Time++; if(Time>=Vario_Period) Time=0; Vario_Time = Time; if(Counter==0) // when no notes are being played, make the vario sound { if(Time<=Vario_Fill) { if(Play_Note!=Vario_Note) Beep_Note(Play_Note=Vario_Note); } else { if(Play_Note!=0) Beep_Note(Play_Note=0x00); } } } #endif //-------------------------------------------------------------------------------------------------------- // SOUND #ifdef WITH_SOUND // extern const uint8_t Sound_737_Traffic_u8[] asm("_binary_737_Traffic_u8_start"); // extern const uint8_t Sound_737_Traffic_end[] asm("_binary_737_Traffic_u8_end"); // const int Sound_737_Traffic_size = Sound_737_Traffic_end-Sound_737_Traffic_u8; // extern const uint8_t Sound_737_Sink_Rate_u8[] asm("_binary_737_Sink_Rate_u8_start"); // extern const uint8_t Sound_737_Sink_Rate_end[] asm("_binary_737_Sink_Rate_u8_end"); // const int Sound_737_Sink_Rate_size = Sound_737_Sink_Rate_end-Sound_737_Sink_Rate_u8; // extern const uint8_t Sound_737_Whoop_Whoop_u8[] asm("_binary_737_Whoop_Whoop_u8_start"); // extern const uint8_t Sound_737_Whoop_Whoop_end[] asm("_binary_737_Whoop_Whoop_u8_end"); // const int Sound_737_Whoop_Whoop_size = Sound_737_Whoop_Whoop_end-Sound_737_Whoop_Whoop_u8; // const uint32_t Sound_SampleRate = 16000; const int Sound_BuffSize = 256; esp_err_t Sound_Init(void) { i2s_config_t i2s_config = { .mode = (i2s_mode_t)(I2S_MODE_MASTER | I2S_MODE_TX | I2S_MODE_DAC_BUILT_IN), .sample_rate = Sound_SampleRate, .bits_per_sample = I2S_BITS_PER_SAMPLE_16BIT, .channel_format = I2S_CHANNEL_FMT_ONLY_RIGHT, // I2S_CHANNEL_FMT_ALL_RIGHT or I2S_CHANNEL_FMT_ONLY_RIGHT ? .communication_format = I2S_COMM_FORMAT_I2S_MSB, .intr_alloc_flags = 0, .dma_buf_count = 4, .dma_buf_len = Sound_BuffSize, .use_apll = 1, .tx_desc_auto_clear = 1, .fixed_mclk = 0 }; i2s_driver_install(I2S_NUM_0, &i2s_config, 0, NULL); // install and start i2s driver // i2s_set_pin(I2S_NUM_0, 0); i2s_set_dac_mode(I2S_DAC_CHANNEL_RIGHT_EN); // init DAC pad // i2s_set_sample_rates(I2S_NUM_0, Sound_SampleRate); // i2s_set_clk(I2S_NUM_0, Sound_SampleRate, I2S_BITS_PER_SAMPLE_16BIT, I2S_CHANNEL_MONO); return ESP_OK; } static uint16_t Sound_Buffer[Sound_BuffSize]; int Sound_Play(const uint16_t *Data, int Len) { size_t Written=0; i2s_write(I2S_NUM_0, Data, Len<<1, &Written, portMAX_DELAY); return Written>>1; } void Sound_PlayU8(const uint8_t *Data, uint16_t Len) { int BuffIdx=0; for( ; Len--; ) { if(BuffIdx>=Sound_BuffSize) { Sound_Play(Sound_Buffer, Sound_BuffSize); BuffIdx=0; } uint16_t DAC = (*Data++); DAC<<=8; Sound_Buffer[BuffIdx++] = DAC; } if(BuffIdx) { Sound_Play(Sound_Buffer, BuffIdx); BuffIdx=0; } } void Sound_PlayS8(const int8_t *Data, uint16_t Len, uint8_t Vol) { if(Vol>8) Vol=8; int BuffIdx=0; for( ; Len--; ) { if(BuffIdx>=Sound_BuffSize) { Sound_Play(Sound_Buffer, Sound_BuffSize); BuffIdx=0; } int16_t DAC = (*Data++); if(DAC&0x80) DAC|=0xFF00; DAC<<=Vol; DAC+=0x8000; Sound_Buffer[BuffIdx++] = DAC; } if(BuffIdx) { Sound_Play(Sound_Buffer, BuffIdx); BuffIdx=0; } } void Sound_PlaySilence(uint16_t Len) { int BuffIdx=0; for( ; Len--; ) { if(BuffIdx>=Sound_BuffSize) { Sound_Play(Sound_Buffer, Sound_BuffSize); BuffIdx=0; } Sound_Buffer[BuffIdx++] = 0x8000; } if(BuffIdx) { Sound_Play(Sound_Buffer, BuffIdx); BuffIdx=0; } } static uint16_t Sound_Phase=0; void Sound_Beep(int16_t Freq, uint16_t Len, int16_t Ampl) { int BuffIdx=0; for( ; Len--; ) { if(BuffIdx>=Sound_BuffSize) { Sound_Play(Sound_Buffer, Sound_BuffSize); BuffIdx=0; } // if buffer full then play it int16_t Sig = IntSine(Sound_Phase)>>16; // 16-bit sine // int16_t Sig = Isin(Sound_Phase); // 13-bit, +/-4096 range sine Sound_Phase += Freq; // increment the Phase // Sig = ((int32_t)Sig*Ampl+0x1000)>>13; // multiply by requested Amplitude Sig>>=1; uint16_t DAC = 0x8000+Sig; // DAC = (DAC&0xFF00) | (DAC>>8); Sound_Buffer[BuffIdx++] = DAC; } if(BuffIdx) { Sound_Play(Sound_Buffer, BuffIdx); BuffIdx=0; } } #endif //-------------------------------------------------------------------------------------------------------- // OLED display #ifdef WITH_OLED #ifdef PIN_OLED_RST void OLED_RESET(bool Level) { gpio_set_level(PIN_OLED_RST, Level); } #endif esp_err_t OLED_Init(uint8_t DispIdx) { i2c_cmd_handle_t cmd = i2c_cmd_link_create(); i2c_master_start(cmd); i2c_master_write_byte(cmd, ((OLED_I2C_ADDR+DispIdx)<<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); // Turn ON the display 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_DisplayON(uint8_t ON, uint8_t DispIdx) { i2c_cmd_handle_t cmd = i2c_cmd_link_create(); i2c_master_start(cmd); i2c_master_write_byte(cmd, ((OLED_I2C_ADDR+DispIdx)<<1) | I2C_MASTER_WRITE, true); i2c_master_write_byte(cmd, OLED_CONTROL_BYTE_CMD_STREAM, true); i2c_master_write_byte(cmd, OLED_CMD_DISPLAY_OFF+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_DisplayINV(uint8_t INV, uint8_t DispIdx) { i2c_cmd_handle_t cmd = i2c_cmd_link_create(); i2c_master_start(cmd); i2c_master_write_byte(cmd, ((OLED_I2C_ADDR+DispIdx)<<1) | I2C_MASTER_WRITE, true); i2c_master_write_byte(cmd, OLED_CONTROL_BYTE_CMD_STREAM, true); i2c_master_write_byte(cmd, OLED_CMD_DISPLAY_NORMAL+INV, 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, uint8_t DispIdx) { i2c_cmd_handle_t cmd = i2c_cmd_link_create(); i2c_master_start(cmd); i2c_master_write_byte(cmd, ((OLED_I2C_ADDR+DispIdx)<<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, uint8_t DispIdx) { 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+DispIdx)<<1) | I2C_MASTER_WRITE, true); i2c_master_write_byte(cmd, OLED_CONTROL_BYTE_CMD_STREAM, true); i2c_master_write_byte(cmd, 0x00, true); // 0x0L => column address: Lower nibble i2c_master_write_byte(cmd, 0x10, true); // 0x1H => column address: Higher nibble i2c_master_write_byte(cmd, 0xB0 | Line, true); // 0xBP => Page address 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+DispIdx)<<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(uint8_t DispIdx) { esp_err_t espRc; for(uint8_t Line=0; Line<8; Line++) { espRc=OLED_PutLine(Line, 0, DispIdx); if(espRc!=ESP_OK) break; } return espRc; } #endif #ifdef WITH_U8G2_OLED static i2c_cmd_handle_t U8G2_Cmd; static uint8_t u8g2_esp32_i2c_byte_cb(u8x8_t *u8x8, uint8_t msg, uint8_t arg_int, void *arg_ptr) { #ifdef DEBUG_PRINT xSemaphoreTake(CONS_Mutex, portMAX_DELAY); Format_String(CONS_UART_Write, "u8g2_byte_cb("); CONS_UART_Write(','); Format_UnsDec(CONS_UART_Write, (uint16_t)msg); CONS_UART_Write(','); Format_UnsDec(CONS_UART_Write, (uint16_t)arg_int); Format_String(CONS_UART_Write, ") "); #endif switch(msg) { case U8X8_MSG_BYTE_SET_DC: break; case U8X8_MSG_BYTE_INIT: break; case U8X8_MSG_BYTE_START_TRANSFER: { U8G2_Cmd=i2c_cmd_link_create(); uint8_t Addr = u8x8_GetI2CAddress(u8x8); #ifdef DEBUG_PRINT Format_Hex(CONS_UART_Write, Addr); #endif i2c_master_start(U8G2_Cmd); i2c_master_write_byte(U8G2_Cmd, (Addr<<1) | I2C_MASTER_WRITE, true); break; } case U8X8_MSG_BYTE_SEND: // { i2c_master_write(U8G2_Cmd, (uint8_t *)arg_ptr, arg_int, true); break; } { uint8_t* Data = (uint8_t *)arg_ptr; for( int Idx=0; Idxcsd.capacity; } int SD_getSectorSize(void) { return SD_Card->csd.sector_size; } void SD_Unmount(void) { esp_vfs_fat_sdmmc_unmount(); SD_Card=0; } esp_err_t SD_Mount(void) { esp_err_t Ret = esp_vfs_fat_sdmmc_mount("/sdcard", &SD_Host, &SD_SlotConfig, &SD_MountConfig, &SD_Card); // ESP_OK => good, ESP_FAIL => failed to mound the file system, other => HW not working if(Ret!=ESP_OK) SD_Unmount(); return Ret; } // ESP_OK => all good, ESP_FAIL => failed to mount file system, other => failed to init. the SD card static esp_err_t SD_Init(void) { // Host = SDSPI_HOST_DEFAULT(); // Host.max_freq_khz = SDMMC_FREQ_PROBING; // esp_err_t Ret = spi_bus_initialize((spi_host_device_t)SD_Host.slot, &SD_BusConfig, SD_SPI_DMA); SD_SlotConfig = SDSPI_SLOT_CONFIG_DEFAULT(); SD_SlotConfig.gpio_miso = PIN_SD_MISO; SD_SlotConfig.gpio_mosi = PIN_SD_MOSI; SD_SlotConfig.gpio_sck = PIN_SD_SCK; SD_SlotConfig.gpio_cs = PIN_SD_CS; // SD_SlotConfig.host_id = (spi_host_device_t)SD_Host.slot; SD_SlotConfig.dma_channel = SD_SPI_DMA; // otherwise it conflicts with RFM SPI or LCD SPI return SD_Mount(); } // ESP_OK => all good, ESP_FAIL => failed to mount file system, other => failed to init. the SD card #endif // WITH_SD //-------------------------------------------------------------------------------------------------------- volatile uint8_t LED_PCB_Counter = 0; void LED_PCB_Flash(uint8_t Time) { if(Time>LED_PCB_Counter) LED_PCB_Counter=Time; } // [ms] #ifdef WITH_LED_TX volatile uint8_t LED_TX_Counter = 0; void LED_TX_Flash(uint8_t Time) { if(Time>LED_TX_Counter) LED_TX_Counter=Time; } // [ms] #endif #ifdef WITH_LED_RX volatile uint8_t LED_RX_Counter = 0; void LED_RX_Flash(uint8_t Time) { if(Time>LED_RX_Counter) LED_RX_Counter=Time; } // [ms] #endif void LED_TimerCheck(uint8_t Ticks) { uint8_t Counter=LED_PCB_Counter; if(Counter) { if(Ticks=30000; // [ms] setup SleepRequest if button pressed for >= 4sec #ifdef WITH_LONGPRESS_SLEEP if(!SleepPending && Button_PressTime>=4000) { SleepIn(); SleepPending=1; } #endif if(Button_ReleaseTime) // if release-time counter non-zero { // Format_String(CONS_UART_Write, "Button pressed: released for "); // Format_UnsDec(CONS_UART_Write, Button_ReleaseTime, 4, 3); // Format_String(CONS_UART_Write, "sec\n"); ReleaseTime=Button_ReleaseTime; // then return the release time Button_ReleaseTime=0; } return ReleaseTime; } // [ms] when button was pressed, return the release time static uint32_t Button_keptReleased(uint8_t Ticks) { uint32_t PressTime=0; Button_ReleaseTime+=Ticks; // count release time if(Button_PressTime) // if pressed-time non-zero { // Format_String(CONS_UART_Write, "Button released: pressed for "); // Format_UnsDec(CONS_UART_Write, Button_PressTime, 4, 3); // Format_String(CONS_UART_Write, "sec\n"); // if(Button_SleepRequest) // { Format_String(CONS_UART_Write, "Sleep in 2 sec\n"); // vTaskDelay(2000); // Sleep(); } PressTime=Button_PressTime; // return the pressed-time #ifdef WITH_SLEEP if(SleepPending) { Sleep(); SleepOut(); SleepPending=0; } #endif Button_PressTime=0; } return PressTime; } // [ms] when button is released, return the press time int32_t Button_TimerCheck(uint8_t Ticks) { int32_t PressReleaseTime=0; #ifdef PIN_BUTTON // CONS_UART_Write(Button_isPressed()?'^':'_'); if(Button_isPressed()) { Button_Filter+=Ticks; if(Button_Filter>Button_FilterTime) Button_Filter=Button_FilterTime; // increment and saturate the counter if(Button_Filter>=Button_FilterThres) // if above the threshold { uint32_t ReleaseTime=Button_keptPressed(Ticks); // count for how long it is being kept pressed if(ReleaseTime) PressReleaseTime=(-(int32_t)ReleaseTime);; } } else { Button_Filter-=Ticks; if(Button_Filter<(-Button_FilterTime)) Button_Filter=(-Button_FilterTime); // decrement and saturate if(Button_Filter<=(-Button_FilterThres)) // if below the threshold { uint32_t PressTime=Button_keptReleased(Ticks); // count for how long it is being kept released if(PressTime) PressReleaseTime=PressTime; } } #endif return PressReleaseTime; } // [ms] return press (positive) or release (negative) button times /* 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(1); } */ //-------------------------------------------------------------------------------------------------------- // AXP192 #ifdef WITH_AXP // SemaphoreHandle_t AXP_Mutex; AXP192 AXP; #endif #ifdef WITH_BQ BQ24295 BQ; #endif //-------------------------------------------------------------------------------------------------------- // ADC static esp_adc_cal_characteristics_t *ADC_characs = (esp_adc_cal_characteristics_t *)calloc(1, sizeof(esp_adc_cal_characteristics_t)); #ifdef WITH_TBEAM static adc1_channel_t ADC_Chan_Batt = ADC1_GPIO35_CHANNEL; static adc1_channel_t ADC_Chan_Knob = ADC1_GPIO34_CHANNEL; #else static adc1_channel_t ADC_Chan_Batt = ADC1_GPIO36_CHANNEL; #endif static const adc_atten_t ADC_atten = ADC_ATTEN_DB_11; static const adc_unit_t ADC_unit = ADC_UNIT_1; #define ADC_Vref 1100 static int ADC_Init(void) { // if (esp_adc_cal_check_efuse(ESP_ADC_CAL_VAL_EFUSE_TP) == ESP_OK) // Check TP is burned into eFuse // if (esp_adc_cal_check_efuse(ESP_ADC_CAL_VAL_EFUSE_VREF) == ESP_OK) // Check Vref is burned into eFuse adc1_config_width(ADC_WIDTH_BIT_12); adc1_config_channel_atten(ADC_Chan_Batt, ADC_atten); esp_adc_cal_value_t val_type = esp_adc_cal_characterize(ADC_unit, ADC_atten, ADC_WIDTH_BIT_12, ADC_Vref, ADC_characs); // calibrate ADC1 return 0; } #ifdef WITH_AXP uint16_t BatterySense(int Samples) { return AXP.readBatteryVoltage(); } // [mV] #else uint16_t BatterySense(int Samples) { uint32_t RawVoltage=0; for( int Idx=0; Idx=Bias) Volt-=Bias; return Volt; } // [mV] #endif #ifdef WITH_TBEAM uint16_t KnobSense(int Samples) { uint16_t RawVoltage=0; for( int Idx=0; Idx0) { if(PressRelease<=700) // short button push: switch pages { KeyBuffer.Write(0x01); } else if(PressRelease<=3000) // longer button push: some page action { KeyBuffer.Write(0x41); } else // very long push { } } } } // ====================================================================================================== 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; } // ====================================================================================================== #ifdef WITH_SPIFFS #ifdef WITH_SPIFFS_FAT // FAT replaces SPIFFS, hopefully no performace and reliability issues int SPIFFS_Register(const char *Path, const char *Label, size_t MaxOpenFiles) { esp_vfs_fat_mount_config_t FSconf; FSconf.max_files = MaxOpenFiles; FSconf.format_if_mount_failed = true; FSconf.allocation_unit_size = 4096; static wl_handle_t Handle = WL_INVALID_HANDLE; return esp_vfs_fat_spiflash_mount(Path, Label, &FSconf, &Handle); } int SPIFFS_Info(size_t &Total, size_t &Used, const char *Label) { FATFS *FS=0; Total=0; Used=0; size_t FreeClusters; int Ret = f_getfree("0:", &FreeClusters, &FS); // if(Ret=!FR_OK) return Ret; if(FS==0) return 0; size_t TotalSectors = (FS->n_fatent-2) * FS->csize; size_t FreeSectors = FreeClusters * FS->csize; Total = TotalSectors * FS->ssize; Used = (TotalSectors-FreeSectors) * FS->ssize; return 0; } #else // SPIFFS: gives troubles when more than few files are open 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); } #endif #endif // ====================================================================================================== SemaphoreHandle_t I2C_Mutex; uint8_t I2C_Read(uint8_t Bus, uint8_t Addr, uint8_t Reg, uint8_t *Data, uint8_t Len, uint8_t Wait) { 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_start(Cmd); i2c_master_write_byte(Cmd, (Addr<<1) | I2C_MASTER_READ, I2C_MASTER_ACK); i2c_master_read(Cmd, Data, Len, I2C_MASTER_LAST_NACK); i2c_master_stop(Cmd); xSemaphoreTake(I2C_Mutex, portMAX_DELAY); esp_err_t Ret = i2c_master_cmd_begin((i2c_port_t)Bus, Cmd, Wait); xSemaphoreGive(I2C_Mutex); i2c_cmd_link_delete(Cmd); return Ret; } uint8_t I2C_Write(uint8_t Bus, uint8_t Addr, uint8_t Reg, uint8_t *Data, uint8_t Len, uint8_t Wait) { 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); xSemaphoreTake(I2C_Mutex, portMAX_DELAY); esp_err_t Ret = i2c_master_cmd_begin((i2c_port_t)Bus, Cmd, Wait); xSemaphoreGive(I2C_Mutex); i2c_cmd_link_delete(Cmd); return Ret; } uint8_t I2C_Restart(uint8_t Bus) { return 0; } // ======================================================================================================