From 923bdbf7b80fa186336188f32c4d0a940e4806a9 Mon Sep 17 00:00:00 2001 From: Alex Mikhalev Date: Fri, 21 Dec 2018 09:20:30 -0800 Subject: [PATCH] add oled support --- .gitignore | 1 + .gitmodules | 3 + components/u8g2 | 1 + main/CMakeLists.txt | 8 +- main/sx127x_driver/sx127x_driver.c | 23 ++- main/sx127x_driver/sx127x_driver.h | 4 +- main/u8g2_esp32_hal.c | 272 +++++++++++++++++++++++++++++ main/u8g2_esp32_hal.h | 45 +++++ main/ugv_main.c | 215 ++++++++++++----------- 9 files changed, 459 insertions(+), 113 deletions(-) create mode 100644 .gitmodules create mode 160000 components/u8g2 create mode 100644 main/u8g2_esp32_hal.c create mode 100644 main/u8g2_esp32_hal.h diff --git a/.gitignore b/.gitignore index c0b1400..b3f7207 100644 --- a/.gitignore +++ b/.gitignore @@ -1,4 +1,5 @@ /.vscode /sdkconfig +/sdkconfig.old /build /cmake-build* \ No newline at end of file diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000..0b035fd --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "components/u8g2"] + path = components/u8g2 + url = https://github.com/olikraus/u8g2.git diff --git a/components/u8g2 b/components/u8g2 new file mode 160000 index 0000000..cd16a10 --- /dev/null +++ b/components/u8g2 @@ -0,0 +1 @@ +Subproject commit cd16a10d0ec85d6c6ddc3579a4e1456f08e10984 diff --git a/main/CMakeLists.txt b/main/CMakeLists.txt index 3c0afc8..c9aa810 100644 --- a/main/CMakeLists.txt +++ b/main/CMakeLists.txt @@ -1,4 +1,8 @@ -set(COMPONENT_SRCS "ugv_main.c" "sx127x_driver/sx127x_driver.c") -set(COMPONENT_ADD_INCLUDEDIRS "." "./sx127x_driver") +set(COMPONENT_SRCS "ugv_main.c" + "u8g2_esp32_hal.c" + "sx127x_driver/sx127x_driver.c") +set(COMPONENT_ADD_INCLUDEDIRS "." + "./sx127x_driver") +set(COMPONENT_REQUIRES "u8g2") register_component() \ No newline at end of file diff --git a/main/sx127x_driver/sx127x_driver.c b/main/sx127x_driver/sx127x_driver.c index a74df15..e17bc47 100644 --- a/main/sx127x_driver/sx127x_driver.c +++ b/main/sx127x_driver/sx127x_driver.c @@ -1,6 +1,8 @@ #include "sx127x_driver.h" -#include "esp_log.h" +#include +#include +#include const char *SX127X_TAG = "sx127x"; @@ -38,13 +40,21 @@ esp_err_t sx127x_init(sx127x_config_t *config, sx127x_t *handle) { esp_err_t ret; - handle->rst_io_num = config->rst_io_num; - handle->irq_io_num = config->irq_io_num; - ret = gpio_set_direction(handle->rst_io_num, GPIO_MODE_OUTPUT); + memcpy(&handle->config, config, sizeof(sx127x_config_t)); + + ret = gpio_set_direction(config->rst_io_num, GPIO_MODE_OUTPUT); SX127X_ERROR_CHECK(ret, "gpio_set_direction") - ret = gpio_set_direction(handle->irq_io_num, GPIO_MODE_OUTPUT); + ret = gpio_set_direction(config->irq_io_num, GPIO_MODE_OUTPUT); SX127X_ERROR_CHECK(ret, "gpio_set_direction") + gpio_set_level(config->cs_io_num, 1); + + // perform reset + gpio_set_level(config->rst_io_num, 0); + vTaskDelay(pdMS_TO_TICKS(10)); + gpio_set_level(config->rst_io_num, 1); + vTaskDelay(pdMS_TO_TICKS(10)); + spi_bus_config_t bus_config = { .mosi_io_num = config->mosi_io_num, .miso_io_num = config->miso_io_num, @@ -54,7 +64,6 @@ esp_err_t sx127x_init(sx127x_config_t *config, sx127x_t *handle) .max_transfer_sz = SX127X_MAX_TRANSFER}; ret = spi_bus_initialize(config->spi_host, &bus_config, 1); SX127X_ERROR_CHECK(ret, "spi_bus_initialize") - handle->spi_host = config->spi_host; spi_device_interface_config_t device_config = { .command_bits = 0, @@ -85,7 +94,7 @@ esp_err_t sx127x_free(sx127x_t *handle) ret = spi_bus_remove_device(handle->device_handle); SX127X_ERROR_CHECK(ret, "spi_bus_remove_device") - ret = spi_bus_free(handle->spi_host); + ret = spi_bus_free(handle->config.spi_host); SX127X_ERROR_CHECK(ret, "spi_bus_free") return ESP_OK; diff --git a/main/sx127x_driver/sx127x_driver.h b/main/sx127x_driver/sx127x_driver.h index 3d64855..d7cddc6 100644 --- a/main/sx127x_driver/sx127x_driver.h +++ b/main/sx127x_driver/sx127x_driver.h @@ -31,10 +31,8 @@ typedef struct sx127x_config typedef struct sx127x { - spi_host_device_t spi_host; + sx127x_config_t config; spi_device_handle_t device_handle; - gpio_num_t rst_io_num; - gpio_num_t irq_io_num; } sx127x_t; esp_err_t sx127x_init(sx127x_config_t *config, sx127x_t *handle); diff --git a/main/u8g2_esp32_hal.c b/main/u8g2_esp32_hal.c new file mode 100644 index 0000000..3147d05 --- /dev/null +++ b/main/u8g2_esp32_hal.c @@ -0,0 +1,272 @@ +#include +#include + +#include "sdkconfig.h" +#include "esp_log.h" + +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" + +#include "u8g2_esp32_hal.h" + +static const char *TAG = "u8g2_hal"; +static const unsigned int I2C_TIMEOUT_MS = 1000; + +static spi_device_handle_t handle_spi; // SPI handle. +static i2c_cmd_handle_t handle_i2c; // I2C handle. +static u8g2_esp32_hal_t u8g2_esp32_hal; // HAL state data. + +#undef ESP_ERROR_CHECK +#define ESP_ERROR_CHECK(x) \ + do \ + { \ + esp_err_t rc = (x); \ + if (rc != ESP_OK) \ + { \ + ESP_LOGE("err", "esp_err_t = %d", rc); \ + assert(0 && #x); \ + } \ + } while (0); + +/* + * Initialze the ESP32 HAL. + */ +void u8g2_esp32_hal_init(u8g2_esp32_hal_t u8g2_esp32_hal_param) +{ + u8g2_esp32_hal = u8g2_esp32_hal_param; +} // u8g2_esp32_hal_init + +/* + * HAL callback function as prescribed by the U8G2 library. This callback is invoked + * to handle SPI communications. + */ +uint8_t u8g2_esp32_spi_byte_cb(u8x8_t *u8x8, uint8_t msg, uint8_t arg_int, void *arg_ptr) +{ + ESP_LOGV(TAG, "spi_byte_cb: Received a msg: %d, arg_int: %d, arg_ptr: %p", msg, arg_int, arg_ptr); + switch (msg) + { + case U8X8_MSG_BYTE_SET_DC: + if (u8g2_esp32_hal.dc != U8G2_ESP32_HAL_UNDEFINED) + { + gpio_set_level(u8g2_esp32_hal.dc, arg_int); + } + break; + + case U8X8_MSG_BYTE_INIT: + { + if (u8g2_esp32_hal.clk == U8G2_ESP32_HAL_UNDEFINED || + u8g2_esp32_hal.mosi == U8G2_ESP32_HAL_UNDEFINED || + u8g2_esp32_hal.cs == U8G2_ESP32_HAL_UNDEFINED) + { + break; + } + + spi_bus_config_t bus_config; + memset(&bus_config, 0, sizeof(spi_bus_config_t)); + bus_config.sclk_io_num = u8g2_esp32_hal.clk; // CLK + bus_config.mosi_io_num = u8g2_esp32_hal.mosi; // MOSI + bus_config.miso_io_num = -1; // MISO + bus_config.quadwp_io_num = -1; // Not used + bus_config.quadhd_io_num = -1; // Not used + //ESP_LOGI(TAG, "... Initializing bus."); + ESP_ERROR_CHECK(spi_bus_initialize(HSPI_HOST, &bus_config, 1)); + + spi_device_interface_config_t dev_config; + dev_config.address_bits = 0; + dev_config.command_bits = 0; + dev_config.dummy_bits = 0; + dev_config.mode = 0; + dev_config.duty_cycle_pos = 0; + dev_config.cs_ena_posttrans = 0; + dev_config.cs_ena_pretrans = 0; + dev_config.clock_speed_hz = 10000; + dev_config.spics_io_num = u8g2_esp32_hal.cs; + dev_config.flags = 0; + dev_config.queue_size = 200; + dev_config.pre_cb = NULL; + dev_config.post_cb = NULL; + //ESP_LOGI(TAG, "... Adding device bus."); + ESP_ERROR_CHECK(spi_bus_add_device(HSPI_HOST, &dev_config, &handle_spi)); + + break; + } + + case U8X8_MSG_BYTE_SEND: + { + spi_transaction_t trans_desc; + trans_desc.addr = 0; + trans_desc.cmd = 0; + trans_desc.flags = 0; + trans_desc.length = 8 * arg_int; // Number of bits NOT number of bytes. + trans_desc.rxlength = 0; + trans_desc.tx_buffer = arg_ptr; + trans_desc.rx_buffer = NULL; + + //ESP_LOGI(TAG, "... Transmitting %d bytes.", arg_int); + ESP_ERROR_CHECK(spi_device_transmit(handle_spi, &trans_desc)); + break; + } + } + return 0; +} // u8g2_esp32_spi_byte_cb + +/* + * HAL callback function as prescribed by the U8G2 library. This callback is invoked + * to handle I2C communications. + */ +uint8_t u8g2_esp32_i2c_byte_cb(u8x8_t *u8x8, uint8_t msg, uint8_t arg_int, void *arg_ptr) +{ + // ESP_LOGV(TAG, "i2c_cb: Received a msg: %d, arg_int: %d, arg_ptr: %p", msg, arg_int, arg_ptr); + + switch (msg) + { + case U8X8_MSG_BYTE_SET_DC: + { + if (u8g2_esp32_hal.dc != U8G2_ESP32_HAL_UNDEFINED) + { + gpio_set_level(u8g2_esp32_hal.dc, arg_int); + } + break; + } + + case U8X8_MSG_BYTE_INIT: + { + if (u8g2_esp32_hal.sda == U8G2_ESP32_HAL_UNDEFINED || + u8g2_esp32_hal.scl == U8G2_ESP32_HAL_UNDEFINED) + { + break; + } + + i2c_config_t conf; + conf.mode = I2C_MODE_MASTER; + ESP_LOGD(TAG, "sda_io_num %d", u8g2_esp32_hal.sda); + conf.sda_io_num = u8g2_esp32_hal.sda; + conf.sda_pullup_en = GPIO_PULLUP_ENABLE; + ESP_LOGD(TAG, "scl_io_num %d", u8g2_esp32_hal.scl); + conf.scl_io_num = u8g2_esp32_hal.scl; + conf.scl_pullup_en = GPIO_PULLUP_ENABLE; + ESP_LOGD(TAG, "clk_speed %d", I2C_MASTER_FREQ_HZ); + conf.master.clk_speed = I2C_MASTER_FREQ_HZ; + ESP_LOGD(TAG, "i2c_param_config %d", conf.mode); + ESP_ERROR_CHECK(i2c_param_config(I2C_MASTER_NUM, &conf)); + ESP_LOGD(TAG, "i2c_driver_install %d", I2C_MASTER_NUM); + ESP_ERROR_CHECK(i2c_driver_install(I2C_MASTER_NUM, conf.mode, I2C_MASTER_RX_BUF_DISABLE, I2C_MASTER_TX_BUF_DISABLE, 0)); + break; + } + + case U8X8_MSG_BYTE_SEND: + { + uint8_t *data_ptr = (uint8_t *)arg_ptr; + ESP_LOG_BUFFER_HEXDUMP(TAG, data_ptr, arg_int, ESP_LOG_VERBOSE); + + while (arg_int > 0) + { + ESP_ERROR_CHECK(i2c_master_write_byte(handle_i2c, *data_ptr, ACK_CHECK_EN)); + data_ptr++; + arg_int--; + } + break; + } + + case U8X8_MSG_BYTE_START_TRANSFER: + { + uint8_t i2c_address = u8x8_GetI2CAddress(u8x8); + handle_i2c = i2c_cmd_link_create(); + // ESP_LOGV(TAG, "Start I2C transfer to %02X.", i2c_address >> 1); + ESP_ERROR_CHECK(i2c_master_start(handle_i2c)); + ESP_ERROR_CHECK(i2c_master_write_byte(handle_i2c, i2c_address | I2C_MASTER_WRITE, ACK_CHECK_EN)); + break; + } + + case U8X8_MSG_BYTE_END_TRANSFER: + { + // ESP_LOGV(TAG, "End I2C transfer."); + ESP_ERROR_CHECK(i2c_master_stop(handle_i2c)); + ESP_ERROR_CHECK(i2c_master_cmd_begin(I2C_MASTER_NUM, handle_i2c, I2C_TIMEOUT_MS / portTICK_RATE_MS)); + i2c_cmd_link_delete(handle_i2c); + break; + } + } + return 0; +} // u8g2_esp32_i2c_byte_cb + +/* + * HAL callback function as prescribed by the U8G2 library. This callback is invoked + * to handle callbacks for GPIO and delay functions. + */ +uint8_t u8g2_esp32_gpio_and_delay_cb(u8x8_t *u8x8, uint8_t msg, uint8_t arg_int, void *arg_ptr) +{ + ESP_LOGV(TAG, "gpio_and_delay_cb: Received a msg: %d, arg_int: %d, arg_ptr: %p", msg, arg_int, arg_ptr); + + switch (msg) + { + // Initialize the GPIO and DELAY HAL functions. If the pins for DC and RESET have been + // specified then we define those pins as GPIO outputs. + case U8X8_MSG_GPIO_AND_DELAY_INIT: + { + uint64_t bitmask = 0; + if (u8g2_esp32_hal.dc != U8G2_ESP32_HAL_UNDEFINED) + { + bitmask = bitmask | (1ull << u8g2_esp32_hal.dc); + } + if (u8g2_esp32_hal.reset != U8G2_ESP32_HAL_UNDEFINED) + { + bitmask = bitmask | (1ull << u8g2_esp32_hal.reset); + } + if (u8g2_esp32_hal.cs != U8G2_ESP32_HAL_UNDEFINED) + { + bitmask = bitmask | (1ull << u8g2_esp32_hal.cs); + } + + if (bitmask == 0) + { + break; + } + gpio_config_t gpioConfig; + gpioConfig.pin_bit_mask = bitmask; + gpioConfig.mode = GPIO_MODE_OUTPUT; + gpioConfig.pull_up_en = GPIO_PULLUP_DISABLE; + gpioConfig.pull_down_en = GPIO_PULLDOWN_ENABLE; + gpioConfig.intr_type = GPIO_INTR_DISABLE; + gpio_config(&gpioConfig); + break; + } + + // Set the GPIO reset pin to the value passed in through arg_int. + case U8X8_MSG_GPIO_RESET: + if (u8g2_esp32_hal.reset != U8G2_ESP32_HAL_UNDEFINED) + { + gpio_set_level(u8g2_esp32_hal.reset, arg_int); + } + break; + // Set the GPIO client select pin to the value passed in through arg_int. + case U8X8_MSG_GPIO_CS: + if (u8g2_esp32_hal.cs != U8G2_ESP32_HAL_UNDEFINED) + { + gpio_set_level(u8g2_esp32_hal.cs, arg_int); + } + break; + // Set the Software I²C pin to the value passed in through arg_int. + case U8X8_MSG_GPIO_I2C_CLOCK: + if (u8g2_esp32_hal.scl != U8G2_ESP32_HAL_UNDEFINED) + { + gpio_set_level(u8g2_esp32_hal.scl, arg_int); + // printf("%c",(arg_int==1?'C':'c')); + } + break; + // Set the Software I²C pin to the value passed in through arg_int. + case U8X8_MSG_GPIO_I2C_DATA: + if (u8g2_esp32_hal.sda != U8G2_ESP32_HAL_UNDEFINED) + { + gpio_set_level(u8g2_esp32_hal.sda, arg_int); + // printf("%c",(arg_int==1?'D':'d')); + } + break; + + // Delay for the number of milliseconds passed in through arg_int. + case U8X8_MSG_DELAY_MILLI: + vTaskDelay(arg_int / portTICK_PERIOD_MS); + break; + } + return 0; +} // u8g2_esp32_gpio_and_delay_cb \ No newline at end of file diff --git a/main/u8g2_esp32_hal.h b/main/u8g2_esp32_hal.h new file mode 100644 index 0000000..3763f20 --- /dev/null +++ b/main/u8g2_esp32_hal.h @@ -0,0 +1,45 @@ +/* + * u8g2_esp32_hal.h + * + * Created on: Feb 12, 2017 + * Author: kolban + */ + +#ifndef U8G2_ESP32_HAL_H_ +#define U8G2_ESP32_HAL_H_ +#include "u8g2.h" + +#include "driver/gpio.h" +#include "driver/spi_master.h" +#include "driver/i2c.h" + +#define U8G2_ESP32_HAL_UNDEFINED (-1) + +#define I2C_MASTER_NUM I2C_NUM_1 // I2C port number for master dev +#define I2C_MASTER_TX_BUF_DISABLE 0 // I2C master do not need buffer +#define I2C_MASTER_RX_BUF_DISABLE 0 // I2C master do not need buffer +#define I2C_MASTER_FREQ_HZ 50000 // I2C master clock frequency +#define ACK_CHECK_EN 0x1 // I2C master will check ack from slave +#define ACK_CHECK_DIS 0x0 // I2C master will not check ack from slave + +typedef struct +{ + gpio_num_t clk; + gpio_num_t mosi; + gpio_num_t sda; // data for I²C + gpio_num_t scl; // clock for I²C + gpio_num_t cs; + gpio_num_t reset; + gpio_num_t dc; +} u8g2_esp32_hal_t; + +#define U8G2_ESP32_HAL_DEFAULT \ + { \ + U8G2_ESP32_HAL_UNDEFINED, U8G2_ESP32_HAL_UNDEFINED, U8G2_ESP32_HAL_UNDEFINED, U8G2_ESP32_HAL_UNDEFINED, U8G2_ESP32_HAL_UNDEFINED, U8G2_ESP32_HAL_UNDEFINED, U8G2_ESP32_HAL_UNDEFINED \ + } + +void u8g2_esp32_hal_init(u8g2_esp32_hal_t u8g2_esp32_hal_param); +uint8_t u8g2_esp32_spi_byte_cb(u8x8_t *u8x8, uint8_t msg, uint8_t arg_int, void *arg_ptr); +uint8_t u8g2_esp32_i2c_byte_cb(u8x8_t *u8x8, uint8_t msg, uint8_t arg_int, void *arg_ptr); +uint8_t u8g2_esp32_gpio_and_delay_cb(u8x8_t *u8x8, uint8_t msg, uint8_t arg_int, void *arg_ptr); +#endif /* U8G2_ESP32_HAL_H_ */ \ No newline at end of file diff --git a/main/ugv_main.c b/main/ugv_main.c index 7f1d2a6..9e1e766 100644 --- a/main/ugv_main.c +++ b/main/ugv_main.c @@ -1,15 +1,22 @@ -#include -#include -#include -#include -#include +#define U8X8_USE_PINS +// #include +#include +// #include +// #include +#include +#include #include +#include +#include + +#include "u8g2_esp32_hal.h" const char *TAG = "uas-ugv"; -class U8G2_SSD1306_128X64_NONAME_F_HW_I2C u8g2(U8G2_R0, 16, 15, 4); +// U8G2_SSD1306_128X64_NONAME_F_HW_I2C u8g2(U8G2_R0, 16, 15, 4); +u8g2_t u8g2; -class SPIClass lora_spi(VSPI); +// SPIClass lora_spi(VSPI); #define LORA_SCK 5 #define LORA_MISO 19 @@ -37,87 +44,84 @@ uint16_t packet_num; void loraTask(void *params); void loraOnReceive(int packetSize); -xTaskHandle lora_task_hndl; -xQueueHandle lora_packet_recv_queue; // packets recieved (type Packet) -xQueueHandle lora_packet_isr_queue; // packet lengths from the recieve isr (type int) +TaskHandle_t lora_task_hndl; +QueueHandle_t lora_packet_recv_queue; // packets recieved (type Packet) +QueueHandle_t lora_packet_isr_queue; // packet lengths from the recieve isr (type int) -Packet packet; +struct Packet packet; + +void setup_serial(void) +{ + const uart_port_t uart_num = UART_NUM_2; + uart_config_t uart_config = { + .baud_rate = 115200, + .data_bits = UART_DATA_8_BITS, + .parity = UART_PARITY_DISABLE, + .stop_bits = UART_STOP_BITS_1, + .flow_ctrl = UART_HW_FLOWCTRL_CTS_RTS, + .rx_flow_ctrl_thresh = 122, + }; + // Configure UART parameters + ESP_ERROR_CHECK(uart_param_config(uart_num, &uart_config)); +} + +void setup_oled(void) +{ + u8g2_esp32_hal_t u8g2_hal_config = { + .scl = 15, + .sda = 4, + .reset = 16, + }; + u8g2_esp32_hal_init(u8g2_hal_config); + + u8g2_Setup_ssd1306_i2c_128x64_noname_f(&u8g2, + U8G2_R0, + u8g2_esp32_i2c_byte_cb, + u8g2_esp32_gpio_and_delay_cb); + u8g2_InitDisplay(&u8g2); + u8g2_ClearDisplay(&u8g2); + u8g2_SetPowerSave(&u8g2, false); +} void setup(void) { - Serial.begin(115200); - while (!Serial) - { - delay(10); - } + setup_serial(); ESP_LOGI(TAG, "setup"); - Serial.println("setup"); - lora_packet_recv_queue = xQueueCreate(4, sizeof(Packet)); + setup_oled(); + + lora_packet_recv_queue = xQueueCreate(4, sizeof(struct Packet)); lora_packet_isr_queue = xQueueCreate(4, sizeof(int)); configASSERT(lora_packet_recv_queue != 0); configASSERT(lora_packet_isr_queue != 0); - lora_spi.begin(LORA_SCK, LORA_MISO, LORA_MOSI, LORA_CS); - LoRa.setSPI(lora_spi); - LoRa.setPins(LORA_CS, LORA_RST, LORA_IRQ); - int res = LoRa.begin(LORA_FREQ); // 433MHz - if (!res) - { - Serial.println("LoRa init failed"); - } - LoRa.setTxPower(17); - LoRa.setSpreadingFactor(11); - LoRa.setSignalBandwidth(125E3); - LoRa.setSyncWord(0x34); - LoRa.enableCrc(); - LoRa.onReceive(loraOnReceive); - LoRa.receive(0); + // lora_spi.begin(LORA_SCK, LORA_MISO, LORA_MOSI, LORA_CS); + // LoRa.setSPI(lora_spi); + // LoRa.setPins(LORA_CS, LORA_RST, LORA_IRQ); + // int res = LoRa.begin(LORA_FREQ); // 433MHz + // if (!res) + // { + ESP_LOGE(TAG, "LoRa init failed"); + // } + // LoRa.setTxPower(17); + // LoRa.setSpreadingFactor(11); + // LoRa.setSignalBandwidth(125E3); + // LoRa.setSyncWord(0x34); + // LoRa.enableCrc(); + // LoRa.onReceive(loraOnReceive); + // LoRa.receive(0); // LoRa.dumpRegisters(Serial); - u8g2.beginSimple(); /* Do not clear the display, wake is not required */ - u8g2.clearDisplay(); - u8g2.setPowerSave(false); - packet_num = 0; xTaskCreate(loraTask, "loraTask", 1024 * 10, NULL, 2, &lora_task_hndl); - memset(&packet, 0, sizeof(Packet)); + memset(&packet, 0, sizeof(struct Packet)); } #define XO 10 -void drawLogo(void) -{ - - u8g2.setFontMode(1); // Transparent - u8g2.setFontDirection(0); - u8g2.setFont(u8g2_font_inb24_mf); - u8g2.drawStr(0 + XO, 30, "U"); - - u8g2.setFontDirection(1); - u8g2.setFont(u8g2_font_inb30_mn); - u8g2.drawStr(21 + XO, 8, "8"); - - u8g2.setFontDirection(0); - u8g2.setFont(u8g2_font_inb24_mf); - u8g2.drawStr(51 + XO, 30, "g"); - u8g2.drawStr(67 + XO, 30, "\xb2"); - - u8g2.drawHLine(2 + XO, 35, 47); - u8g2.drawHLine(3 + XO, 36, 47); - u8g2.drawVLine(45 + XO, 32, 12); - u8g2.drawVLine(46 + XO, 33, 12); -} - -void drawURL(void) -{ - u8g2.setFont(u8g2_font_6x12_tr); - u8g2.drawStr(1 + XO, 54, "github.com/olikraus/u8g2"); -} - void loraOnReceive(int packetSize) { if (packetSize == 0) @@ -134,7 +138,7 @@ void loraTask(void *params) TickType_t send_period = pdMS_TO_TICKS(2000); TickType_t current_time = xTaskGetTickCount(); TickType_t next_send = current_time + send_period; - Packet recvd_packet; + struct Packet recvd_packet; while (true) { TickType_t delay_ticks = next_send - current_time; @@ -142,25 +146,26 @@ void loraTask(void *params) if (didReceive) { int packetSize = (packet_len > LORA_BUF_LEN - 1) ? (LORA_BUF_LEN - 1) : (packet_len); - LoRa.setTimeout(50); - LoRa.readBytes(recvd_packet.buffer, packetSize); + // LoRa.setTimeout(50); + // LoRa.readBytes(recvd_packet.buffer, packetSize); recvd_packet.buffer_len = packetSize; recvd_packet.buffer[packetSize - 1] = '\0'; - recvd_packet.rssi = LoRa.packetRssi(); - recvd_packet.snr = LoRa.packetSnr(); + // recvd_packet.rssi = LoRa.packetRssi(); + // recvd_packet.snr = LoRa.packetSnr(); xQueueSend(lora_packet_recv_queue, &recvd_packet, 10); } current_time = xTaskGetTickCount(); - if (current_time >= next_send) { + if (current_time >= next_send) + { sprintf(outBuf, "hello world %d", packet_num); packet_num++; - LoRa.beginPacket(); - size_t written = LoRa.write((uint8_t *)outBuf, outBufLen - 1); - LoRa.endPacket(); - Serial.printf("lora wrote %d bytes\n", written); - LoRa.receive(0); // go back to receive mode - + // LoRa.beginPacket(); + // size_t written = LoRa.write((uint8_t *)outBuf, outBufLen - 1); + // LoRa.endPacket(); + // ESP_LOGI(TAG, "lora wrote %d bytes\n", written); + // LoRa.receive(0); // go back to receive mode + current_time = xTaskGetTickCount(); next_send = current_time + send_period; } @@ -169,36 +174,44 @@ void loraTask(void *params) void loop(void) { - Serial.println("loop"); - u8g2.firstPage(); + ESP_LOGI(TAG, "loop"); + u8g2_FirstPage(&u8g2); bool recieved_packet = xQueueReceive(lora_packet_recv_queue, &packet, 10); do { - // drawLogo(); - // drawURL(); - - u8g2.drawRFrame(0, 0, OLED_W, OLED_H, 4); + u8g2_DrawRFrame(&u8g2, 0, 0, OLED_W, OLED_H, 4); uint32_t free_heap = xPortGetFreeHeapSize(); - u8g2.setFont(u8g2_font_4x6_mf); - u8g2.drawStr(4, 8, "Hello World!"); - u8g2.setCursor(4, 8 + 8); - u8g2.printf("free heap: %d", free_heap); + u8g2_SetFont(&u8g2, u8g2_font_4x6_mf); + u8g2_DrawStr(&u8g2, 4, 8, "Hello World!"); + char buf[40]; + snprintf(buf, 40, "free heap: %d", free_heap); + u8g2_DrawStr(&u8g2, 4, 8 + 8, buf); if (packet.buffer_len) { - Serial.printf("lora received packet (len %d, rssi: %d, snr: %f): %s\n", - packet.buffer_len, packet.rssi, packet.snr, packet.buffer); - u8g2.setFont(u8g2_font_4x6_mf); - u8g2.setCursor(4, 8 + 8 + 8); - u8g2.printf("lora pkt(rssi: %d, snr: %f)", packet.rssi, packet.snr); - u8g2.setCursor(4, 8 + 8 + 8 + 8); - u8g2.printf("%s", packet.buffer); + ESP_LOGI(TAG, "lora received packet (len %d, rssi: %d, snr: %f): %s\n", + packet.buffer_len, packet.rssi, packet.snr, packet.buffer); + u8g2_SetFont(&u8g2, u8g2_font_4x6_mf); + snprintf(buf, 40, "lora pkt(rssi: %d, snr: %f)", packet.rssi, packet.snr); + u8g2_DrawStr(&u8g2, 4, 8 + 8 + 8, buf); + snprintf(buf, 40, "%s", packet.buffer); + u8g2_DrawStr(&u8g2, 4, 8 + 8 + 8 + 8, buf); } + } while (u8g2_NextPage(&u8g2)); + vTaskDelay(pdMS_TO_TICKS(1000)); +} + +void loopTask(void *pvUser) +{ + setup(); + while (1) + { + loop(); + } +} - /* draw a frame around the picture */ - // u8g2.drawFrame(0,0,OLED_W,OLED_H); - // u8g2.drawFrame(1,1,384-2,240-2); - } while (u8g2.nextPage()); - delay(1000); +void app_main() +{ + xTaskCreatePinnedToCore(loopTask, "loopTask", 8192, NULL, 1, NULL, 1); }