From 0f2850dfca96122af99b1a89ccda00efb3adf24a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bruno=20Ryb=C3=A1rsky?= Date: Sun, 27 Apr 2025 01:45:02 +0200 Subject: [PATCH] get mostly one directional comms working --- .devcontainer/Dockerfile | 13 + .devcontainer/devcontainer.json | 21 + .gitignore | 3 + .vscode/c_cpp_properties.json | 23 + .vscode/launch.json | 15 + .vscode/settings.json | 24 + CMakeLists.txt | 8 + README.md | 32 ++ main/CMakeLists.txt | 2 + main/buscfg.h | 19 + main/dataproc.c | 23 + main/dataproc.h | 43 ++ main/main.c | 44 ++ main/packets.h | 121 ++++ main/radio.c | 271 +++++++++ main/radio.h | 19 + main/sx1262.c | 970 ++++++++++++++++++++++++++++++++ main/sx1262.h | 434 ++++++++++++++ 18 files changed, 2085 insertions(+) create mode 100644 .devcontainer/Dockerfile create mode 100644 .devcontainer/devcontainer.json create mode 100644 .gitignore create mode 100644 .vscode/c_cpp_properties.json create mode 100644 .vscode/launch.json create mode 100644 .vscode/settings.json create mode 100644 CMakeLists.txt create mode 100644 README.md create mode 100644 main/CMakeLists.txt create mode 100644 main/buscfg.h create mode 100644 main/dataproc.c create mode 100644 main/dataproc.h create mode 100644 main/main.c create mode 100644 main/packets.h create mode 100644 main/radio.c create mode 100644 main/radio.h create mode 100644 main/sx1262.c create mode 100644 main/sx1262.h diff --git a/.devcontainer/Dockerfile b/.devcontainer/Dockerfile new file mode 100644 index 0000000..dafb8ad --- /dev/null +++ b/.devcontainer/Dockerfile @@ -0,0 +1,13 @@ +ARG DOCKER_TAG=latest +FROM espressif/idf:${DOCKER_TAG} + +ENV LC_ALL=C.UTF-8 +ENV LANG=C.UTF-8 + +RUN apt-get update -y && apt-get install udev -y + +RUN echo "source /opt/esp/idf/export.sh > /dev/null 2>&1" >> ~/.bashrc + +ENTRYPOINT [ "/opt/esp/entrypoint.sh" ] + +CMD ["/bin/bash", "-c"] \ No newline at end of file diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json new file mode 100644 index 0000000..b801786 --- /dev/null +++ b/.devcontainer/devcontainer.json @@ -0,0 +1,21 @@ +{ + "name": "ESP-IDF QEMU", + "build": { + "dockerfile": "Dockerfile" + }, + "customizations": { + "vscode": { + "settings": { + "terminal.integrated.defaultProfile.linux": "bash", + "idf.espIdfPath": "/opt/esp/idf", + "idf.toolsPath": "/opt/esp", + "idf.gitPath": "/usr/bin/git" + }, + "extensions": [ + "espressif.esp-idf-extension", + "espressif.esp-idf-web" + ] + } + }, + "runArgs": ["--privileged"] +} \ No newline at end of file diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..51c9513 --- /dev/null +++ b/.gitignore @@ -0,0 +1,3 @@ +build/ +sdkconfig +sdkconfig.old \ No newline at end of file diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json new file mode 100644 index 0000000..837c329 --- /dev/null +++ b/.vscode/c_cpp_properties.json @@ -0,0 +1,23 @@ +{ + "configurations": [ + { + "name": "ESP-IDF", + "compilerPath": "${config:idf.toolsPath}/tools/xtensa-esp-elf/esp-14.2.0_20241119/xtensa-esp-elf/bin/xtensa-esp32s3-elf-gcc", + "compileCommands": "${config:idf.buildPath}/compile_commands.json", + "includePath": [ + "${config:idf.espIdfPath}/components/**", + "${config:idf.espIdfPathWin}/components/**", + "${workspaceFolder}/**" + ], + "browse": { + "path": [ + "${config:idf.espIdfPath}/components", + "${config:idf.espIdfPathWin}/components", + "${workspaceFolder}" + ], + "limitSymbolsToIncludedHeaders": true + } + } + ], + "version": 4 +} diff --git a/.vscode/launch.json b/.vscode/launch.json new file mode 100644 index 0000000..2511a38 --- /dev/null +++ b/.vscode/launch.json @@ -0,0 +1,15 @@ +{ + "version": "0.2.0", + "configurations": [ + { + "type": "gdbtarget", + "request": "attach", + "name": "Eclipse CDT GDB Adapter" + }, + { + "type": "espidf", + "name": "Launch", + "request": "launch" + } + ] +} \ No newline at end of file diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 0000000..b7c4a37 --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,24 @@ +{ + "C_Cpp.intelliSenseEngine": "default", + "idf.espIdfPath": "/home/bruno/esp/master/esp-idf", + "idf.pythonInstallPath": "/usr/bin/python", + "idf.openOcdConfigs": [ + "board/esp32s3-builtin.cfg" + ], + "idf.port": "/dev/ttyUSB0", + "idf.toolsPath": "/home/bruno/.espressif", + "idf.customExtraVars": { + "OPENOCD_SCRIPTS": "/home/bruno/.espressif/tools/openocd-esp32/v0.12.0-esp32-20240821/openocd-esp32/share/openocd/scripts", + "ESP_ROM_ELF_DIR": "/home/bruno/.espressif/tools/esp-rom-elfs/20240305/", + "IDF_TARGET": "esp32s3" + }, + "idf.flashType": "UART", + "files.associations": { + "**/debian/*.install": "plain", + "dataproc.h": "c", + "array": "c", + "string": "c", + "string_view": "c", + "span": "c" + } +} diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..ef1c14d --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,8 @@ +# For more information about build system see +# https://docs.espressif.com/projects/esp-idf/en/latest/api-guides/build-system.html +# The following five lines of boilerplate have to be in your project's +# CMakeLists in this exact order for cmake to work correctly +cmake_minimum_required(VERSION 3.5) + +include($ENV{IDF_PATH}/tools/cmake/project.cmake) +project(EmbeddedInterFace) \ No newline at end of file diff --git a/README.md b/README.md new file mode 100644 index 0000000..455eb90 --- /dev/null +++ b/README.md @@ -0,0 +1,32 @@ +# _Sample project_ + +(See the README.md file in the upper level 'examples' directory for more information about examples.) + +This is the simplest buildable example. The example is used by command `idf.py create-project` +that copies the project to user specified path and set it's name. For more information follow the [docs page](https://docs.espressif.com/projects/esp-idf/en/latest/api-guides/build-system.html#start-a-new-project) + + + +## How to use example +We encourage the users to use the example as a template for the new projects. +A recommended way is to follow the instructions on a [docs page](https://docs.espressif.com/projects/esp-idf/en/latest/api-guides/build-system.html#start-a-new-project). + +## Example folder contents + +The project **sample_project** contains one source file in C language [main.c](main/main.c). The file is located in folder [main](main). + +ESP-IDF projects are built using CMake. The project build configuration is contained in `CMakeLists.txt` +files that provide set of directives and instructions describing the project's source files and targets +(executable, library, or both). + +Below is short explanation of remaining files in the project folder. + +``` +├── CMakeLists.txt +├── main +│   ├── CMakeLists.txt +│   └── main.c +└── README.md This is the file you are currently reading +``` +Additionally, the sample project contains Makefile and component.mk files, used for the legacy Make based build system. +They are not used or needed when building with CMake and idf.py. diff --git a/main/CMakeLists.txt b/main/CMakeLists.txt new file mode 100644 index 0000000..784085e --- /dev/null +++ b/main/CMakeLists.txt @@ -0,0 +1,2 @@ +idf_component_register(SRCS "radio.c" "radio.h" "packets.h" "sx1262.c" "sx1262.h" "main.c" + INCLUDE_DIRS ".") \ No newline at end of file diff --git a/main/buscfg.h b/main/buscfg.h new file mode 100644 index 0000000..fdf57c7 --- /dev/null +++ b/main/buscfg.h @@ -0,0 +1,19 @@ +#ifndef BUSCFG_FILE +#define BUSCFG_FILE + +#include "soc/gpio_num.h" + +#define ESP_USB_DP GPIO_NUM_20 +#define ESP_USB_DM GPIO_NUM_19 +#define ESP_RXD0 GPIO_NUM_44 +#define ESP_TXD0 GPIO_NUM_43 + +#define HSPI_MISO_GPIO GPIO_NUM_11 +#define HSPI_MOSI_GPIO GPIO_NUM_10 + +#define HSPI_SCK_GPIO GPIO_NUM_9 +#define HSPI_LORA_CS GPIO_NUM_8 +#define LORA_DIO1 GPIO_NUM_14 +#define LORA_BUSY GPIO_NUM_13 +#define LORA_RESET GPIO_NUM_12 +#endif \ No newline at end of file diff --git a/main/dataproc.c b/main/dataproc.c new file mode 100644 index 0000000..2a4871c --- /dev/null +++ b/main/dataproc.c @@ -0,0 +1,23 @@ +#define MAG_SCALE (4912.0f / 32760.0f) +#include "dataproc.h" + +bme680_cal_factors_t dev_cal_factors; + +ambient_temperature = 25; + +void mpu9250_convert_data(int16_t *accel, int16_t *gyro, int16_t temp, int16_t *magnet, float *accel_out, float *gyro_out, float *temp_out, float *magnet_out) +{ + accel_out[0] = accel[0] / 16384.0; // Accel X in g + accel_out[1] = accel[1] / 16384.0; // Accel Y in g + accel_out[2] = accel[2] / 16384.0; // Accel Z in g + + gyro_out[0] = gyro[0] / 131.0; // Gyro X in deg/s + gyro_out[1] = gyro[1] / 131.0; // Gyro Y in deg/s + gyro_out[2] = gyro[2] / 131.0; // Gyro Z in deg/s + + magnet_out[0] = magnet[0] * MAG_SCALE; // Gyro X in deg/s + magnet_out[1] = magnet[1] * MAG_SCALE; // Gyro Y in deg/s + magnet_out[2] = magnet[2] * MAG_SCALE; // Gyro Z in deg/s + + *temp_out = (temp / 333.87) + 21.0; // Temperature in °C +} \ No newline at end of file diff --git a/main/dataproc.h b/main/dataproc.h new file mode 100644 index 0000000..e226430 --- /dev/null +++ b/main/dataproc.h @@ -0,0 +1,43 @@ +#ifndef DATAPROC_COMPONENT +#define DATAPROC_COMPONENT + +#include + +typedef struct bme680_cal_factors_s { + /* temperature compensation */ + uint16_t par_T1; + int16_t par_T2; + int8_t par_T3; + float temperature_fine; + /* humidity compensation */ + uint16_t par_H1; + uint16_t par_H2; + int8_t par_H3; + int8_t par_H4; + int8_t par_H5; + uint8_t par_H6; + int8_t par_H7; + /* pressure compensation */ + uint16_t par_P1; + int16_t par_P2; + int8_t par_P3; + int16_t par_P4; + int16_t par_P5; + int8_t par_P6; + int8_t par_P7; + int16_t par_P8; + int16_t par_P9; + uint8_t par_P10; + /* resistance heat compensation */ + int8_t par_G1; + int16_t par_G2; + int8_t par_G3; + /* other */ + uint8_t res_heat_range; + int8_t res_heat_val; + int8_t range_switching_error; +} bme680_cal_factors_t; + + + +#endif diff --git a/main/main.c b/main/main.c new file mode 100644 index 0000000..3f0270a --- /dev/null +++ b/main/main.c @@ -0,0 +1,44 @@ +#include +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "driver/gpio.h" +#include "esp_log.h" +#include "sdkconfig.h" +#include "esp_mac.h" +#include +#include "radio.h" +#include "buscfg.h" +#include "driver/spi_master.h" + +#define TAG "canZem" + +void app_main(void) +{ + + ESP_LOGI("BOOT", "BRN Systems incorporated CanSat flight firmware build: %s %s", __DATE__, __TIME__); + + spi_bus_config_t HighSpeedBusCfg = { + // CONNECTED to LoRa and SD card + .mosi_io_num = HSPI_MOSI_GPIO, + .miso_io_num = HSPI_MISO_GPIO, + .sclk_io_num = HSPI_SCK_GPIO, + .quadwp_io_num = -1, + .quadhd_io_num = -1, + .max_transfer_sz = 64, // probably change + }; + ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &HighSpeedBusCfg, SPI_DMA_CH_AUTO)); + + xTaskCreate( + lora_comms_task, + "LoraCommsTask", + 8192, + NULL, + (tskIDLE_PRIORITY + 2), + NULL); + + while (1) + { + + vTaskDelay(100 / portTICK_PERIOD_MS); + } +} \ No newline at end of file diff --git a/main/packets.h b/main/packets.h new file mode 100644 index 0000000..f027309 --- /dev/null +++ b/main/packets.h @@ -0,0 +1,121 @@ +#ifndef PACKETS_STRUCTS +#define PACKETS_STRUCTS +#include "stdint.h" + +#define UplinkSync "PlechHore" +#define DownlinkSync "PlechDole" + +#define UplinkPacketType_SystemControl 0 +#define UplinkPacketType_Ping 1 +#define UplinkPacketType_ACK 255 + +#define DownlinkPacketType_Telemetry 0 +#define DownlinkPacketType_Ping 1 +#define DownlinkPacketType_ACK 255 + +typedef struct __attribute__((packed)) +{ + char syncPhrase[10]; + uint32_t packetIndex; + uint8_t packetType; + uint32_t missionTimer; +} DownBoundPacket; + +typedef struct __attribute__((packed)) +{ + // MPU data + int16_t accelerationX; + int16_t accelerationY; + int16_t accelerationZ; + int16_t gyroX; + int16_t gyroY; + int16_t gyroZ; + int16_t magnetX; + int16_t magnetY; + int16_t magnetZ; + int16_t accelerometer_temperature; + + // CCS data + uint16_t eCO2; + uint16_t tvoc; + uint8_t currentCCS; + uint16_t rawCCSData; + + // INA data + uint16_t volts; + uint16_t current; + uint16_t power; + + // BME DATA + uint32_t temperature; + uint16_t humidity; + uint32_t pressure; + uint16_t gas; + bool gas_valid; + bool heater_stable; + uint8_t gas_range; + uint8_t gas_index; + + float air_temperature; /*!< air temperature in degrees celsius */ + float relative_humidity; /*!< relative humidity in percent */ + float barometric_pressure; /*!< barometric pressure in hecto-pascal */ + float gas_resistance; /*!< gas resistance in ohms */ + uint16_t iaq_score; /*!< air quality index (0..500) */ + float temperature_score; + float humidity_score; + float gas_score; + + // GPS DATA + uint32_t time_seconds; // Seconds since start of day + int32_t latitude_centi_degrees; // Latitude * 10,000 + int32_t longitude_centi_degrees; // Longitude * 10,000 + int16_t altitude_centi_meters; // Altitude * 100 + uint8_t fix_quality; + uint8_t num_satellites; + uint16_t date_yyddmm; // YYDDMM (from GPRMC) + uint16_t speed_centi_knots; // Speed * 100 (from GPRMC) + + int32_t predicted_latitude_centi_degrees; // Latitude * 10,000 + int32_t predicted_longitude_centi_degrees; // Longitude * 10,000 + int16_t predicted_altitude_centi_meters; // Altitude * 100 + + // ADC DATA + int32_t NH3; + int32_t CO; + int32_t NO2; + int32_t UVC; + + int16_t currentServoA; + int16_t targetServoA; + int16_t currentServoB; + int16_t targetServoB; + +} TelemetryPacket; + +typedef struct __attribute__((packed)) +{ + char syncPhrase[10]; + uint32_t packetIndex; + uint8_t packetType; +} UplinkPacket; + +typedef struct __attribute__((packed)) +{ + uint8_t powerMode; + uint8_t controlMode; + uint16_t servoA; + uint16_t servoB; +} SystemControlPacket; + +typedef struct __attribute__((packed)) +{ + uint8_t PingData[20]; +} PingPacket; + +typedef struct __attribute__((packed)) +{ + uint32_t packetIndex; + uint32_t crc32Checksum; +} ACKPacket; + +#endif \ No newline at end of file diff --git a/main/radio.c b/main/radio.c new file mode 100644 index 0000000..329d270 --- /dev/null +++ b/main/radio.c @@ -0,0 +1,271 @@ +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "sx1262.h" +#include "radio.h" +#include "esp_log.h" +#include "string.h" +#include "esp_timer.h" +#include "packets.h" +#include "esp_rom_crc.h" + + +#define TAG "LoRaGS" + +uint32_t uplinkPacketIndex = 0; + +TelemetryPacket telemetryPacket; +uint8_t packetReadiness = 0; + +void send_ack(uint32_t packetIndex, uint32_t crc) +{ + ACKPacket ack; + ack.packetIndex = packetIndex; + ack.crc32Checksum = crc; + + UplinkPacket uplinkHeader = {0}; + memcpy(uplinkHeader.syncPhrase, UplinkSync, sizeof(UplinkSync)); + uplinkHeader.packetIndex = uplinkPacketIndex++; + uplinkHeader.packetType = UplinkPacketType_ACK; + + uint8_t txBuf[256] = {0}; + int offset = 0; + + memcpy(txBuf + offset, &uplinkHeader, sizeof(uplinkHeader)); + offset += sizeof(uplinkHeader); + + memcpy(txBuf + offset, &ack, sizeof(ack)); + offset += sizeof(ack); + + ESP_LOGI(TAG, "Sending ACK for packet %lu...", packetIndex); + + if (!LoRaSend(txBuf, offset, SX126x_TXMODE_SYNC)) + { + ESP_LOGE(TAG, "ACK Send Failed"); + } +} + +#define MAG_SCALE (4912.0f / 32760.0f) + +void printTelemetryPacket(const TelemetryPacket *packet) +{ + ESP_LOGI(TAG, "Telemetry Packet:"); + + float accel_f[3], gyro_f[3], temp_f, magnet_f[3]; + + accel_f[0] = packet->accelerationX / 16384.0; // Accel X in g + accel_f[1] = packet->accelerationY / 16384.0; // Accel Y in g + accel_f[2] = packet->accelerationZ / 16384.0; // Accel Z in g + + gyro_f[0] = packet->gyroX / 131.0; // Gyro X in deg/s + gyro_f[1] = packet->gyroY / 131.0; // Gyro Y in deg/s + gyro_f[2] = packet->gyroZ / 131.0; // Gyro Z in deg/s + + magnet_f[0] = packet->magnetX * MAG_SCALE; // Gyro X in deg/s + magnet_f[1] = packet->magnetY * MAG_SCALE; // Gyro Y in deg/s + magnet_f[2] = packet->magnetZ * MAG_SCALE; // Gyro Z in deg/s + + temp_f = (packet->accelerometer_temperature / 333.87) + 21.0; // Temperature in °C + + // MPU Data + ESP_LOGI(TAG, " MPU:"); + ESP_LOGI(TAG, " Acceleration [X: %d, Y: %d, Z: %d]", packet->accelerationX, packet->accelerationY, packet->accelerationZ); + ESP_LOGI(TAG, " Gyroscope [X: %d, Y: %d, Z: %d]", packet->gyroX, packet->gyroY, packet->gyroZ); + ESP_LOGI(TAG, " Magnetometer [X: %d, Y: %d, Z: %d]", packet->magnetX, packet->magnetY, packet->magnetZ); + ESP_LOGI(TAG, " Accelerometer Temp: %d", packet->accelerometer_temperature); + + ESP_LOGI(TAG, " MPU (Processed Readings):"); + + ESP_LOGI(TAG, " Acceleration [X: %.3f g, Y: %.3f g, Z: %.3f g]", accel_f[0], accel_f[1], accel_f[2]); + ESP_LOGI(TAG, " Gyroscope [X: %.3f deg/s, Y: %.3f deg/s, Z: %.3f deg/s]", gyro_f[0], gyro_f[1], gyro_f[2]); + ESP_LOGI(TAG, " Magnetometer [X: %.3f uT, Y: %.3f uT, Z: %.3f uT]", magnet_f[0], magnet_f[1], magnet_f[2]); + ESP_LOGI(TAG, " Accelerometer Temp: %f °C", temp_f); + + // CCS Data + ESP_LOGI(TAG, " CCS:"); + ESP_LOGI(TAG, " eCO2: %u ppm", packet->eCO2); + ESP_LOGI(TAG, " TVOC: %u ppb", packet->tvoc); + ESP_LOGI(TAG, " Current CCS: %u", packet->currentCCS); + ESP_LOGI(TAG, " Raw CCS Data: %u", packet->rawCCSData); + + float miliVolts = packet->volts * 1.25; + float miliAmps = packet->current * 1.25; + float power = packet->power * 10; + + // INA Data + ESP_LOGI(TAG, " INA:"); + ESP_LOGI(TAG, " Voltage: %f mV", miliVolts); + ESP_LOGI(TAG, " Current: %f mA", miliAmps); + ESP_LOGI(TAG, " Power: %f mW", power); + + // BME Data + ESP_LOGI(TAG, " BME:"); + ESP_LOGI(TAG, " Temperature: %.2f °C", packet->temperature / 100.0f); + ESP_LOGI(TAG, " Humidity: %.2f %%", packet->humidity / 100.0f); + ESP_LOGI(TAG, " Pressure: %.2f hPa", packet->pressure / 100.0f); + ESP_LOGI(TAG, " Gas Resistance: %u Ohms", packet->gas); + ESP_LOGI(TAG, " Gas Valid: %s", packet->gas_valid ? "Yes" : "No"); + ESP_LOGI(TAG, " Heater Stable: %s", packet->heater_stable ? "Yes" : "No"); + ESP_LOGI(TAG, " Gas Range: %u", packet->gas_range); + ESP_LOGI(TAG, " Gas Index: %u", packet->gas_index); + + // BME Processed Data + ESP_LOGI(TAG, " BME (Processed / Compensated Readings):"); + ESP_LOGI(TAG, " Air Temperature: %.2f °C", packet->air_temperature); + ESP_LOGI(TAG, " Relative Humidity: %.2f %%", packet->relative_humidity); + ESP_LOGI(TAG, " Barometric Pressure: %.2f hPa", packet->barometric_pressure); + ESP_LOGI(TAG, " Gas Resistance: %.2f Ohms", packet->gas_resistance); + ESP_LOGI(TAG, " IAQ Score: %u", packet->iaq_score); + ESP_LOGI(TAG, " Temperature Score: %.2f", packet->temperature_score); + ESP_LOGI(TAG, " Humidity Score: %.2f", packet->humidity_score); + ESP_LOGI(TAG, " Gas Score: %.2f", packet->gas_score); + + // GPS Data + ESP_LOGI(TAG, " GPS:"); + ESP_LOGI(TAG, " Time (seconds): %u", packet->time_seconds); + ESP_LOGI(TAG, " Latitude: %.4f°", packet->latitude_centi_degrees / 10000.0f); + ESP_LOGI(TAG, " Longitude: %.4f°", packet->longitude_centi_degrees / 10000.0f); + ESP_LOGI(TAG, " Altitude: %.2f m", packet->altitude_centi_meters / 100.0f); + ESP_LOGI(TAG, " Fix Quality: %u", packet->fix_quality); + ESP_LOGI(TAG, " Satellites: %u", packet->num_satellites); + ESP_LOGI(TAG, " Date (YYDDMM): %06u", packet->date_yyddmm); + ESP_LOGI(TAG, " Speed: %.2f knots", packet->speed_centi_knots / 100.0f); + + ESP_LOGI(TAG, " GPS Prediction:"); + ESP_LOGI(TAG, " Predicted Latitude: %.4f°", packet->predicted_latitude_centi_degrees / 10000.0f); + ESP_LOGI(TAG, " Predicted Longitude: %.4f°", packet->predicted_longitude_centi_degrees / 10000.0f); + ESP_LOGI(TAG, " Predicted Altitude: %.2f m", packet->predicted_altitude_centi_meters / 100.0f); + + // ADC Data + ESP_LOGI(TAG, " ADC Sensors:"); + ESP_LOGI(TAG, " NH3: %d", packet->NH3); + ESP_LOGI(TAG, " CO: %d", packet->CO); + ESP_LOGI(TAG, " NO2: %d", packet->NO2); + ESP_LOGI(TAG, " UVC: %d", packet->UVC); + + // Servo Data + ESP_LOGI(TAG, " Servos:"); + ESP_LOGI(TAG, " Servo A: Current = %d, Target = %d", packet->currentServoA, packet->targetServoA); + ESP_LOGI(TAG, " Servo B: Current = %d, Target = %d", packet->currentServoB, packet->targetServoB); +} + +void handle_downlink_packet(uint8_t *buf, uint8_t rxLen) +{ + if (rxLen < sizeof(DownBoundPacket)) + { + ESP_LOGW(TAG, "Received packet too small to be valid."); + return; + } + + DownBoundPacket down; + memcpy(&down, buf, sizeof(DownBoundPacket)); + + ESP_LOGI(TAG, "Downlink packet index: %lu, type: %u", down.packetIndex, down.packetType); + + // Verify sync phrase + if (strncmp(down.syncPhrase, DownlinkSync, strlen(DownlinkSync)) != 0) + { + ESP_LOGW(TAG, "Invalid sync phrase, ignoring packet."); + return; + } + + uint8_t *payload = buf + sizeof(DownBoundPacket); + uint32_t payloadSize = rxLen - sizeof(DownBoundPacket); + + switch (down.packetType) + { + case DownlinkPacketType_Telemetry: + if (payloadSize >= sizeof(TelemetryPacket)) + { + memcpy(&telemetryPacket, payload, sizeof(TelemetryPacket)); + ESP_LOGI(TAG, "Telemetry packet received!"); + printTelemetryPacket(&telemetryPacket); + // Here you would actually do something with the telemetry, like save it or display it + } + else + { + ESP_LOGW(TAG, "Telemetry packet too small (%u bytes)", payloadSize); + } + break; + case DownlinkPacketType_Ping: + ESP_LOGI(TAG, "Ping packet received!"); + // Optionally respond with pong here + break; + case DownlinkPacketType_ACK: + ESP_LOGI(TAG, "ACK packet received!"); + break; + default: + ESP_LOGW(TAG, "Unknown packet type: %u", down.packetType); + break; + } + + uint32_t crc = esp_rom_crc32_le(0, &(buf[0]) + sizeof(DownBoundPacket), payloadSize); + + + send_ack(down.packetIndex, crc); +} + +void lora_comms_task(void *pvParameters) +{ + const int64_t interval_us = 100000; // 100 ms + int64_t start_time, end_time, elapsed; + + LoRaInit(); + int8_t txPowerInDbm = 20; + uint32_t frequencyInHz = 869525000; + + ESP_LOGW(TAG, "Enable TCXO"); + float tcxoVoltage = 2.2; + bool useRegulatorLDO = true; + + LoRaDebugPrint(false); + if (LoRaBegin(frequencyInHz, txPowerInDbm, tcxoVoltage, useRegulatorLDO) != 0) + { + ESP_LOGE(TAG, "Does not recognize the module"); + while (1) + { + vTaskDelay(1); + } + } + + uint8_t spreadingFactor = 6; + uint8_t bandwidth = SX126X_LORA_BW_250_0; + uint8_t codingRate = SX126X_LORA_CR_4_8; + uint16_t preambleLength = 8; + bool crcOn = true; + bool invertIrq = false; + + LoRaConfig(spreadingFactor, bandwidth, codingRate, preambleLength, 0, crcOn, invertIrq); + + uint8_t bufIn[256]; + + while (1) + { + start_time = esp_timer_get_time(); + + uint8_t rxLen = LoRaReceive(bufIn, sizeof(bufIn)); + if (rxLen > 0) + { + ESP_LOGI(TAG, "%d byte packet received", rxLen); + + int8_t rssi, snr; + GetPacketStatus(&rssi, &snr); + ESP_LOGI(TAG, "rssi=%d[dBm] snr=%d[dB]", rssi, snr); + + handle_downlink_packet(bufIn, rxLen); + } + + int lost = GetPacketLost(); + if (lost != 0) + { + ESP_LOGW(TAG, "%d packets lost", lost); + } + + end_time = esp_timer_get_time(); + elapsed = end_time - start_time; + + if (elapsed < interval_us) + { + vTaskDelay(pdMS_TO_TICKS((interval_us - elapsed) / 1000)); + } + } +} diff --git a/main/radio.h b/main/radio.h new file mode 100644 index 0000000..f7b9bcb --- /dev/null +++ b/main/radio.h @@ -0,0 +1,19 @@ +#ifndef RADIO_COMPONENT +#define RADIO_COMPONENT + +#define LORA_POWER_LOW 2 +#define LORA_POWER_HIGH 20 +#define LORA_POWER_MAX_MAYBE_UNSAFE 22 + +#define LORA_TX_POWER LORA_POWER_LOW + +#define TAG_RADIO "RADIO" + +#include "packets.h" + +void lora_comms_task(void *pvParameters); + +extern TelemetryPacket telemetryPacket; +extern uint8_t packetReadiness; + +#endif \ No newline at end of file diff --git a/main/sx1262.c b/main/sx1262.c new file mode 100644 index 0000000..ebe18f9 --- /dev/null +++ b/main/sx1262.c @@ -0,0 +1,970 @@ +#include +#include +#include +#include +#include + +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" + +#include +#include +#include "esp_log.h" +#include "buscfg.h" + +#include "sx1262.h" + +#define TAG "SX1262" + +#define HOST_ID SPI3_HOST + +static spi_device_handle_t SpiHandle; + +// Global Stuff +static uint8_t PacketParams[6]; +static bool txActive; +static int txLost = 0; +static bool debugPrint; +static int SX126x_SPI_SELECT; +static int SX126x_BUSY; + +// Arduino compatible macros +#define delayMicroseconds(us) esp_rom_delay_us(us) +#define delay(ms) esp_rom_delay_us(ms*1000) + + +void LoRaErrorDefault(int error) +{ + if (debugPrint) { + ESP_LOGE(TAG, "LoRaErrorDefault=%d", error); + } + while (true) { + vTaskDelay(1); + } +} + +__attribute__ ((weak, alias ("LoRaErrorDefault"))) void LoRaError(int error); + + +void LoRaInit(void) +{ + ESP_LOGI(TAG, "HSPI_MISO_GPIO=%d", HSPI_MISO_GPIO); + ESP_LOGI(TAG, "HSPI_MOSI_GPIO=%d", HSPI_MOSI_GPIO); + ESP_LOGI(TAG, "HSPI_SCK_GPIO=%d", HSPI_SCK_GPIO); + ESP_LOGI(TAG, "HSPI_LORA_CS=%d", HSPI_LORA_CS); + ESP_LOGI(TAG, "LORA_BUSY=%d", LORA_BUSY); + + SX126x_SPI_SELECT = HSPI_LORA_CS; + SX126x_BUSY = LORA_BUSY; + + txActive = false; + debugPrint = false; + + gpio_reset_pin(LORA_RESET); + gpio_set_direction(LORA_RESET, GPIO_MODE_OUTPUT); + gpio_set_level(LORA_RESET, 1); + + gpio_reset_pin(SX126x_SPI_SELECT); + gpio_set_direction(SX126x_SPI_SELECT, GPIO_MODE_OUTPUT); + gpio_set_level(SX126x_SPI_SELECT, 1); + + gpio_reset_pin(SX126x_BUSY); + gpio_set_direction(SX126x_BUSY, GPIO_MODE_INPUT); + + spi_bus_config_t spi_bus_config = { + .sclk_io_num = HSPI_SCK_GPIO, + .mosi_io_num = HSPI_MOSI_GPIO, + .miso_io_num = HSPI_MISO_GPIO, + .quadwp_io_num = -1, + .quadhd_io_num = -1 + }; + + esp_err_t ret; + spi_device_interface_config_t devcfg = { + .clock_speed_hz = 9000000, + .mode = 0, + .spics_io_num = HSPI_LORA_CS, + .queue_size = 7, + .flags = 0, + .pre_cb = NULL + }; + //spi_device_handle_t handle; + ret = spi_bus_add_device( HOST_ID, &devcfg, &SpiHandle); + ESP_LOGI(TAG, "spi_bus_add_device=%d",ret); + assert(ret==ESP_OK); +} + +void spi_write_byte(uint8_t* Dataout, size_t DataLength ) +{ + spi_transaction_t SPITransaction; + + if ( DataLength > 0 ) { + memset( &SPITransaction, 0, sizeof( spi_transaction_t ) ); + SPITransaction.length = DataLength * 8; + SPITransaction.tx_buffer = Dataout; + SPITransaction.rx_buffer = NULL; + spi_device_transmit( SpiHandle, &SPITransaction ); + } + + return; +} + +void spi_read_byte(uint8_t* Datain, uint8_t* Dataout, size_t DataLength ) +{ + spi_transaction_t SPITransaction; + + if ( DataLength > 0 ) { + memset( &SPITransaction, 0, sizeof( spi_transaction_t ) ); + SPITransaction.length = DataLength * 8; + SPITransaction.tx_buffer = Dataout; + SPITransaction.rx_buffer = Datain; + spi_device_transmit( SpiHandle, &SPITransaction ); + } + + return; +} + +uint8_t spi_transfer(uint8_t address) +{ + uint8_t datain[1]; + uint8_t dataout[1]; + dataout[0] = address; + //spi_write_byte(dataout, 1 ); + spi_read_byte(datain, dataout, 1 ); + return datain[0]; +} + + +int16_t LoRaBegin(uint32_t frequencyInHz, int8_t txPowerInDbm, float tcxoVoltage, bool useRegulatorLDO) +{ + if ( txPowerInDbm > 22 ) + txPowerInDbm = 22; + if ( txPowerInDbm < -3 ) + txPowerInDbm = -3; + + Reset(); + + uint8_t wk[2]; + ReadRegister(SX126X_REG_LORA_SYNC_WORD_MSB, wk, 2); // 0x0740 + uint16_t syncWord = (wk[0] << 8) + wk[1]; + ESP_LOGI(TAG, "syncWord=0x%x", syncWord); + if (syncWord != SX126X_SYNC_WORD_PUBLIC && syncWord != SX126X_SYNC_WORD_PRIVATE) { + ESP_LOGE(TAG, "SX126x error, maybe no SPI connection"); + return ERR_INVALID_MODE; + } + + ESP_LOGI(TAG, "SX126x installed"); + SetStandby(SX126X_STANDBY_RC); + + SetDio2AsRfSwitchCtrl(true); + ESP_LOGI(TAG, "tcxoVoltage=%f", tcxoVoltage); + // set TCXO control, if requested + if(tcxoVoltage > 0.0) { + SetDio3AsTcxoCtrl(tcxoVoltage, RADIO_TCXO_SETUP_TIME); // Configure the radio to use a TCXO controlled by DIO3 + } + + Calibrate( SX126X_CALIBRATE_IMAGE_ON + | SX126X_CALIBRATE_ADC_BULK_P_ON + | SX126X_CALIBRATE_ADC_BULK_N_ON + | SX126X_CALIBRATE_ADC_PULSE_ON + | SX126X_CALIBRATE_PLL_ON + | SX126X_CALIBRATE_RC13M_ON + | SX126X_CALIBRATE_RC64K_ON + ); + + ESP_LOGI(TAG, "useRegulatorLDO=%d", useRegulatorLDO); + if (useRegulatorLDO) { + SetRegulatorMode(SX126X_REGULATOR_LDO); // set regulator mode: LDO + } else { + SetRegulatorMode(SX126X_REGULATOR_DC_DC); // set regulator mode: DC-DC + } + + SetBufferBaseAddress(0, 0); +#if 0 + // SX1261_TRANCEIVER + SetPaConfig(0x06, 0x00, 0x01, 0x01); // PA Optimal Settings +15 dBm + // SX1262_TRANCEIVER + SetPaConfig(0x04, 0x07, 0x00, 0x01); // PA Optimal Settings +22 dBm + // SX1268_TRANCEIVER + SetPaConfig(0x04, 0x07, 0x00, 0x01); // PA Optimal Settings +22 dBm +#endif + SetPaConfig(0x04, 0x07, 0x00, 0x01); // PA Optimal Settings +22 dBm + SetOvercurrentProtection(60.0); // current max 60mA for the whole device + SetPowerConfig(txPowerInDbm, SX126X_PA_RAMP_200U); //0 fuer Empfaenger + SetRfFrequency(frequencyInHz); + return ERR_NONE; +} + +void FixInvertedIQ(uint8_t iqConfig) +{ + // fixes IQ configuration for inverted IQ + // see SX1262/SX1268 datasheet, chapter 15 Known Limitations, section 15.4 for details + // When exchanging LoRa packets with inverted IQ polarity, some packet losses may be observed for longer packets. + // Workaround: Bit 2 at address 0x0736 must be set to: + // “0” when using inverted IQ polarity (see the SetPacketParam(...) command) + // “1” when using standard IQ polarity + + // read current IQ configuration + uint8_t iqConfigCurrent = 0; + ReadRegister(SX126X_REG_IQ_POLARITY_SETUP, &iqConfigCurrent, 1); // 0x0736 + + // set correct IQ configuration + //if(iqConfig == SX126X_LORA_IQ_STANDARD) { + if(iqConfig == SX126X_LORA_IQ_INVERTED) { + iqConfigCurrent &= 0xFB; // using inverted IQ polarity + } else { + iqConfigCurrent |= 0x04; // using standard IQ polarity + } + + // update with the new value + WriteRegister(SX126X_REG_IQ_POLARITY_SETUP, &iqConfigCurrent, 1); // 0x0736 +} + + +void LoRaConfig(uint8_t spreadingFactor, uint8_t bandwidth, uint8_t codingRate, uint16_t preambleLength, uint8_t payloadLen, bool crcOn, bool invertIrq) +{ + SetStopRxTimerOnPreambleDetect(false); + SetLoRaSymbNumTimeout(0); + SetPacketType(SX126X_PACKET_TYPE_LORA); // SX126x.ModulationParams.PacketType : MODEM_LORA + uint8_t ldro = 0; // LowDataRateOptimize OFF + SetModulationParams(spreadingFactor, bandwidth, codingRate, ldro); + + PacketParams[0] = (preambleLength >> 8) & 0xFF; + PacketParams[1] = preambleLength; + if ( payloadLen ) + { + PacketParams[2] = 0x01; // Fixed length packet (implicit header) + PacketParams[3] = payloadLen; + } + else + { + PacketParams[2] = 0x00; // Variable length packet (explicit header) + PacketParams[3] = 0xFF; + } + + if ( crcOn ) + PacketParams[4] = SX126X_LORA_CRC_ON; + else + PacketParams[4] = SX126X_LORA_CRC_OFF; + + if ( invertIrq ) + PacketParams[5] = 0x01; // Inverted LoRa I and Q signals setup + else + PacketParams[5] = 0x00; // Standard LoRa I and Q signals setup + + // fixes IQ configuration for inverted IQ + FixInvertedIQ(PacketParams[5]); + + WriteCommand(SX126X_CMD_SET_PACKET_PARAMS, PacketParams, 6); // 0x8C + + // Do not use DIO interruptst + SetDioIrqParams(SX126X_IRQ_ALL, //all interrupts enabled + SX126X_IRQ_NONE, //interrupts on DIO1 + SX126X_IRQ_NONE, //interrupts on DIO2 + SX126X_IRQ_NONE //interrupts on DIO3 + ); + + + ESP_LOGI(TAG, "Almost done setting LoRa"); + // Receive state no receive timeoout + SetRx(0xFFFFFF); +} + + +void LoRaDebugPrint(bool enable) +{ + debugPrint = enable; +} + + +uint8_t LoRaReceive(uint8_t *pData, int16_t len) +{ + uint8_t rxLen = 0; + uint16_t irqRegs = GetIrqStatus(); + //uint8_t status = GetStatus(); + + if( irqRegs & SX126X_IRQ_RX_DONE ) + { + //ClearIrqStatus(SX126X_IRQ_RX_DONE); + ClearIrqStatus(SX126X_IRQ_ALL); + rxLen = ReadBuffer(pData, len); + } + + return rxLen; +} + + +bool LoRaSend(uint8_t *pData, int16_t len, uint8_t mode) +{ + uint16_t irqStatus; + bool rv = false; + + if ( txActive == false ) + { + txActive = true; + if (PacketParams[2] == 0x00) { // Variable length packet (explicit header) + PacketParams[3] = len; + } + WriteCommand(SX126X_CMD_SET_PACKET_PARAMS, PacketParams, 6); // 0x8C + + //ClearIrqStatus(SX126X_IRQ_TX_DONE | SX126X_IRQ_TIMEOUT); + ClearIrqStatus(SX126X_IRQ_ALL); + + WriteBuffer(pData, len); + SetTx(500); + + if ( mode & SX126x_TXMODE_SYNC ) + { + irqStatus = GetIrqStatus(); + while ( (!(irqStatus & SX126X_IRQ_TX_DONE)) && (!(irqStatus & SX126X_IRQ_TIMEOUT)) ) + { + delay(1); + irqStatus = GetIrqStatus(); + } + if (debugPrint) { + ESP_LOGI(TAG, "irqStatus=0x%x", irqStatus); + if (irqStatus & SX126X_IRQ_TX_DONE) { + ESP_LOGI(TAG, "SX126X_IRQ_TX_DONE"); + } + if (irqStatus & SX126X_IRQ_TIMEOUT) { + ESP_LOGI(TAG, "SX126X_IRQ_TIMEOUT"); + } + } + txActive = false; + + SetRx(0xFFFFFF); + + if ( irqStatus & SX126X_IRQ_TX_DONE) { + rv = true; + } + } + else + { + rv = true; + } + } + if (debugPrint) { + ESP_LOGI(TAG, "Send rv=0x%x", rv); + } + if (rv == false) txLost++; + return rv; +} + + +bool ReceiveMode(void) +{ + uint16_t irq; + bool rv = false; + + if ( txActive == false ) + { + rv = true; + } + else + { + irq = GetIrqStatus(); + if ( irq & (SX126X_IRQ_TX_DONE | SX126X_IRQ_TIMEOUT) ) + { + SetRx(0xFFFFFF); + txActive = false; + rv = true; + } + } + + return rv; +} + + +void GetPacketStatus(int8_t *rssiPacket, int8_t *snrPacket) +{ + uint8_t buf[4]; + ReadCommand( SX126X_CMD_GET_PACKET_STATUS, buf, 4 ); // 0x14 + *rssiPacket = (buf[3] >> 1) * -1; + ( buf[2] < 128 ) ? ( *snrPacket = buf[2] >> 2 ) : ( *snrPacket = ( ( buf[2] - 256 ) >> 2 ) ); +} + + +void SetTxPower(int8_t txPowerInDbm) +{ + SetPowerConfig(txPowerInDbm, SX126X_PA_RAMP_200U); +} + + +void Reset(void) +{ + delay(10); + gpio_set_level(LORA_RESET, 0); + delay(20); + gpio_set_level(LORA_RESET, 1); + delay(10); + // ensure BUSY is low (state meachine ready) + WaitForIdle(BUSY_WAIT, "Reset", true); +} + + +void Wakeup(void) +{ + GetStatus(); +} + + +void SetStandby(uint8_t mode) +{ + uint8_t data = mode; + WriteCommand(SX126X_CMD_SET_STANDBY, &data, 1); // 0x80 +} + + +uint8_t GetStatus(void) +{ + uint8_t rv; + ReadCommand(SX126X_CMD_GET_STATUS, &rv, 1); // 0xC0 + return rv; +} + + +void SetDio3AsTcxoCtrl(float voltage, uint32_t delay) +{ + uint8_t buf[4]; + + //buf[0] = tcxoVoltage & 0x07; + if(fabs(voltage - 1.6) <= 0.001) { + buf[0] = SX126X_DIO3_OUTPUT_1_6; + } else if(fabs(voltage - 1.7) <= 0.001) { + buf[0] = SX126X_DIO3_OUTPUT_1_7; + } else if(fabs(voltage - 1.8) <= 0.001) { + buf[0] = SX126X_DIO3_OUTPUT_1_8; + } else if(fabs(voltage - 2.2) <= 0.001) { + buf[0] = SX126X_DIO3_OUTPUT_2_2; + } else if(fabs(voltage - 2.4) <= 0.001) { + buf[0] = SX126X_DIO3_OUTPUT_2_4; + } else if(fabs(voltage - 2.7) <= 0.001) { + buf[0] = SX126X_DIO3_OUTPUT_2_7; + } else if(fabs(voltage - 3.0) <= 0.001) { + buf[0] = SX126X_DIO3_OUTPUT_3_0; + } else { + buf[0] = SX126X_DIO3_OUTPUT_3_3; + } + + uint32_t delayValue = (float)delay / 15.625; + buf[1] = ( uint8_t )( ( delayValue >> 16 ) & 0xFF ); + buf[2] = ( uint8_t )( ( delayValue >> 8 ) & 0xFF ); + buf[3] = ( uint8_t )( delayValue & 0xFF ); + + WriteCommand(SX126X_CMD_SET_DIO3_AS_TCXO_CTRL, buf, 4); // 0x97 +} + + +void Calibrate(uint8_t calibParam) +{ + uint8_t data = calibParam; + WriteCommand(SX126X_CMD_CALIBRATE, &data, 1); // 0x89 +} + + +void SetDio2AsRfSwitchCtrl(uint8_t enable) +{ + uint8_t data = enable; + WriteCommand(SX126X_CMD_SET_DIO2_AS_RF_SWITCH_CTRL, &data, 1); // 0x9D +} + + +void SetRfFrequency(uint32_t frequency) +{ + uint8_t buf[4]; + uint32_t freq = 0; + + CalibrateImage(frequency); + + freq = (uint32_t)((double)frequency / (double)FREQ_STEP); + buf[0] = (uint8_t)((freq >> 24) & 0xFF); + buf[1] = (uint8_t)((freq >> 16) & 0xFF); + buf[2] = (uint8_t)((freq >> 8) & 0xFF); + buf[3] = (uint8_t)(freq & 0xFF); + WriteCommand(SX126X_CMD_SET_RF_FREQUENCY, buf, 4); // 0x86 +} + + +void CalibrateImage(uint32_t frequency) +{ + uint8_t calFreq[2]; + + if( frequency> 900000000 ) + { + calFreq[0] = 0xE1; + calFreq[1] = 0xE9; + } + else if( frequency > 850000000 ) + { + calFreq[0] = 0xD7; + calFreq[1] = 0xDB; + } + else if( frequency > 770000000 ) + { + calFreq[0] = 0xC1; + calFreq[1] = 0xC5; + } + else if( frequency > 460000000 ) + { + calFreq[0] = 0x75; + calFreq[1] = 0x81; + } + else if( frequency > 425000000 ) + { + calFreq[0] = 0x6B; + calFreq[1] = 0x6F; + } + WriteCommand(SX126X_CMD_CALIBRATE_IMAGE, calFreq, 2); // 0x98 +} + + +void SetRegulatorMode(uint8_t mode) +{ + uint8_t data = mode; + WriteCommand(SX126X_CMD_SET_REGULATOR_MODE, &data, 1); // 0x96 +} + + +void SetBufferBaseAddress(uint8_t txBaseAddress, uint8_t rxBaseAddress) +{ + uint8_t buf[2]; + + buf[0] = txBaseAddress; + buf[1] = rxBaseAddress; + WriteCommand(SX126X_CMD_SET_BUFFER_BASE_ADDRESS, buf, 2); // 0x8F +} + + +void SetPowerConfig(int8_t power, uint8_t rampTime) +{ + uint8_t buf[2]; + + if( power > 22 ) + { + power = 22; + } + else if( power < -3 ) + { + power = -3; + } + + buf[0] = power; + buf[1] = ( uint8_t )rampTime; + WriteCommand(SX126X_CMD_SET_TX_PARAMS, buf, 2); // 0x8E +} + + +void SetPaConfig(uint8_t paDutyCycle, uint8_t hpMax, uint8_t deviceSel, uint8_t paLut) +{ + uint8_t buf[4]; + + buf[0] = paDutyCycle; + buf[1] = hpMax; + buf[2] = deviceSel; + buf[3] = paLut; + WriteCommand(SX126X_CMD_SET_PA_CONFIG, buf, 4); // 0x95 +} + + +void SetOvercurrentProtection(float currentLimit) +{ + if((currentLimit >= 0.0) && (currentLimit <= 140.0)) { + uint8_t buf[1]; + buf[0] = (uint8_t)(currentLimit / 2.5); + WriteRegister(SX126X_REG_OCP_CONFIGURATION, buf, 1); // 0x08E7 + } +} + +void SetSyncWord(int16_t sync) { + uint8_t buf[2]; + + buf[0] = (uint8_t)((sync >> 8) & 0x00FF); + buf[1] = (uint8_t)(sync & 0x00FF); + WriteRegister(SX126X_REG_LORA_SYNC_WORD_MSB, buf, 2); // 0x0740 +} + +void SetDioIrqParams +( uint16_t irqMask, uint16_t dio1Mask, uint16_t dio2Mask, uint16_t dio3Mask ) +{ + uint8_t buf[8]; + + buf[0] = (uint8_t)((irqMask >> 8) & 0x00FF); + buf[1] = (uint8_t)(irqMask & 0x00FF); + buf[2] = (uint8_t)((dio1Mask >> 8) & 0x00FF); + buf[3] = (uint8_t)(dio1Mask & 0x00FF); + buf[4] = (uint8_t)((dio2Mask >> 8) & 0x00FF); + buf[5] = (uint8_t)(dio2Mask & 0x00FF); + buf[6] = (uint8_t)((dio3Mask >> 8) & 0x00FF); + buf[7] = (uint8_t)(dio3Mask & 0x00FF); + WriteCommand(SX126X_CMD_SET_DIO_IRQ_PARAMS, buf, 8); // 0x08 +} + + +void SetStopRxTimerOnPreambleDetect(bool enable) +{ + ESP_LOGI(TAG, "SetStopRxTimerOnPreambleDetect enable=%d", enable); + //uint8_t data = (uint8_t)enable; + uint8_t data = 0; + if (enable) data = 1; + WriteCommand(SX126X_CMD_STOP_TIMER_ON_PREAMBLE, &data, 1); // 0x9F +} + + +void SetLoRaSymbNumTimeout(uint8_t SymbNum) +{ + uint8_t data = SymbNum; + WriteCommand(SX126X_CMD_SET_LORA_SYMB_NUM_TIMEOUT, &data, 1); // 0xA0 +} + + +void SetPacketType(uint8_t packetType) +{ + uint8_t data = packetType; + WriteCommand(SX126X_CMD_SET_PACKET_TYPE, &data, 1); // 0x01 +} + + +void SetModulationParams(uint8_t spreadingFactor, uint8_t bandwidth, uint8_t codingRate, uint8_t lowDataRateOptimize) +{ + uint8_t data[4]; + //currently only LoRa supported + data[0] = spreadingFactor; + data[1] = bandwidth; + data[2] = codingRate; + data[3] = lowDataRateOptimize; + WriteCommand(SX126X_CMD_SET_MODULATION_PARAMS, data, 4); // 0x8B +} + + +void SetCadParams(uint8_t cadSymbolNum, uint8_t cadDetPeak, uint8_t cadDetMin, uint8_t cadExitMode, uint32_t cadTimeout) +{ + uint8_t data[7]; + data[0] = cadSymbolNum; + data[1] = cadDetPeak; + data[2] = cadDetMin; + data[3] = cadExitMode; + data[4] = (uint8_t)((cadTimeout >> 16) & 0xFF); + data[5] = (uint8_t)((cadTimeout >> 8) & 0xFF); + data[6] = (uint8_t)(cadTimeout & 0xFF); + WriteCommand(SX126X_CMD_SET_CAD_PARAMS, data, 7); // 0x88 +} + + +void SetCad() +{ + uint8_t data = 0; + WriteCommand(SX126X_CMD_SET_CAD, &data, 0); // 0xC5 +} + + +uint16_t GetIrqStatus( void ) +{ + uint8_t data[3]; + ReadCommand(SX126X_CMD_GET_IRQ_STATUS, data, 3); // 0x12 + return (data[1] << 8) | data[2]; +} + + +void ClearIrqStatus(uint16_t irq) +{ + uint8_t buf[2]; + + buf[0] = (uint8_t)(((uint16_t)irq >> 8) & 0x00FF); + buf[1] = (uint8_t)((uint16_t)irq & 0x00FF); + WriteCommand(SX126X_CMD_CLEAR_IRQ_STATUS, buf, 2); // 0x02 +} + + +void SetRx(uint32_t timeout) +{ + if (debugPrint) { + ESP_LOGI(TAG, "----- SetRx timeout=%"PRIu32, timeout); + } + SetStandby(SX126X_STANDBY_RC); + uint8_t buf[3]; + buf[0] = (uint8_t)((timeout >> 16) & 0xFF); + buf[1] = (uint8_t)((timeout >> 8) & 0xFF); + buf[2] = (uint8_t)(timeout & 0xFF); + WriteCommand(SX126X_CMD_SET_RX, buf, 3); // 0x82 + + for(int retry=0;retry<10;retry++) { + if ((GetStatus() & 0x70) == 0x50) break; + delay(1); + } + if ((GetStatus() & 0x70) != 0x50) { + ESP_LOGE(TAG, "SetRx Illegal Status"); + LoRaError(ERR_INVALID_SETRX_STATE); + } +} + + +void SetTx(uint32_t timeoutInMs) +{ + if (debugPrint) { + ESP_LOGI(TAG, "----- SetTx timeoutInMs=%"PRIu32, timeoutInMs); + } + SetStandby(SX126X_STANDBY_RC); + uint8_t buf[3]; + uint32_t tout = timeoutInMs; + if (timeoutInMs != 0) { + uint32_t timeoutInUs = timeoutInMs * 1000; + tout = (uint32_t)(timeoutInUs / 0.015625); + } + if (debugPrint) { + ESP_LOGI(TAG, "SetTx timeoutInMs=%"PRIu32" tout=%"PRIu32, timeoutInMs, tout); + } + buf[0] = (uint8_t)((tout >> 16) & 0xFF); + buf[1] = (uint8_t)((tout >> 8) & 0xFF); + buf[2] = (uint8_t )(tout & 0xFF); + WriteCommand(SX126X_CMD_SET_TX, buf, 3); // 0x83 + + for(int retry=0;retry<10;retry++) { + if ((GetStatus() & 0x70) == 0x60) break; + vTaskDelay(1); + } + if ((GetStatus() & 0x70) != 0x60) { + ESP_LOGE(TAG, "SetTx Illegal Status"); + LoRaError(ERR_INVALID_SETTX_STATE); + } +} + +int GetPacketLost() +{ + return txLost; +} + + +uint8_t GetRssiInst() +{ + uint8_t buf[2]; + ReadCommand( SX126X_CMD_GET_RSSI_INST, buf, 2 ); // 0x15 + return buf[1]; +} + + +void GetRxBufferStatus(uint8_t *payloadLength, uint8_t *rxStartBufferPointer) +{ + uint8_t buf[3]; + ReadCommand( SX126X_CMD_GET_RX_BUFFER_STATUS, buf, 3 ); // 0x13 + *payloadLength = buf[1]; + *rxStartBufferPointer = buf[2]; +} + + +void WaitForIdleBegin(unsigned long timeout, char *text) { + // ensure BUSY is low (state meachine ready) + bool stop = false; + for (int retry=0;retry<10;retry++) { + if (retry == 9) stop = true; + bool ret = WaitForIdle(BUSY_WAIT, text, stop); + if (ret == true) break; + ESP_LOGW(TAG, "WaitForIdle fail retry=%d", retry); + vTaskDelay(1); + } +} + + +bool WaitForIdle(unsigned long timeout, char *text, bool stop) +{ + bool ret = true; + TickType_t start = xTaskGetTickCount(); + delayMicroseconds(1); + while(xTaskGetTickCount() - start < (timeout/portTICK_PERIOD_MS)) { + if (gpio_get_level(SX126x_BUSY) == 0) break; + delayMicroseconds(1); + } + if (gpio_get_level(SX126x_BUSY)) { + if (stop) { + ESP_LOGE(TAG, "WaitForIdle Timeout text=%s timeout=%lu start=%"PRIu32, text, timeout, start); + LoRaError(ERR_IDLE_TIMEOUT); + } else { + ESP_LOGW(TAG, "WaitForIdle Timeout text=%s timeout=%lu start=%"PRIu32, text, timeout, start); + ret = false; + } + } + return ret; +} + + +uint8_t ReadBuffer(uint8_t *rxData, int16_t rxDataLen) +{ + uint8_t offset = 0; + uint8_t payloadLength = 0; + GetRxBufferStatus(&payloadLength, &offset); + if( payloadLength > rxDataLen ) + { + ESP_LOGW(TAG, "ReadBuffer rxDataLen too small. payloadLength=%d rxDataLen=%d", payloadLength, rxDataLen); + return 0; + } + + // ensure BUSY is low (state meachine ready) + WaitForIdle(BUSY_WAIT, "start ReadBuffer", true); + + // start transfer + uint8_t *buf; + buf = malloc(payloadLength+3); + if (buf != NULL) { + buf[0] = SX126X_CMD_READ_BUFFER; // 0x1E + buf[1] = offset; // offset in rx fifo + buf[2] = SX126X_CMD_NOP; + memset(&buf[3], SX126X_CMD_NOP, payloadLength); + spi_read_byte(buf, buf, payloadLength+3); + memcpy(rxData, &buf[3], payloadLength); + free(buf); + } else { + ESP_LOGE(TAG, "ReadBuffer malloc fail"); + payloadLength = 0; + } + + // wait for BUSY to go low + WaitForIdle(BUSY_WAIT, "end ReadBuffer", false); + + return payloadLength; +} + + +void WriteBuffer(uint8_t *txData, int16_t txDataLen) +{ + // ensure BUSY is low (state meachine ready) + WaitForIdle(BUSY_WAIT, "start WriteBuffer", true); + + // start transfer + uint8_t *buf; + buf = malloc(txDataLen+2); + if (buf != NULL) { + buf[0] = SX126X_CMD_WRITE_BUFFER; // 0x0E + buf[1] = 0; // offset in tx fifo + memcpy(&buf[2], txData, txDataLen); + spi_write_byte(buf, txDataLen+2); + free(buf); + } else { + ESP_LOGE(TAG, "WriteBuffer malloc fail"); + } + + // wait for BUSY to go low + WaitForIdle(BUSY_WAIT, "end WriteBuffer", false); +} + + +void WriteRegister(uint16_t reg, uint8_t* data, uint8_t numBytes) { + // ensure BUSY is low (state meachine ready) + WaitForIdle(BUSY_WAIT, "start WriteRegister", true); + + if(debugPrint) { + ESP_LOGI(TAG, "WriteRegister: REG=0x%02x", reg); + for(uint8_t n = 0; n < numBytes; n++) { + ESP_LOGI(TAG, "DataOut:%02x ", data[n]); + } + } + + // start transfer + uint8_t buf[16]; + buf[0] = SX126X_CMD_WRITE_REGISTER; + buf[1] = (reg & 0xFF00) >> 8; + buf[2] = reg & 0xff; + memcpy(&buf[3], data, numBytes); + spi_write_byte(buf, 3 + numBytes); + + // wait for BUSY to go low + WaitForIdle(BUSY_WAIT, "end WriteRegister", false); +} + + +void ReadRegister(uint16_t reg, uint8_t* data, uint8_t numBytes) { + // ensure BUSY is low (state meachine ready) + WaitForIdle(BUSY_WAIT, "start ReadRegister", true); + + if(debugPrint) { + ESP_LOGI(TAG, "ReadRegister: REG=0x%02x", reg); + } + + // start transfer + uint8_t buf[16]; + memset(buf, SX126X_CMD_NOP, sizeof(buf)); + buf[0] = SX126X_CMD_READ_REGISTER; + buf[1] = (reg & 0xFF00) >> 8; + buf[2] = reg & 0xff; + spi_read_byte(buf, buf, 4 + numBytes); + memcpy(data, &buf[4], numBytes); + if(debugPrint) { + for(uint8_t n = 0; n < numBytes; n++) { + ESP_LOGI(TAG, "DataIn:%02x ", data[n]); + } + } + + // wait for BUSY to go low + WaitForIdle(BUSY_WAIT, "end ReadRegister", false); +} + +// WriteCommand with retry +void WriteCommand(uint8_t cmd, uint8_t* data, uint8_t numBytes) { + uint8_t status; + for (int retry=1; retry<10; retry++) { + status = WriteCommand2(cmd, data, numBytes); + ESP_LOGD(TAG, "status=%02x", status); + if (status == 0) break; + ESP_LOGW(TAG, "WriteCommand2 status=%02x retry=%d", status, retry); + } + if (status != 0) { + ESP_LOGE(TAG, "SPI Transaction error:0x%02x", status); + LoRaError(ERR_SPI_TRANSACTION); + } +} + +uint8_t WriteCommand2(uint8_t cmd, uint8_t* data, uint8_t numBytes) { + // ensure BUSY is low (state meachine ready) + WaitForIdle(BUSY_WAIT, "start WriteCommand2", true); + + if(debugPrint) { + ESP_LOGI(TAG, "WriteCommand: CMD=0x%02x", cmd); + } + + // start transfer + uint8_t buf[16]; + buf[0] = cmd; + memcpy(&buf[1], data, numBytes); + spi_read_byte(buf, buf, numBytes + 1); + + uint8_t status = 0; + uint8_t cmd_status = buf[1] & 0xe; + + switch(cmd_status){ + case SX126X_STATUS_CMD_TIMEOUT: + case SX126X_STATUS_CMD_INVALID: + case SX126X_STATUS_CMD_FAILED: + status = cmd_status; + break; + + case 0: + case 7: + status = SX126X_STATUS_SPI_FAILED; + break; + // default: break; // success + } + + // wait for BUSY to go low + WaitForIdle(BUSY_WAIT, "end WriteCommand2", false); + return status; +} + + +void ReadCommand(uint8_t cmd, uint8_t* data, uint8_t numBytes) { + // ensure BUSY is low (state meachine ready) + WaitForIdleBegin(BUSY_WAIT, "start ReadCommand"); + + if(debugPrint) { + ESP_LOGI(TAG, "ReadCommand: CMD=0x%02x", cmd); + } + + // start transfer + uint8_t buf[16]; + memset(buf, SX126X_CMD_NOP, sizeof(buf)); + buf[0] = cmd; + spi_read_byte(buf, buf, 1 + numBytes); + if (data != NULL && numBytes) + memcpy(data, &buf[1], numBytes); + + // wait for BUSY to go low + vTaskDelay(1); + WaitForIdle(BUSY_WAIT, "end ReadCommand", false); +} \ No newline at end of file diff --git a/main/sx1262.h b/main/sx1262.h new file mode 100644 index 0000000..08ad225 --- /dev/null +++ b/main/sx1262.h @@ -0,0 +1,434 @@ +#ifndef _RA01S_H +#define _RA01S_H + +#include "driver/spi_master.h" + +//return values +#define ERR_NONE 0 +#define ERR_PACKET_TOO_LONG 1 +#define ERR_UNKNOWN 2 +#define ERR_TX_TIMEOUT 3 +#define ERR_RX_TIMEOUT 4 +#define ERR_CRC_MISMATCH 5 +#define ERR_WRONG_MODEM 6 +#define ERR_INVALID_BANDWIDTH 7 +#define ERR_INVALID_SPREADING_FACTOR 8 +#define ERR_INVALID_CODING_RATE 9 +#define ERR_INVALID_FREQUENCY_DEVIATION 10 +#define ERR_INVALID_BIT_RATE 11 +#define ERR_INVALID_RX_BANDWIDTH 12 +#define ERR_INVALID_DATA_SHAPING 13 +#define ERR_INVALID_SYNC_WORD 14 +#define ERR_INVALID_OUTPUT_POWER 15 +#define ERR_INVALID_MODE 16 +#define ERR_INVALID_TRANCEIVER 17 +#define ERR_INVALID_SETRX_STATE 18 +#define ERR_INVALID_SETTX_STATE 19 +#define ERR_IDLE_TIMEOUT 20 +#define ERR_SPI_TRANSACTION 21 + +// SX126X physical layer properties +#define XTAL_FREQ ( double )32000000 +#define FREQ_DIV ( double )pow( 2.0, 25.0 ) +#define FREQ_STEP ( double )( XTAL_FREQ / FREQ_DIV ) + +#define LOW 0 +#define HIGH 1 +#define BUSY_WAIT 5000 + +// SX126X Model +#define SX1261_TRANCEIVER 0x01 +#define SX1262_TRANCEIVER 0x02 +#define SX1268_TRANCEIVER 0x08 + +// SX126X SPI commands +// operational modes commands +#define SX126X_CMD_NOP 0x00 +#define SX126X_CMD_SET_SLEEP 0x84 +#define SX126X_CMD_SET_STANDBY 0x80 +#define SX126X_CMD_SET_FS 0xC1 +#define SX126X_CMD_SET_TX 0x83 +#define SX126X_CMD_SET_RX 0x82 +#define SX126X_CMD_STOP_TIMER_ON_PREAMBLE 0x9F +#define SX126X_CMD_SET_RX_DUTY_CYCLE 0x94 +#define SX126X_CMD_SET_CAD 0xC5 +#define SX126X_CMD_SET_TX_CONTINUOUS_WAVE 0xD1 +#define SX126X_CMD_SET_TX_INFINITE_PREAMBLE 0xD2 +#define SX126X_CMD_SET_REGULATOR_MODE 0x96 +#define SX126X_CMD_CALIBRATE 0x89 +#define SX126X_CMD_CALIBRATE_IMAGE 0x98 +#define SX126X_CMD_SET_PA_CONFIG 0x95 +#define SX126X_CMD_SET_RX_TX_FALLBACK_MODE 0x93 + +// register and buffer access commands +#define SX126X_CMD_WRITE_REGISTER 0x0D +#define SX126X_CMD_READ_REGISTER 0x1D +#define SX126X_CMD_WRITE_BUFFER 0x0E +#define SX126X_CMD_READ_BUFFER 0x1E + +// DIO and IRQ control +#define SX126X_CMD_SET_DIO_IRQ_PARAMS 0x08 +#define SX126X_CMD_GET_IRQ_STATUS 0x12 +#define SX126X_CMD_CLEAR_IRQ_STATUS 0x02 +#define SX126X_CMD_SET_DIO2_AS_RF_SWITCH_CTRL 0x9D +#define SX126X_CMD_SET_DIO3_AS_TCXO_CTRL 0x97 + +// RF, modulation and packet commands +#define SX126X_CMD_SET_RF_FREQUENCY 0x86 +#define SX126X_CMD_SET_PACKET_TYPE 0x8A +#define SX126X_CMD_GET_PACKET_TYPE 0x11 +#define SX126X_CMD_SET_TX_PARAMS 0x8E +#define SX126X_CMD_SET_MODULATION_PARAMS 0x8B +#define SX126X_CMD_SET_PACKET_PARAMS 0x8C +#define SX126X_CMD_SET_CAD_PARAMS 0x88 +#define SX126X_CMD_SET_BUFFER_BASE_ADDRESS 0x8F +#define SX126X_CMD_SET_LORA_SYMB_NUM_TIMEOUT 0xA0 + +#define SX126X_PA_CONFIG_SX1261 0x01 +#define SX126X_PA_CONFIG_SX1262 0x00 + +// status commands +#define SX126X_CMD_GET_STATUS 0xC0 +#define SX126X_CMD_GET_RSSI_INST 0x15 +#define SX126X_CMD_GET_RX_BUFFER_STATUS 0x13 +#define SX126X_CMD_GET_PACKET_STATUS 0x14 +#define SX126X_CMD_GET_DEVICE_ERRORS 0x17 +#define SX126X_CMD_CLEAR_DEVICE_ERRORS 0x07 +#define SX126X_CMD_GET_STATS 0x10 +#define SX126X_CMD_RESET_STATS 0x00 + + +// SX126X register map +#define SX126X_REG_HOPPING_ENABLE 0x0385 +#define SX126X_REG_PACKECT_LENGTH 0x0386 +#define SX126X_REG_NB_HOPPING_BLOCKS 0x0387 +#define SX126X_REG_NB_SYMBOLS0 0x0388 +#define SX126X_REG_FREQ0 0x038A +#define SX126X_REG_NB_SYMBOLS15 0x03E2 +#define SX126X_REG_FREQ15 0x03E4 +#define SX126X_REG_DIOX_OUTPUT_ENABLE 0x0580 +#define SX126X_REG_DIOX_INPUT_ENABLE 0x0583 +#define SX126X_REG_DIOX_PILL_UP_CONTROL 0x0584 +#define SX126X_REG_DIOX_PULL_DOWN_CONTROL 0x0585 +#define SX126X_REG_WHITENING_INITIAL_MSB 0x06B8 +#define SX126X_REG_WHITENING_INITIAL_LSB 0x06B9 +#define SX126X_REG_CRC_INITIAL_MSB 0x06BC +#define SX126X_REG_CRC_INITIAL_LSB 0x06BD +#define SX126X_REG_CRC_POLYNOMIAL_MSB 0x06BE +#define SX126X_REG_CRC_POLYNOMIAL_LSB 0x06BF +#define SX126X_REG_SYNC_WORD_0 0x06C0 +#define SX126X_REG_SYNC_WORD_1 0x06C1 +#define SX126X_REG_SYNC_WORD_2 0x06C2 +#define SX126X_REG_SYNC_WORD_3 0x06C3 +#define SX126X_REG_SYNC_WORD_4 0x06C4 +#define SX126X_REG_SYNC_WORD_5 0x06C5 +#define SX126X_REG_SYNC_WORD_6 0x06C6 +#define SX126X_REG_SYNC_WORD_7 0x06C7 +#define SX126X_REG_NODE_ADDRESS 0x06CD +#define SX126X_REG_BROADCAST_ADDRESS 0x06CE +#define SX126X_REG_IQ_POLARITY_SETUP 0x0736 +#define SX126X_REG_LORA_SYNC_WORD_MSB 0x0740 +#define SX126X_REG_LORA_SYNC_WORD_LSB 0x0741 +#define SX126X_REG_RANDOM_NUMBER_0 0x0819 +#define SX126X_REG_RANDOM_NUMBER_1 0x081A +#define SX126X_REG_RANDOM_NUMBER_2 0x081B +#define SX126X_REG_RANDOM_NUMBER_3 0x081C +#define SX126X_REG_TX_MODULETION 0x0889 +#define SX126X_REG_RX_GAIN 0x08AC +#define SX126X_REG_TX_CLAMP_CONFIG 0x08D8 +#define SX126X_REG_OCP_CONFIGURATION 0x08E7 +#define SX126X_REG_RTC_CONTROL 0x0902 +#define SX126X_REG_XTA_TRIM 0x0911 +#define SX126X_REG_XTB_TRIM 0x0912 +#define SX126X_REG_DIO3_OUTPUT_VOLTAGE_CONTROL 0x0920 +#define SX126X_REG_EVENT_MASK 0x0944 + + +// SX126X SPI command variables +//SX126X_CMD_SET_SLEEP +#define SX126X_SLEEP_START_COLD 0b00000000 // 2 2 sleep mode: cold start, configuration is lost (default) +#define SX126X_SLEEP_START_WARM 0b00000100 // 2 2 warm start, configuration is retained +#define SX126X_SLEEP_RTC_OFF 0b00000000 // 0 0 wake on RTC timeout: disabled +#define SX126X_SLEEP_RTC_ON 0b00000001 // 0 0 enabled + +//SX126X_CMD_SET_STANDBY +#define SX126X_STANDBY_RC 0x00 // 7 0 standby mode: 13 MHz RC oscillator +#define SX126X_STANDBY_XOSC 0x01 // 7 0 32 MHz crystal oscillator + +//SX126X_CMD_SET_RX +#define SX126X_RX_TIMEOUT_NONE 0x000000 // 23 0 Rx timeout duration: no timeout (Rx single mode) +#define SX126X_RX_TIMEOUT_INF 0xFFFFFF // 23 0 infinite (Rx continuous mode) + +//SX126X_CMD_STOP_TIMER_ON_PREAMBLE +#define SX126X_STOP_ON_PREAMBLE_OFF 0x00 // 7 0 stop timer on: sync word or header (default) +#define SX126X_STOP_ON_PREAMBLE_ON 0x01 // 7 0 preamble detection + +//SX126X_CMD_SET_REGULATOR_MODE +#define SX126X_REGULATOR_LDO 0x00 // 7 0 set regulator mode: LDO (default) +#define SX126X_REGULATOR_DC_DC 0x01 // 7 0 DC-DC + +//SX126X_CMD_CALIBRATE +#define SX126X_CALIBRATE_IMAGE_OFF 0b00000000 // 6 6 image calibration: disabled +#define SX126X_CALIBRATE_IMAGE_ON 0b01000000 // 6 6 enabled +#define SX126X_CALIBRATE_ADC_BULK_P_OFF 0b00000000 // 5 5 ADC bulk P calibration: disabled +#define SX126X_CALIBRATE_ADC_BULK_P_ON 0b00100000 // 5 5 enabled +#define SX126X_CALIBRATE_ADC_BULK_N_OFF 0b00000000 // 4 4 ADC bulk N calibration: disabled +#define SX126X_CALIBRATE_ADC_BULK_N_ON 0b00010000 // 4 4 enabled +#define SX126X_CALIBRATE_ADC_PULSE_OFF 0b00000000 // 3 3 ADC pulse calibration: disabled +#define SX126X_CALIBRATE_ADC_PULSE_ON 0b00001000 // 3 3 enabled +#define SX126X_CALIBRATE_PLL_OFF 0b00000000 // 2 2 PLL calibration: disabled +#define SX126X_CALIBRATE_PLL_ON 0b00000100 // 2 2 enabled +#define SX126X_CALIBRATE_RC13M_OFF 0b00000000 // 1 1 13 MHz RC osc. calibration: disabled +#define SX126X_CALIBRATE_RC13M_ON 0b00000010 // 1 1 enabled +#define SX126X_CALIBRATE_RC64K_OFF 0b00000000 // 0 0 64 kHz RC osc. calibration: disabled +#define SX126X_CALIBRATE_RC64K_ON 0b00000001 // 0 0 enabled + +//SX126X_CMD_CALIBRATE_IMAGE +#define SX126X_CAL_IMG_430_MHZ_1 0x6B +#define SX126X_CAL_IMG_430_MHZ_2 0x6F +#define SX126X_CAL_IMG_470_MHZ_1 0x75 +#define SX126X_CAL_IMG_470_MHZ_2 0x81 +#define SX126X_CAL_IMG_779_MHZ_1 0xC1 +#define SX126X_CAL_IMG_779_MHZ_2 0xC5 +#define SX126X_CAL_IMG_863_MHZ_1 0xD7 +#define SX126X_CAL_IMG_863_MHZ_2 0xDB +#define SX126X_CAL_IMG_902_MHZ_1 0xE1 +#define SX126X_CAL_IMG_902_MHZ_2 0xE9 + +//SX126X_CMD_SET_PA_CONFIG +#define SX126X_PA_CONFIG_HP_MAX 0x07 +#define SX126X_PA_CONFIG_SX1268 0x01 +#define SX126X_PA_CONFIG_PA_LUT 0x01 + +//SX126X_CMD_SET_RX_TX_FALLBACK_MODE +#define SX126X_RX_TX_FALLBACK_MODE_FS 0x40 // 7 0 after Rx/Tx go to: FS mode +#define SX126X_RX_TX_FALLBACK_MODE_STDBY_XOSC 0x30 // 7 0 standby with crystal oscillator +#define SX126X_RX_TX_FALLBACK_MODE_STDBY_RC 0x20 // 7 0 standby with RC oscillator (default) + +//SX126X_CMD_SET_DIO_IRQ_PARAMS +#define SX126X_IRQ_TIMEOUT 0b1000000000 // 9 9 Rx or Tx timeout +#define SX126X_IRQ_CAD_DETECTED 0b0100000000 // 8 8 channel activity detected +#define SX126X_IRQ_CAD_DONE 0b0010000000 // 7 7 channel activity detection finished +#define SX126X_IRQ_CRC_ERR 0b0001000000 // 6 6 wrong CRC received +#define SX126X_IRQ_HEADER_ERR 0b0000100000 // 5 5 LoRa header CRC error +#define SX126X_IRQ_HEADER_VALID 0b0000010000 // 4 4 valid LoRa header received +#define SX126X_IRQ_SYNC_WORD_VALID 0b0000001000 // 3 3 valid sync word detected +#define SX126X_IRQ_PREAMBLE_DETECTED 0b0000000100 // 2 2 preamble detected +#define SX126X_IRQ_RX_DONE 0b0000000010 // 1 1 packet received +#define SX126X_IRQ_TX_DONE 0b0000000001 // 0 0 packet transmission completed +#define SX126X_IRQ_ALL 0b1111111111 // 9 0 all interrupts +#define SX126X_IRQ_NONE 0b0000000000 // 9 0 no interrupts + +//SX126X_CMD_SET_DIO2_AS_RF_SWITCH_CTRL +#define SX126X_DIO2_AS_IRQ 0x00 // 7 0 DIO2 configuration: IRQ +#define SX126X_DIO2_AS_RF_SWITCH 0x01 // 7 0 RF switch control + +//SX126X_CMD_SET_DIO3_AS_TCXO_CTRL +#define SX126X_DIO3_OUTPUT_1_6 0x00 // 7 0 DIO3 voltage output for TCXO: 1.6 V +#define SX126X_DIO3_OUTPUT_1_7 0x01 // 7 0 1.7 V +#define SX126X_DIO3_OUTPUT_1_8 0x02 // 7 0 1.8 V +#define SX126X_DIO3_OUTPUT_2_2 0x03 // 7 0 2.2 V +#define SX126X_DIO3_OUTPUT_2_4 0x04 // 7 0 2.4 V +#define SX126X_DIO3_OUTPUT_2_7 0x05 // 7 0 2.7 V +#define SX126X_DIO3_OUTPUT_3_0 0x06 // 7 0 3.0 V +#define SX126X_DIO3_OUTPUT_3_3 0x07 // 7 0 3.3 V + +//Radio complete Wake-up Time with TCXO stabilisation time +#define RADIO_TCXO_SETUP_TIME 5000 // [us] + +//SX126X_CMD_SET_PACKET_TYPE +#define SX126X_PACKET_TYPE_GFSK 0x00 // 7 0 packet type: GFSK +#define SX126X_PACKET_TYPE_LORA 0x01 // 7 0 LoRa + +//SX126X_CMD_SET_TX_PARAMS +#define SX126X_PA_RAMP_10U 0x00 // 7 0 ramp time: 10 us +#define SX126X_PA_RAMP_20U 0x01 // 7 0 20 us +#define SX126X_PA_RAMP_40U 0x02 // 7 0 40 us +#define SX126X_PA_RAMP_80U 0x03 // 7 0 80 us +#define SX126X_PA_RAMP_200U 0x04 // 7 0 200 us +#define SX126X_PA_RAMP_800U 0x05 // 7 0 800 us +#define SX126X_PA_RAMP_1700U 0x06 // 7 0 1700 us +#define SX126X_PA_RAMP_3400U 0x07 // 7 0 3400 us + +//SX126X_CMD_SET_MODULATION_PARAMS +#define SX126X_GFSK_FILTER_NONE 0x00 // 7 0 GFSK filter: none +#define SX126X_GFSK_FILTER_GAUSS_0_3 0x08 // 7 0 Gaussian, BT = 0.3 +#define SX126X_GFSK_FILTER_GAUSS_0_5 0x09 // 7 0 Gaussian, BT = 0.5 +#define SX126X_GFSK_FILTER_GAUSS_0_7 0x0A // 7 0 Gaussian, BT = 0.7 +#define SX126X_GFSK_FILTER_GAUSS_1 0x0B // 7 0 Gaussian, BT = 1 +#define SX126X_GFSK_RX_BW_4_8 0x1F // 7 0 GFSK Rx bandwidth: 4.8 kHz +#define SX126X_GFSK_RX_BW_5_8 0x17 // 7 0 5.8 kHz +#define SX126X_GFSK_RX_BW_7_3 0x0F // 7 0 7.3 kHz +#define SX126X_GFSK_RX_BW_9_7 0x1E // 7 0 9.7 kHz +#define SX126X_GFSK_RX_BW_11_7 0x16 // 7 0 11.7 kHz +#define SX126X_GFSK_RX_BW_14_6 0x0E // 7 0 14.6 kHz +#define SX126X_GFSK_RX_BW_19_5 0x1D // 7 0 19.5 kHz +#define SX126X_GFSK_RX_BW_23_4 0x15 // 7 0 23.4 kHz +#define SX126X_GFSK_RX_BW_29_3 0x0D // 7 0 29.3 kHz +#define SX126X_GFSK_RX_BW_39_0 0x1C // 7 0 39.0 kHz +#define SX126X_GFSK_RX_BW_46_9 0x14 // 7 0 46.9 kHz +#define SX126X_GFSK_RX_BW_58_6 0x0C // 7 0 58.6 kHz +#define SX126X_GFSK_RX_BW_78_2 0x1B // 7 0 78.2 kHz +#define SX126X_GFSK_RX_BW_93_8 0x13 // 7 0 93.8 kHz +#define SX126X_GFSK_RX_BW_117_3 0x0B // 7 0 117.3 kHz +#define SX126X_GFSK_RX_BW_156_2 0x1A // 7 0 156.2 kHz +#define SX126X_GFSK_RX_BW_187_2 0x12 // 7 0 187.2 kHz +#define SX126X_GFSK_RX_BW_234_3 0x0A // 7 0 234.3 kHz +#define SX126X_GFSK_RX_BW_312_0 0x19 // 7 0 312.0 kHz +#define SX126X_GFSK_RX_BW_373_6 0x11 // 7 0 373.6 kHz +#define SX126X_GFSK_RX_BW_467_0 0x09 // 7 0 467.0 kHz +#define SX126X_LORA_BW_7_8 0x00 // 7 0 LoRa bandwidth: 7.8 kHz +#define SX126X_LORA_BW_10_4 0x08 // 7 0 10.4 kHz +#define SX126X_LORA_BW_15_6 0x01 // 7 0 15.6 kHz +#define SX126X_LORA_BW_20_8 0x09 // 7 0 20.8 kHz +#define SX126X_LORA_BW_31_25 0x02 // 7 0 31.25 kHz +#define SX126X_LORA_BW_41_7 0x0A // 7 0 41.7 kHz +#define SX126X_LORA_BW_62_5 0x03 // 7 0 62.5 kHz +#define SX126X_LORA_BW_125_0 0x04 // 7 0 125.0 kHz +#define SX126X_LORA_BW_250_0 0x05 // 7 0 250.0 kHz +#define SX126X_LORA_BW_500_0 0x06 // 7 0 500.0 kHz +#define SX126X_LORA_CR_4_5 0x01 // 7 0 LoRa coding rate: 4/5 +#define SX126X_LORA_CR_4_6 0x02 // 7 0 4/6 +#define SX126X_LORA_CR_4_7 0x03 // 7 0 4/7 +#define SX126X_LORA_CR_4_8 0x04 // 7 0 4/8 +#define SX126X_LORA_LOW_DATA_RATE_OPTIMIZE_OFF 0x00 // 7 0 LoRa low data rate optimization: disabled +#define SX126X_LORA_LOW_DATA_RATE_OPTIMIZE_ON 0x01 // 7 0 enabled + +//SX126X_CMD_SET_PACKET_PARAMS +#define SX126X_GFSK_PREAMBLE_DETECT_OFF 0x00 // 7 0 GFSK minimum preamble length before reception starts: detector disabled +#define SX126X_GFSK_PREAMBLE_DETECT_8 0x04 // 7 0 8 bits +#define SX126X_GFSK_PREAMBLE_DETECT_16 0x05 // 7 0 16 bits +#define SX126X_GFSK_PREAMBLE_DETECT_24 0x06 // 7 0 24 bits +#define SX126X_GFSK_PREAMBLE_DETECT_32 0x07 // 7 0 32 bits +#define SX126X_GFSK_ADDRESS_FILT_OFF 0x00 // 7 0 GFSK address filtering: disabled +#define SX126X_GFSK_ADDRESS_FILT_NODE 0x01 // 7 0 node only +#define SX126X_GFSK_ADDRESS_FILT_NODE_BROADCAST 0x02 // 7 0 node and broadcast +#define SX126X_GFSK_PACKET_FIXED 0x00 // 7 0 GFSK packet type: fixed (payload length known in advance to both sides) +#define SX126X_GFSK_PACKET_VARIABLE 0x01 // 7 0 variable (payload length added to packet) +#define SX126X_GFSK_CRC_OFF 0x01 // 7 0 GFSK packet CRC: disabled +#define SX126X_GFSK_CRC_1_BYTE 0x00 // 7 0 1 byte +#define SX126X_GFSK_CRC_2_BYTE 0x02 // 7 0 2 byte +#define SX126X_GFSK_CRC_1_BYTE_INV 0x04 // 7 0 1 byte, inverted +#define SX126X_GFSK_CRC_2_BYTE_INV 0x06 // 7 0 2 byte, inverted +#define SX126X_GFSK_WHITENING_OFF 0x00 // 7 0 GFSK data whitening: disabled +#define SX126X_GFSK_WHITENING_ON 0x01 // 7 0 enabled +#define SX126X_LORA_HEADER_EXPLICIT 0x00 // 7 0 LoRa header mode: explicit +#define SX126X_LORA_HEADER_IMPLICIT 0x01 // 7 0 implicit +#define SX126X_LORA_CRC_OFF 0x00 // 7 0 LoRa CRC mode: disabled +#define SX126X_LORA_CRC_ON 0x01 // 7 0 enabled +#define SX126X_LORA_IQ_STANDARD 0x00 // 7 0 LoRa IQ setup: standard +#define SX126X_LORA_IQ_INVERTED 0x01 // 7 0 inverted + +//SX126X_CMD_SET_CAD_PARAMS +#define SX126X_CAD_ON_1_SYMB 0x00 // 7 0 number of symbols used for CAD: 1 +#define SX126X_CAD_ON_2_SYMB 0x01 // 7 0 2 +#define SX126X_CAD_ON_4_SYMB 0x02 // 7 0 4 +#define SX126X_CAD_ON_8_SYMB 0x03 // 7 0 8 +#define SX126X_CAD_ON_16_SYMB 0x04 // 7 0 16 +#define SX126X_CAD_GOTO_STDBY 0x00 // 7 0 after CAD is done, always go to STDBY_RC mode +#define SX126X_CAD_GOTO_RX 0x01 // 7 0 after CAD is done, go to Rx mode if activity is detected + +//SX126X_CMD_GET_STATUS +#define SX126X_STATUS_MODE_STDBY_RC 0b00100000 // 6 4 current chip mode: STDBY_RC +#define SX126X_STATUS_MODE_STDBY_XOSC 0b00110000 // 6 4 STDBY_XOSC +#define SX126X_STATUS_MODE_FS 0b01000000 // 6 4 FS +#define SX126X_STATUS_MODE_RX 0b01010000 // 6 4 RX +#define SX126X_STATUS_MODE_TX 0b01100000 // 6 4 TX +#define SX126X_STATUS_DATA_AVAILABLE 0b00000100 // 3 1 command status: packet received and data can be retrieved +#define SX126X_STATUS_CMD_TIMEOUT 0b00000110 // 3 1 SPI command timed out +#define SX126X_STATUS_CMD_INVALID 0b00001000 // 3 1 invalid SPI command +#define SX126X_STATUS_CMD_FAILED 0b00001010 // 3 1 SPI command failed to execute +#define SX126X_STATUS_TX_DONE 0b00001100 // 3 1 packet transmission done +#define SX126X_STATUS_SPI_FAILED 0b11111111 // 7 0 SPI transaction failed + +//SX126X_CMD_GET_PACKET_STATUS +#define SX126X_GFSK_RX_STATUS_PREAMBLE_ERR 0b10000000 // 7 7 GFSK Rx status: preamble error +#define SX126X_GFSK_RX_STATUS_SYNC_ERR 0b01000000 // 6 6 sync word error +#define SX126X_GFSK_RX_STATUS_ADRS_ERR 0b00100000 // 5 5 address error +#define SX126X_GFSK_RX_STATUS_CRC_ERR 0b00010000 // 4 4 CRC error +#define SX126X_GFSK_RX_STATUS_LENGTH_ERR 0b00001000 // 3 3 length error +#define SX126X_GFSK_RX_STATUS_ABORT_ERR 0b00000100 // 2 2 abort error +#define SX126X_GFSK_RX_STATUS_PACKET_RECEIVED 0b00000010 // 2 2 packet received +#define SX126X_GFSK_RX_STATUS_PACKET_SENT 0b00000001 // 2 2 packet sent + +//SX126X_CMD_GET_DEVICE_ERRORS +#define SX126X_PA_RAMP_ERR 0b100000000 // 8 8 device errors: PA ramping failed +#define SX126X_PLL_LOCK_ERR 0b001000000 // 6 6 PLL failed to lock +#define SX126X_XOSC_START_ERR 0b000100000 // 5 5 crystal oscillator failed to start +#define SX126X_IMG_CALIB_ERR 0b000010000 // 4 4 image calibration failed +#define SX126X_ADC_CALIB_ERR 0b000001000 // 3 3 ADC calibration failed +#define SX126X_PLL_CALIB_ERR 0b000000100 // 2 2 PLL calibration failed +#define SX126X_RC13M_CALIB_ERR 0b000000010 // 1 1 RC13M calibration failed +#define SX126X_RC64K_CALIB_ERR 0b000000001 // 0 0 RC64K calibration failed + + +// SX126X SPI register variables +//SX126X_REG_LORA_SYNC_WORD_MSB + LSB +#define SX126X_SYNC_WORD_PUBLIC 0x3444 +#define SX126X_SYNC_WORD_PRIVATE 0x1424 + +#define SX126x_TXMODE_ASYNC 0x01 +#define SX126x_TXMODE_SYNC 0x02 +#define SX126x_TXMODE_BACK2RX 0x04 + +// Public function +void LoRaInit(void); +int16_t LoRaBegin(uint32_t frequencyInHz, int8_t txPowerInDbm, float tcxoVoltage, bool useRegulatorLDO); +void LoRaConfig(uint8_t spreadingFactor, uint8_t bandwidth, uint8_t codingRate, uint16_t preambleLength, uint8_t payloadLen, bool crcOn, bool invertIrq); +uint8_t LoRaReceive(uint8_t *pData, int16_t len); +bool LoRaSend(uint8_t *pData, int16_t len, uint8_t mode); +void LoRaDebugPrint(bool enable); + +// Private function +void spi_write_byte(uint8_t* Dataout, size_t DataLength ); +void spi_read_byte(uint8_t* Datain, uint8_t* Dataout, size_t DataLength ); +uint8_t spi_transfer(uint8_t address); + +bool ReceiveMode(void); +void GetPacketStatus(int8_t *rssiPacket, int8_t *snrPacket); +void SetTxPower(int8_t txPowerInDbm); + +void FixInvertedIQ(uint8_t iqConfig); +void SetDio3AsTcxoCtrl(float voltage, uint32_t delay); +void SetDio2AsRfSwitchCtrl(uint8_t enable); +void Reset(void); +void SetStandby(uint8_t mode); +void SetRfFrequency(uint32_t frequency); +void Calibrate(uint8_t calibParam); +void CalibrateImage(uint32_t frequency); +void SetRegulatorMode(uint8_t mode); +void SetBufferBaseAddress(uint8_t txBaseAddress, uint8_t rxBaseAddress); +void SetPowerConfig(int8_t power, uint8_t rampTime); +void SetOvercurrentProtection(float currentLimit); +void SetSyncWord(int16_t sync); +void SetPaConfig(uint8_t paDutyCycle, uint8_t hpMax, uint8_t deviceSel, uint8_t paLut); +void SetDioIrqParams(uint16_t irqMask, uint16_t dio1Mask, uint16_t dio2Mask, uint16_t dio3Mask); +void SetStopRxTimerOnPreambleDetect(bool enable); +void SetLoRaSymbNumTimeout(uint8_t SymbNum); +void SetPacketType(uint8_t packetType); +void SetModulationParams(uint8_t spreadingFactor, uint8_t bandwidth, uint8_t codingRate, uint8_t lowDataRateOptimize); +void SetCadParams(uint8_t cadSymbolNum, uint8_t cadDetPeak, uint8_t cadDetMin, uint8_t cadExitMode, uint32_t cadTimeout); +void SetCad(); +uint8_t GetStatus(void); +uint16_t GetIrqStatus(void); +void ClearIrqStatus(uint16_t irq); +void SetRx(uint32_t timeout); +void SetTx(uint32_t timeoutInMs); +int GetPacketLost(); +uint8_t GetRssiInst(); +void GetRxBufferStatus(uint8_t *payloadLength, uint8_t *rxStartBufferPointer); +void Wakeup(void); +void WaitForIdleBegin(unsigned long timeout, char *text); +bool WaitForIdle(unsigned long timeout, char *text, bool stop); +uint8_t ReadBuffer(uint8_t *rxData, int16_t rxDataLen); +void WriteBuffer(uint8_t *txData, int16_t txDataLen); +void WriteRegister(uint16_t reg, uint8_t* data, uint8_t numBytes); +void ReadRegister(uint16_t reg, uint8_t* data, uint8_t numBytes); +void WriteCommand(uint8_t cmd, uint8_t* data, uint8_t numBytes); +uint8_t WriteCommand2(uint8_t cmd, uint8_t* data, uint8_t numBytes); +void ReadCommand(uint8_t cmd, uint8_t* data, uint8_t numBytes); +void SPItransfer(uint8_t cmd, bool write, uint8_t* dataOut, uint8_t* dataIn, uint8_t numBytes, bool waitForBusy); +void LoRaError(int error); + + +#endif