save some implementation
This commit is contained in:
70
main/hw/buscfg.h
Normal file
70
main/hw/buscfg.h
Normal file
@@ -0,0 +1,70 @@
|
||||
#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 ESP_CONNECTOR_P1 MCP3550_MISO_GPIO
|
||||
#define ESP_CONNECTOR_P2 MCP3550_MOSI_GPIO
|
||||
#define ESP_CONNECTOR_P3 MCP3550_SCK_GPIO
|
||||
#define ESP_CONNECTOR_P4 GPIO_NUM_39
|
||||
#define ESP_CONNECTOR_P5 GPIO_NUM_38
|
||||
#define ESP_CONNECTOR_P6 HSPI_UNKNOWN_CS
|
||||
#define ESP_CONNECTOR_P9 HSPI_MISO_GPIO
|
||||
#define ESP_CONNECTOR_P10 MCP3550_MOSI_GPIO
|
||||
#define ESP_CONNECTOR_P11 MCP3550_SCK_GPIO
|
||||
#define ESP_CONNECTOR_P12 HSPI_SD_CS
|
||||
#define ESP_CONNECTOR_P13 HSPI_LORA_CS
|
||||
#define ESP_CONNECTOR_P17 HWI2C_SDA
|
||||
#define ESP_CONNECTOR_P18 HWI2C_SCL
|
||||
#define ESP_CONNECTOR_P19 I2C2_SDA
|
||||
#define ESP_CONNECTOR_P20 I2C2_SCL
|
||||
#define ESP_CONNECTOR_P25 LORA_DIO1
|
||||
#define ESP_CONNECTOR_P26 LORA_BUSY
|
||||
#define ESP_CONNECTOR_P27 LORA_RXEN_MANUAL
|
||||
#define ESP_CONNECTOR_P28 GPIO_NUM_6
|
||||
#define ESP_CONNECTOR_P29 GPIO_NUM_5
|
||||
#define ESP_CONNECTOR_P30 GPIO_NUM_4
|
||||
#define ESP_CONNECTOR_P47 GPS_RXD
|
||||
#define ESP_CONNECTOR_P48 GPS_TXD
|
||||
#define ESP_CONNECTOR_P51 ESP_RXD0
|
||||
#define ESP_CONNECTOR_P52 ESP_TXD0
|
||||
#define ESP_CONNECTOR_P57 ESP_USB_DP
|
||||
#define ESP_CONNECTOR_P58 ESP_USB_DM
|
||||
|
||||
|
||||
#define HSPI_UNKNOWN_CS GPIO_NUM_42
|
||||
#define LORA_RXEN_MANUAL GPIO_NUM_7
|
||||
|
||||
#define HSPI_MISO_GPIO GPIO_NUM_13
|
||||
#define HSPI_MOSI_GPIO GPIO_NUM_11
|
||||
//#define HSPI_MISO_GPIO GPIO_NUM_11
|
||||
//#define HSPI_MOSI_GPIO GPIO_NUM_13
|
||||
|
||||
#define HSPI_SCK_GPIO GPIO_NUM_12
|
||||
#define HSPI_LORA_CS GPIO_NUM_48
|
||||
#define LORA_DIO1 GPIO_NUM_16
|
||||
#define LORA_BUSY GPIO_NUM_15
|
||||
#define HSPI_SD_CS GPIO_NUM_10
|
||||
|
||||
#define MCP3550_MOSI_GPIO GPIO_NUM_35
|
||||
#define MCP3550_SCK_GPIO GPIO_NUM_36
|
||||
#define MCP3550_MISO_GPIO GPIO_NUM_37
|
||||
|
||||
#define GPS_TXD GPIO_NUM_17
|
||||
#define GPS_RXD GPIO_NUM_18
|
||||
#define GPS_RTS UART_PIN_NO_CHANGE
|
||||
#define GPS_CTS UART_PIN_NO_CHANGE
|
||||
|
||||
#define GPS_UART_NUM UART_NUM_2
|
||||
|
||||
#define HWI2C_SDA GPIO_NUM_8
|
||||
#define HWI2C_SCL GPIO_NUM_9
|
||||
#define I2C2_SDA GPIO_NUM_40
|
||||
#define I2C2_SCL GPIO_NUM_41
|
||||
|
||||
#endif
|
@@ -10,6 +10,22 @@ i2c_device_config_t CCS811_DEV_CFG = {
|
||||
|
||||
i2c_master_dev_handle_t CCS811_DEV_HANDLE;
|
||||
|
||||
void ccs811_getStatus()
|
||||
{
|
||||
uint8_t errorID;
|
||||
uint8_t status;
|
||||
uint8_t hardwareVersion;
|
||||
uint16_t version;
|
||||
uint16_t bootVersion;
|
||||
|
||||
i2c_read_register_8(CCS811_DEV_HANDLE, CCS811_REG_STATUS, &status);
|
||||
i2c_read_register_16(CCS811_DEV_HANDLE, CCS811_REG_FW_APP_VERSION, &version);
|
||||
i2c_read_register_16(CCS811_DEV_HANDLE, CCS811_REG_FW_BOOT_VERSION, &bootVersion);
|
||||
i2c_read_register_8(CCS811_DEV_HANDLE, CCS811_REG_HW_VERSION, &hardwareVersion);
|
||||
i2c_read_register_8(CCS811_DEV_HANDLE, CCS811_REG_ERROR_ID, &errorID);
|
||||
ESP_LOGW(TAG_CCS, "CCS811 status: %d, version: %d, boot version: %d, hardware version: %d, error ID: %d", status, version, bootVersion, hardwareVersion, errorID);
|
||||
}
|
||||
|
||||
void ccs811_init()
|
||||
{
|
||||
ESP_ERROR_CHECK(i2c_master_bus_add_device(i2c0_bus_hdl, &CCS811_DEV_CFG, &CCS811_DEV_HANDLE));
|
||||
@@ -17,30 +33,47 @@ void ccs811_init()
|
||||
mcp23018_set_pin(MCP23018_DEV_HANDLE, MCP_CCS811_POWER, 1);
|
||||
vTaskDelay(10 / portTICK_PERIOD_MS);
|
||||
uint8_t reset_seq[4] = {0x11, 0xE5, 0x72, 0x8A};
|
||||
i2c_write_register(CCS811_DEV_HANDLE, 0xFF, reset_seq, sizeof(reset_seq)); //Reset
|
||||
i2c_write_register(CCS811_DEV_HANDLE, CCS811_REG_SW_RESET, reset_seq, sizeof(reset_seq)); // Reset
|
||||
vTaskDelay(10 / portTICK_PERIOD_MS);
|
||||
uint8_t status;
|
||||
uint16_t version;
|
||||
i2c_read_register_8(CCS811_DEV_HANDLE, 0x00, &status);
|
||||
i2c_read_register_16(CCS811_DEV_HANDLE, 0x24, &version);
|
||||
ESP_LOGW(TAG_CCS, "CCS811 status: %d, version: %d", status, version);
|
||||
i2c_write_register(CCS811_DEV_HANDLE, 0xF4, NULL, 0); //start
|
||||
vTaskDelay(10 / portTICK_PERIOD_MS);
|
||||
i2c_write_register_8(CCS811_DEV_HANDLE, 0x10, 0x0001); // MODE 1 interrupts vypnuté
|
||||
i2c_read_register_8(CCS811_DEV_HANDLE, 0x00, &status);
|
||||
i2c_read_register_16(CCS811_DEV_HANDLE, 0x24, &version);
|
||||
ESP_LOGW(TAG_CCS, "CCS811 status: %d, version: %d", status, version);
|
||||
}
|
||||
|
||||
esp_err_t ccs811_get_data(uint16_t * eCO2, uint16_t * tvoc)
|
||||
ccs811_getStatus();
|
||||
i2c_write_register(CCS811_DEV_HANDLE, CCS811_REG_APP_START, NULL, 0); // start
|
||||
vTaskDelay(10 / portTICK_PERIOD_MS);
|
||||
i2c_write_register_8(CCS811_DEV_HANDLE, CCS811_REG_MEAS_MODE, 0x40); // MODE 1 interrupts vypnuté
|
||||
ccs811_getStatus();
|
||||
}
|
||||
esp_err_t ccs811_get_data(uint16_t *eCO2, uint16_t *tvoc, uint8_t *current, uint16_t *rawData)
|
||||
{
|
||||
uint8_t ccsResult[8];
|
||||
esp_err_t ret = i2c_read_register(CCS811_DEV_HANDLE, 0x05, ccsResult, 8);
|
||||
uint8_t algResultData[8];
|
||||
esp_err_t ret = i2c_read_register(CCS811_DEV_HANDLE, CCS811_REG_ALG_RESULT_DATA, algResultData, 8);
|
||||
|
||||
if (ret == ESP_OK)
|
||||
{
|
||||
*eCO2 = (((uint16_t)(ccsResult[0] & 0xFF)) << 8) | (ccsResult[1] & 0xFF);
|
||||
*tvoc = (((uint16_t)(ccsResult[2] & 0xFF)) << 8) | (ccsResult[3] & 0xFF);
|
||||
ESP_LOGI(TAG_CCS, "CCS Status: %d, Error %d", ccsResult[4], ccsResult[5]);
|
||||
*eCO2 = ((uint16_t)algResultData[0] << 8) | algResultData[1];
|
||||
*tvoc = ((uint16_t)algResultData[2] << 8) | algResultData[3];
|
||||
*current = algResultData[6] >> 2;
|
||||
*rawData = ((uint16_t)(algResultData[6] & 0x03) << 8) | algResultData[7];
|
||||
|
||||
ESP_LOGI(TAG_CCS, "CCS Status: %d, Error: %d", algResultData[4], algResultData[5]);
|
||||
return ESP_OK;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
||||
esp_err_t ccs811_set_env_data(float temperature, float humidity)
|
||||
{
|
||||
uint8_t envData[4];
|
||||
|
||||
// Convert humidity: %RH × 512 (rounding)
|
||||
uint16_t hum_conv = (uint16_t)(humidity * 512.0f + 0.5f);
|
||||
envData[0] = (hum_conv >> 8) & 0xFF;
|
||||
envData[1] = hum_conv & 0xFF;
|
||||
|
||||
// Convert temperature: (°C + 25) × 512
|
||||
uint16_t temp_conv = (uint16_t)((temperature + 25.0f) * 512.0f + 0.5f);
|
||||
envData[2] = (temp_conv >> 8) & 0xFF;
|
||||
envData[3] = temp_conv & 0xFF;
|
||||
|
||||
return i2c_write_register(CCS811_DEV_HANDLE, CCS811_REG_ENV_DATA, envData, 4);
|
||||
}
|
||||
|
@@ -5,11 +5,39 @@
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#define TAG_CCS "CCS811"
|
||||
|
||||
// CCS811 Registers
|
||||
#define CCS811_REG_STATUS 0x00
|
||||
#define CCS811_REG_MEAS_MODE 0x01
|
||||
#define CCS811_REG_ALG_RESULT_DATA 0x02
|
||||
#define CCS811_REG_RAW_DATA 0x03
|
||||
#define CCS811_REG_ENV_DATA 0x05
|
||||
#define CCS811_REG_THRESHOLDS 0x10
|
||||
#define CCS811_REG_BASELINE 0x11
|
||||
#define CCS811_REG_HW_ID 0x20
|
||||
#define CCS811_REG_HW_VERSION 0x21
|
||||
#define CCS811_REG_FW_BOOT_VERSION 0x23
|
||||
#define CCS811_REG_FW_APP_VERSION 0x24
|
||||
#define CCS811_REG_INTERNAL_STATE 0xA0
|
||||
#define CCS811_REG_ERROR_ID 0xE0
|
||||
#define CCS811_REG_APP_ERASE 0xF1
|
||||
#define CCS811_REG_APP_DATA 0xF2
|
||||
#define CCS811_REG_APP_VERIFY 0xF3
|
||||
#define CCS811_REG_APP_START 0xF4
|
||||
#define CCS811_REG_SW_RESET 0xFF
|
||||
|
||||
// Measurement Modes
|
||||
#define CCS811_MODE_IDLE 0x00
|
||||
#define CCS811_MODE_CONSTANT_1S 0x10
|
||||
#define CCS811_MODE_CONSTANT_10S 0x20
|
||||
#define CCS811_MODE_CONSTANT_60S 0x30
|
||||
#define CCS811_MODE_WAKEUP 0x40
|
||||
|
||||
extern i2c_device_config_t CCS811_DEV_CFG;
|
||||
|
||||
extern i2c_master_dev_handle_t CCS811_DEV_HANDLE;
|
||||
|
||||
void ccs811_init();
|
||||
esp_err_t ccs811_get_data(uint16_t * eCO2, uint16_t * tvoc);
|
||||
|
||||
esp_err_t ccs811_get_data(uint16_t *eCO2, uint16_t *tvoc, uint8_t *current, uint16_t *rawData);
|
||||
esp_err_t ccs811_set_env_data(float temperature, float humidity);
|
||||
#endif
|
136
main/hw/gps.c
Normal file
136
main/hw/gps.c
Normal file
@@ -0,0 +1,136 @@
|
||||
#include "driver/uart.h"
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "esp_log.h"
|
||||
#include "string.h"
|
||||
#include "gps.h"
|
||||
|
||||
#define TAG "GPS"
|
||||
#define BUF_SIZE 1024
|
||||
#define GPS_LINE_MAX_LEN 128
|
||||
|
||||
static QueueHandle_t uart_queue;
|
||||
|
||||
// Initializes UART for GPS
|
||||
void gps_init()
|
||||
{
|
||||
uart_config_t uart_config = {
|
||||
.baud_rate = 9600,
|
||||
.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,
|
||||
};
|
||||
ESP_ERROR_CHECK(uart_param_config(GPS_UART_NUM, &uart_config));
|
||||
ESP_ERROR_CHECK(uart_set_pin(GPS_UART_NUM, GPS_TXD, GPS_RXD, GPS_RTS, GPS_CTS));
|
||||
|
||||
const int uart_buffer_size = (1024 * 2);
|
||||
ESP_ERROR_CHECK(uart_driver_install(GPS_UART_NUM, uart_buffer_size, uart_buffer_size, 10, &uart_queue, 0));
|
||||
}
|
||||
|
||||
|
||||
void gps_task(void *arg)
|
||||
{
|
||||
uint8_t byte;
|
||||
char line[GPS_LINE_MAX_LEN];
|
||||
size_t line_pos = 0;
|
||||
|
||||
gps_init();
|
||||
|
||||
while (1) {
|
||||
int len = uart_read_bytes(GPS_UART_NUM, &byte, 1, pdMS_TO_TICKS(1000));
|
||||
if (len > 0) {
|
||||
if (byte == '\n') {
|
||||
line[line_pos] = '\0';
|
||||
|
||||
if (line[0] == '$') {
|
||||
ESP_LOGV(TAG, "Received NMEA: %s", line);
|
||||
|
||||
if (strstr(line, "$GPGGA") == line) {
|
||||
parse_gpgga(line);
|
||||
} else if (strstr(line, "$GPRMC") == line) {
|
||||
parse_gprmc(line);
|
||||
}
|
||||
}
|
||||
|
||||
line_pos = 0;
|
||||
} else if (byte != '\r' && line_pos < (GPS_LINE_MAX_LEN - 1)) {
|
||||
line[line_pos++] = byte;
|
||||
} else if (line_pos >= GPS_LINE_MAX_LEN - 1) {
|
||||
ESP_LOGW(TAG, "Line too long, discarded");
|
||||
line_pos = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void parse_gpgga(const char *nmea)
|
||||
{
|
||||
char *fields[15];
|
||||
char temp[GPS_LINE_MAX_LEN];
|
||||
strncpy(temp, nmea, GPS_LINE_MAX_LEN);
|
||||
temp[GPS_LINE_MAX_LEN - 1] = '\0';
|
||||
|
||||
int i = 0;
|
||||
char *token = strtok(temp, ",");
|
||||
while (token != NULL && i < 15) {
|
||||
fields[i++] = token;
|
||||
token = strtok(NULL, ",");
|
||||
}
|
||||
|
||||
if (i < 10) return; // Not enough fields
|
||||
|
||||
// Time (hhmmss.sss)
|
||||
const char *utc_time = fields[1];
|
||||
|
||||
// Latitude (ddmm.mmmm)
|
||||
const char *lat = fields[2];
|
||||
const char *lat_dir = fields[3];
|
||||
|
||||
// Longitude (dddmm.mmmm)
|
||||
const char *lon = fields[4];
|
||||
const char *lon_dir = fields[5];
|
||||
|
||||
// Fix quality (0 = invalid, 1 = GPS fix, 2 = DGPS fix)
|
||||
const char *fix_quality = fields[6];
|
||||
|
||||
// Number of satellites
|
||||
const char *num_satellites = fields[7];
|
||||
|
||||
// Altitude
|
||||
const char *altitude = fields[9];
|
||||
|
||||
ESP_LOGI(TAG, "[GPGGA] Time: %s, Lat: %s %s, Lon: %s %s, Fix: %s, Sats: %s, Alt: %sm",
|
||||
utc_time, lat, lat_dir, lon, lon_dir, fix_quality, num_satellites, altitude);
|
||||
}
|
||||
|
||||
void parse_gprmc(const char *nmea)
|
||||
{
|
||||
char *fields[13];
|
||||
char temp[GPS_LINE_MAX_LEN];
|
||||
strncpy(temp, nmea, GPS_LINE_MAX_LEN);
|
||||
temp[GPS_LINE_MAX_LEN - 1] = '\0';
|
||||
|
||||
int i = 0;
|
||||
char *token = strtok(temp, ",");
|
||||
while (token != NULL && i < 13) {
|
||||
fields[i++] = token;
|
||||
token = strtok(NULL, ",");
|
||||
}
|
||||
|
||||
if (i < 12) return;
|
||||
|
||||
const char *utc_time = fields[1];
|
||||
const char *status = fields[2]; // A = active, V = void
|
||||
const char *lat = fields[3];
|
||||
const char *lat_dir = fields[4];
|
||||
const char *lon = fields[5];
|
||||
const char *lon_dir = fields[6];
|
||||
const char *speed_knots = fields[7];
|
||||
const char *date = fields[9];
|
||||
|
||||
ESP_LOGI(TAG, "[GPRMC] Date: %s, Time: %s, Lat: %s %s, Lon: %s %s, Speed: %s knots, Status: %s",
|
||||
date, utc_time, lat, lat_dir, lon, lon_dir, speed_knots, status);
|
||||
}
|
||||
|
14
main/hw/gps.h
Normal file
14
main/hw/gps.h
Normal file
@@ -0,0 +1,14 @@
|
||||
#ifndef GPS_COMPONENT
|
||||
#define GPS_COMPONENT
|
||||
|
||||
#include "driver/uart.h"
|
||||
#include "soc/uart_struct.h"
|
||||
#include "buscfg.h"
|
||||
|
||||
|
||||
|
||||
void gps_task(void *arg);
|
||||
void parse_gpgga(const char *nmea);
|
||||
void parse_gprmc(const char *nmea);
|
||||
|
||||
#endif
|
@@ -3,50 +3,84 @@
|
||||
i2c_master_bus_config_t i2c0_bus_cfg = {
|
||||
.clk_source = I2C_CLK_SRC_DEFAULT,
|
||||
.i2c_port = I2C_NUM_0,
|
||||
.scl_io_num = GPIO_NUM_9,
|
||||
.sda_io_num = GPIO_NUM_8,
|
||||
.scl_io_num = HWI2C_SCL,
|
||||
.sda_io_num = HWI2C_SDA,
|
||||
.glitch_ignore_cnt = 7,
|
||||
.flags.enable_internal_pullup = true,
|
||||
};
|
||||
i2c_master_bus_handle_t i2c0_bus_hdl;
|
||||
|
||||
esp_err_t i2c_master_bus_detect_devices(i2c_master_bus_handle_t handle)
|
||||
{
|
||||
const uint16_t probe_timeout_ms = 50; // timeout in milliseconds
|
||||
uint8_t address;
|
||||
// esp_err_t i2c_master_bus_detect_devices(i2c_master_bus_handle_t handle)
|
||||
// {
|
||||
// const uint16_t probe_timeout_ms = 20; // timeout in milliseconds
|
||||
// uint8_t address;
|
||||
|
||||
printf(" 0 1 2 3 4 5 6 7 8 9 a b c d e f\r\n");
|
||||
// printf(" 0 1 2 3 4 5 6 7 8 9 a b c d e f\r\n");
|
||||
|
||||
for (int i = 0; i < 128; i += 16)
|
||||
{
|
||||
printf("%02x: ", i);
|
||||
// for (int i = 0; i < 128; i += 16)
|
||||
// {
|
||||
// printf("%02x: ", i);
|
||||
|
||||
for (int j = 0; j < 16; j++)
|
||||
{
|
||||
fflush(stdout);
|
||||
// for (int j = 0; j < 16; j++)
|
||||
// {
|
||||
// fflush(stdout);
|
||||
|
||||
address = i + j;
|
||||
// address = i + j;
|
||||
|
||||
esp_err_t ret = i2c_master_probe(handle, address, probe_timeout_ms);
|
||||
// esp_err_t ret = i2c_master_probe(handle, address, probe_timeout_ms);
|
||||
|
||||
if (ret == ESP_OK)
|
||||
{
|
||||
printf("%02x ", address);
|
||||
}
|
||||
else if (ret == ESP_ERR_TIMEOUT)
|
||||
{
|
||||
printf("UU ");
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("-- ");
|
||||
}
|
||||
}
|
||||
printf("\r\n");
|
||||
}
|
||||
// if (ret == ESP_OK)
|
||||
// {
|
||||
// printf("%02x ", address);
|
||||
// }
|
||||
// else if (ret == ESP_ERR_TIMEOUT)
|
||||
// {
|
||||
// printf("UU ");
|
||||
// }
|
||||
// else
|
||||
// {
|
||||
// printf("-- ");
|
||||
// }
|
||||
// }
|
||||
// printf("\r\n");
|
||||
// }
|
||||
|
||||
return ESP_OK;
|
||||
}
|
||||
// return ESP_OK;
|
||||
// }
|
||||
|
||||
|
||||
/**
|
||||
* i2c master initialization
|
||||
*/
|
||||
|
||||
esp_err_t i2c_master_bus_detect_devices(i2c_master_bus_handle_t handle)
|
||||
{
|
||||
uint8_t address;
|
||||
bool found_any = false;
|
||||
|
||||
printf("Scanning I2C bus...\n");
|
||||
|
||||
for (int i = 0; i < 128; i++)
|
||||
{
|
||||
fflush(stdout);
|
||||
address = i;
|
||||
|
||||
esp_err_t ret = i2c_master_probe(handle, address, 20);
|
||||
|
||||
if (ret == ESP_OK)
|
||||
{
|
||||
printf("Found device at 0x%02X\n", address);
|
||||
found_any = true;
|
||||
}
|
||||
}
|
||||
|
||||
if (!found_any)
|
||||
{
|
||||
printf("No I2C devices found.\n");
|
||||
}
|
||||
|
||||
return ESP_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Writes data to a specific register of an I2C device.
|
||||
|
@@ -3,6 +3,7 @@
|
||||
#define I2C_TIMEOUT_MS_VALUE 20
|
||||
#include <string.h>
|
||||
#include "esp_log.h"
|
||||
#include "buscfg.h"
|
||||
|
||||
#define TAG_I2C "cani2c"
|
||||
|
||||
|
@@ -16,7 +16,8 @@ void ina260_reset() {
|
||||
void ina260_init()
|
||||
{
|
||||
ESP_ERROR_CHECK(i2c_master_bus_add_device(i2c0_bus_hdl, &INA260_DEV_CFG, &INA260_DEV_HANDLE));
|
||||
i2c_write_register_16(INA260_DEV_HANDLE, INA260_CONFIG_REGISTER, 0x0FFF); // set ina max averaging and max time
|
||||
i2c_write_register_16(INA260_DEV_HANDLE, INA260_CONFIG_REGISTER,
|
||||
CONFIG_AVG_1024 | CONFIG_VBUSCT_8_244MS | CONFIG_ISHCT_8_244MS | CONFIG_MODE_CURRENT_VOLTAGE_CONTINOUS); // set ina max averaging and max time
|
||||
}
|
||||
|
||||
|
||||
|
@@ -16,60 +16,57 @@ extern i2c_master_dev_handle_t INA260_DEV_HANDLE;
|
||||
#define INA260_DIE_ID_REGISTER (0xFF)
|
||||
|
||||
// Bit masks
|
||||
#define CONFIG_RST_BIT (1 << 15)
|
||||
#define CONFIG_AVG_MASK (0x7 << 9)
|
||||
#define CONFIG_VBUSCT_MASK (0x7 << 6)
|
||||
#define CONFIG_ISHCT_MASK (0x7 << 3)
|
||||
#define CONFIG_MODE_MASK (0x7 << 0)
|
||||
#define CONFIG_RST_BIT (1 << 15)
|
||||
#define CONFIG_AVG_MASK (0x7 << 9)
|
||||
#define CONFIG_VBUSCT_MASK (0x7 << 6)
|
||||
#define CONFIG_ISHCT_MASK (0x7 << 3)
|
||||
#define CONFIG_MODE_MASK (0x7 << 0)
|
||||
|
||||
// Read-only bits
|
||||
#define CONFIG_RESERVED_BITS (0x7 << 12) // Bits 14–12 = 110b
|
||||
#define CONFIG_RESERVED_BITS (0x7 << 12) // Bits 14–12 = 110b
|
||||
|
||||
// Averaging modes (AVG)
|
||||
#define CONFIG_AVG_1 (0x0 << 9)
|
||||
#define CONFIG_AVG_4 (0x1 << 9)
|
||||
#define CONFIG_AVG_16 (0x2 << 9)
|
||||
#define CONFIG_AVG_64 (0x3 << 9)
|
||||
#define CONFIG_AVG_128 (0x4 << 9)
|
||||
#define CONFIG_AVG_256 (0x5 << 9)
|
||||
#define CONFIG_AVG_512 (0x6 << 9)
|
||||
#define CONFIG_AVG_1024 (0x7 << 9)
|
||||
#define CONFIG_AVG_1 (0x0 << 9)
|
||||
#define CONFIG_AVG_4 (0x1 << 9)
|
||||
#define CONFIG_AVG_16 (0x2 << 9)
|
||||
#define CONFIG_AVG_64 (0x3 << 9)
|
||||
#define CONFIG_AVG_128 (0x4 << 9)
|
||||
#define CONFIG_AVG_256 (0x5 << 9)
|
||||
#define CONFIG_AVG_512 (0x6 << 9)
|
||||
#define CONFIG_AVG_1024 (0x7 << 9)
|
||||
|
||||
// Bus voltage conversion time (VBUSCT)
|
||||
#define CONFIG_VBUSCT_140US (0x0 << 6)
|
||||
#define CONFIG_VBUSCT_204US (0x1 << 6)
|
||||
#define CONFIG_VBUSCT_332US (0x2 << 6)
|
||||
#define CONFIG_VBUSCT_588US (0x3 << 6)
|
||||
#define CONFIG_VBUSCT_1_1MS (0x4 << 6)
|
||||
#define CONFIG_VBUSCT_2_116MS (0x5 << 6)
|
||||
#define CONFIG_VBUSCT_4_156MS (0x6 << 6)
|
||||
#define CONFIG_VBUSCT_8_244MS (0x7 << 6)
|
||||
#define CONFIG_VBUSCT_140US (0x0 << 6)
|
||||
#define CONFIG_VBUSCT_204US (0x1 << 6)
|
||||
#define CONFIG_VBUSCT_332US (0x2 << 6)
|
||||
#define CONFIG_VBUSCT_588US (0x3 << 6)
|
||||
#define CONFIG_VBUSCT_1_1MS (0x4 << 6)
|
||||
#define CONFIG_VBUSCT_2_116MS (0x5 << 6)
|
||||
#define CONFIG_VBUSCT_4_156MS (0x6 << 6)
|
||||
#define CONFIG_VBUSCT_8_244MS (0x7 << 6)
|
||||
|
||||
// Shunt current conversion time (ISHCT)
|
||||
#define CONFIG_ISHCT_140US (0x0 << 3)
|
||||
#define CONFIG_ISHCT_204US (0x1 << 3)
|
||||
#define CONFIG_ISHCT_332US (0x2 << 3)
|
||||
#define CONFIG_ISHCT_588US (0x3 << 3)
|
||||
#define CONFIG_ISHCT_1_1MS (0x4 << 3)
|
||||
#define CONFIG_ISHCT_2_116MS (0x5 << 3)
|
||||
#define CONFIG_ISHCT_4_156MS (0x6 << 3)
|
||||
#define CONFIG_ISHCT_8_244MS (0x7 << 3)
|
||||
#define CONFIG_ISHCT_140US (0x0 << 3)
|
||||
#define CONFIG_ISHCT_204US (0x1 << 3)
|
||||
#define CONFIG_ISHCT_332US (0x2 << 3)
|
||||
#define CONFIG_ISHCT_588US (0x3 << 3)
|
||||
#define CONFIG_ISHCT_1_1MS (0x4 << 3)
|
||||
#define CONFIG_ISHCT_2_116MS (0x5 << 3)
|
||||
#define CONFIG_ISHCT_4_156MS (0x6 << 3)
|
||||
#define CONFIG_ISHCT_8_244MS (0x7 << 3)
|
||||
|
||||
// Operating mode (MODE)
|
||||
#define CONFIG_MODE_POWERDOWN (0x0 << 0)
|
||||
#define CONFIG_MODE_CURRENT_TRIGGER (0x1 << 0)
|
||||
#define CONFIG_MODE_VOLTAGE_TRIGGER (0x2 << 0)
|
||||
#define CONFIG_MODE_CURRENT_VOLTAGE_TRIGGER (0x3 << 0)
|
||||
#define CONFIG_MODE_POWERDOWN2 (0x4 << 0)
|
||||
#define CONFIG_MODE_POWERDOWN (0x5 << 0)
|
||||
#define CONFIG_MODE_POWERDOWN (0x6 << 0)
|
||||
#define CONFIG_MODE_POWERDOWN (0x7 << 0)
|
||||
|
||||
|
||||
#define CONFIG_MODE_POWERDOWN 0x00
|
||||
#define CONFIG_MODE_CURRENT_TRIGGER 0x01
|
||||
#define CONFIG_MODE_VOLTAGE_TRIGGER 0x02
|
||||
#define CONFIG_MODE_CURRENT_VOLTAGE_TRIGGER 0x03
|
||||
#define CONFIG_MODE_POWERDOWN2 0x04
|
||||
#define CONFIG_MODE_CURRENT_CONTINOUS 0x05
|
||||
#define CONFIG_MODE_VOLTAGE_CONTINOUS 0x06
|
||||
#define CONFIG_MODE_CURRENT_VOLTAGE_CONTINOUS 0x07
|
||||
|
||||
void ina260_init();
|
||||
void ina260_readParams(uint16_t *volt, uint16_t *cur, uint16_t *pow);
|
||||
void ina260_printParams(uint16_t volt, uint16_t cur, uint16_t pow);
|
||||
|
||||
|
||||
#endif
|
@@ -1,4 +1,6 @@
|
||||
#include "mcp23018.h"
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
// Local buffer for tracking GPIO state
|
||||
|
||||
i2c_device_config_t MCP23018_DEV_CFG = {
|
||||
@@ -36,6 +38,7 @@ void mcp23018_set_pin(i2c_master_dev_handle_t dev_handle, uint8_t pin, uint8_t v
|
||||
// Write updated buffer to MCP23018
|
||||
i2c_write_register_8(dev_handle, MCP23018_GPIOB, gpiob_state);
|
||||
}
|
||||
vTaskDelay(1 / portTICK_PERIOD_MS);
|
||||
}
|
||||
|
||||
void mcp23018_init()
|
||||
|
118
main/hw/mcp3550.c
Normal file
118
main/hw/mcp3550.c
Normal file
@@ -0,0 +1,118 @@
|
||||
#include "mcp3550.h"
|
||||
#include "mcp23018.h"
|
||||
#include "driver/gpio.h"
|
||||
#include <esp_timer.h>
|
||||
|
||||
|
||||
#define TAG_MICS "MICS_ADC"
|
||||
#define MCP3550_SPS 3.75f
|
||||
#define MCP3550_CONVERSION_MS ((int)(1000.0f / MCP3550_SPS)) // ~267ms
|
||||
#define MCP3550_TIMEOUT_MS 400
|
||||
|
||||
#define ADC_COUNT 4
|
||||
const uint8_t adc_cs_pins[ADC_COUNT] = {
|
||||
MCP_CS_ADC_NH3, MCP_CS_ADC_CO, MCP_CS_ADC_NO2, MCP_CS_ADC_UVC
|
||||
};
|
||||
|
||||
|
||||
spi_device_handle_t mcp3550_handle;
|
||||
|
||||
void mcp3550_spi_init()
|
||||
{
|
||||
spi_device_interface_config_t devcfg = {
|
||||
.clock_speed_hz = 100000,
|
||||
.mode = 0,
|
||||
.spics_io_num = -1, // We handle CS manually
|
||||
.queue_size = 1,
|
||||
};
|
||||
|
||||
ESP_ERROR_CHECK(spi_bus_add_device(SPI2_HOST, &devcfg, &mcp3550_handle));
|
||||
|
||||
// Set MISO pin for input (needed for polling)
|
||||
gpio_set_direction(MCP3550_MISO_GPIO, GPIO_MODE_INPUT);
|
||||
mcp23018_set_pin(MCP23018_DEV_HANDLE, MCP_MICS_POWER, 1); // CS HIGH
|
||||
}
|
||||
|
||||
|
||||
int32_t mcp3550_read(uint8_t cs_pin)
|
||||
{
|
||||
uint8_t rx_buf[4] = {0}; // 25 bits fits in 4 bytes
|
||||
|
||||
int64_t start = esp_timer_get_time(); // in microseconds
|
||||
while (true) {
|
||||
mcp23018_set_pin(MCP23018_DEV_HANDLE, cs_pin, 0); // CS LOW
|
||||
|
||||
spi_transaction_t trans = {
|
||||
.length = 25,
|
||||
.rx_buffer = rx_buf,
|
||||
};
|
||||
|
||||
esp_err_t err = spi_device_transmit(mcp3550_handle, &trans);
|
||||
|
||||
mcp23018_set_pin(MCP23018_DEV_HANDLE, cs_pin, 1); // CS HIGH
|
||||
|
||||
if (err != ESP_OK) {
|
||||
ESP_LOGE(TAG_MICS, "SPI transmit failed on CS pin %u", cs_pin);
|
||||
return INT32_MIN;
|
||||
}
|
||||
|
||||
bool dr = (rx_buf[0] & 0x80) != 0;
|
||||
if (!dr) break;
|
||||
|
||||
if ((esp_timer_get_time() - start) > (MCP3550_TIMEOUT_MS * 1000)) {
|
||||
ESP_LOGW(TAG_MICS, "Timeout waiting for DR=0 on CS pin %u", cs_pin);
|
||||
return INT32_MIN;
|
||||
}
|
||||
|
||||
vTaskDelay(pdMS_TO_TICKS(10)); // Wait before retrying
|
||||
}
|
||||
|
||||
// Combine 22-bit result (drop DR + status bits)
|
||||
uint32_t raw = ((rx_buf[0] & 0x3F) << 16) | (rx_buf[1] << 8) | rx_buf[2];
|
||||
|
||||
// Sign-extend 22-bit value
|
||||
int32_t value = raw;
|
||||
if (value & (1 << 21)) value |= 0xFFC00000;
|
||||
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
float mcp3550_to_voltage(int32_t value, float vref)
|
||||
{
|
||||
return ((float)value / (1 << 21)) * vref;
|
||||
}
|
||||
|
||||
mics_adc_data_t mcp3550_read_all(float vref)
|
||||
{
|
||||
mics_adc_data_t data;
|
||||
int32_t raw[ADC_COUNT];
|
||||
float volts[ADC_COUNT];
|
||||
|
||||
for (int i = 0; i < ADC_COUNT; i++) {
|
||||
raw[i] = mcp3550_read(adc_cs_pins[i]);
|
||||
vTaskDelay(pdMS_TO_TICKS(10)); // Wait before retrying
|
||||
volts[i] = mcp3550_to_voltage(raw[i], vref);
|
||||
}
|
||||
|
||||
data.raw_nh3 = raw[0]; data.volts_nh3 = volts[0];
|
||||
data.raw_co = raw[1]; data.volts_co = volts[1];
|
||||
data.raw_no2 = raw[2]; data.volts_no2 = volts[2];
|
||||
data.raw_uvc = raw[3]; data.volts_uvc = volts[3];
|
||||
|
||||
return data;
|
||||
}
|
||||
|
||||
void log_mics_adc_values(mics_adc_data_t *data)
|
||||
{
|
||||
ESP_LOGI(TAG_MICS,
|
||||
"ADC Readings:\n"
|
||||
" NH3 -> Raw: %8d, Voltage: %7.6f V\n"
|
||||
" CO -> Raw: %8d, Voltage: %7.6f V\n"
|
||||
" NO2 -> Raw: %8d, Voltage: %7.6f V\n"
|
||||
" UVC -> Raw: %8d, Voltage: %7.6f V",
|
||||
data->raw_nh3, data->volts_nh3,
|
||||
data->raw_co, data->volts_co,
|
||||
data->raw_no2, data->volts_no2,
|
||||
data->raw_uvc, data->volts_uvc);
|
||||
}
|
38
main/hw/mcp3550.h
Normal file
38
main/hw/mcp3550.h
Normal file
@@ -0,0 +1,38 @@
|
||||
#ifndef MPC3550_COMPONENT
|
||||
#define MPC3550_COMPONENT
|
||||
|
||||
#include "driver/spi_master.h"
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "esp_log.h"
|
||||
#include "buscfg.h"
|
||||
|
||||
#define CONFIG_FREERTOS_HZ 100
|
||||
|
||||
#define MCP3550_SPS 3.75f
|
||||
#define MCP3550_CONVERSION_MS ((int)(1000.0f / MCP3550_SPS)) // ~267ms
|
||||
|
||||
|
||||
extern spi_device_handle_t mcp3550_handle;
|
||||
|
||||
void mcp3550_spi_init();
|
||||
int32_t mcp3550_read(uint8_t cs_pin);
|
||||
float mcp3550_to_voltage(int32_t value, float vref);
|
||||
|
||||
typedef struct {
|
||||
int32_t raw_nh3;
|
||||
int32_t raw_co;
|
||||
int32_t raw_no2;
|
||||
int32_t raw_uvc;
|
||||
float volts_nh3;
|
||||
float volts_co;
|
||||
float volts_no2;
|
||||
float volts_uvc;
|
||||
} mics_adc_data_t;
|
||||
|
||||
extern spi_device_handle_t mcp3550_handle;
|
||||
|
||||
void log_mics_adc_values(mics_adc_data_t *data);
|
||||
mics_adc_data_t mcp3550_read_all(float vref);
|
||||
|
||||
#endif
|
578
main/hw/sx1262.c
Normal file
578
main/hw/sx1262.c
Normal file
@@ -0,0 +1,578 @@
|
||||
#include "sx1262.h"
|
||||
|
||||
spi_device_handle_t spiSXko;
|
||||
|
||||
#define TAG_SPIDUMP "[SPI]"
|
||||
|
||||
void sx1262_init()
|
||||
{
|
||||
ESP_LOGI(TAG, "Initializing SX1262...");
|
||||
|
||||
gpio_set_direction(HSPI_LORA_CS, GPIO_MODE_OUTPUT);
|
||||
gpio_set_direction(LORA_BUSY, GPIO_MODE_INPUT);
|
||||
|
||||
gpio_set_level(HSPI_LORA_CS, 1);
|
||||
mcp23018_set_pin(MCP23018_DEV_HANDLE, MCP_LORA_RST, 1);
|
||||
|
||||
spi_bus_config_t buscfg;
|
||||
memset(&buscfg, 0, sizeof(spi_bus_config_t));
|
||||
buscfg.miso_io_num = HSPI_MISO_GPIO;
|
||||
buscfg.mosi_io_num = HSPI_MOSI_GPIO;
|
||||
buscfg.sclk_io_num = HSPI_SCK_GPIO;
|
||||
buscfg.max_transfer_sz = 32;
|
||||
buscfg.quadwp_io_num = -1;
|
||||
buscfg.quadhd_io_num = -1;
|
||||
|
||||
spi_device_interface_config_t devcfg = {
|
||||
.command_bits = 0,
|
||||
.address_bits = 0,
|
||||
.mode = 0,
|
||||
.cs_ena_pretrans = 10,
|
||||
.clock_speed_hz = 8 * 1000 * 1000,
|
||||
.spics_io_num = HSPI_LORA_CS,
|
||||
.flags = 0,
|
||||
.queue_size = 1};
|
||||
|
||||
ESP_LOGI(TAG, "Adding SPI device...");
|
||||
esp_err_t ret = spi_bus_add_device(LORA_SPI_HOST, &devcfg, &spiSXko);
|
||||
if (ret != ESP_OK)
|
||||
{
|
||||
ESP_LOGE(TAG, "SPI device init failed!");
|
||||
return;
|
||||
}
|
||||
|
||||
ESP_LOGI(TAG, "SX1262 Initialized");
|
||||
sx1262_reset();
|
||||
}
|
||||
|
||||
void sx1262_reset()
|
||||
{
|
||||
ESP_LOGI(TAG, "Resetting SX1262...");
|
||||
vTaskDelay(pdMS_TO_TICKS(10));
|
||||
mcp23018_set_pin(MCP23018_DEV_HANDLE, MCP_LORA_RST, 0);
|
||||
vTaskDelay(pdMS_TO_TICKS(20));
|
||||
mcp23018_set_pin(MCP23018_DEV_HANDLE, MCP_LORA_RST, 1);
|
||||
vTaskDelay(pdMS_TO_TICKS(10));
|
||||
sx1262_wait_for_busy();
|
||||
ESP_LOGI(TAG, "SX1262 Reset complete.");
|
||||
}
|
||||
|
||||
void sx1262_wait_for_busy()
|
||||
{
|
||||
ESP_LOGV("WAIT", "Waiting for SX1262 to be ready...");
|
||||
while (gpio_get_level(LORA_BUSY) == 1)
|
||||
{
|
||||
vTaskDelay(pdMS_TO_TICKS(10));
|
||||
}
|
||||
ESP_LOGV("WAIT", "SX1262 is ready.");
|
||||
}
|
||||
|
||||
void sx1262_write_command(uint8_t cmd, uint8_t *data, uint8_t len)
|
||||
{
|
||||
ESP_LOGV(TAG, "Writing command 0x%02X with length %d", cmd, len);
|
||||
spi_transaction_t t;
|
||||
memset(&t, 0, sizeof(t));
|
||||
t.length = (len + 1) * 8;
|
||||
uint8_t *tx_data = malloc(len + 1);
|
||||
memset(tx_data, 0, len + 1);
|
||||
tx_data[0] = cmd;
|
||||
if (len)
|
||||
{
|
||||
memcpy(tx_data + 1, data, len);
|
||||
}
|
||||
t.tx_buffer = tx_data;
|
||||
|
||||
sx1262_wait_for_busy();
|
||||
|
||||
ESP_LOGI(TAG_SPIDUMP, "SPI TX (cmd 0x%02X):", cmd);
|
||||
ESP_LOG_BUFFER_HEXDUMP(TAG_SPIDUMP, tx_data, len + 1, ESP_LOG_INFO);
|
||||
|
||||
esp_err_t ret = spi_device_transmit(spiSXko, &t);
|
||||
|
||||
if (ret != ESP_OK)
|
||||
{
|
||||
ESP_LOGE(TAG, "SPI write failed!");
|
||||
}
|
||||
else
|
||||
{
|
||||
ESP_LOGV(TAG, "SPI write successful");
|
||||
}
|
||||
free(tx_data);
|
||||
}
|
||||
|
||||
uint8_t SX1262_STATUS = 0;
|
||||
|
||||
void sx1262_read_command(uint8_t cmd, uint8_t *tx_payload_buffer, uint8_t tx_payload_len, uint8_t *rx_buffer, uint8_t len)
|
||||
{
|
||||
ESP_LOGV(TAG, "Reading command 0x%02X with expected length %d", cmd, len);
|
||||
spi_transaction_t t;
|
||||
memset(&t, 0, sizeof(t));
|
||||
t.length = (len + 2) * 8;
|
||||
uint8_t *tx_data = malloc(len + 2);
|
||||
uint8_t *rx_data = malloc(len + 2);
|
||||
memset(tx_data, 0, len + 2);
|
||||
memset(rx_data, 0, len + 2);
|
||||
|
||||
memset(tx_data, 0, sizeof(tx_data));
|
||||
memset(rx_data, 0, sizeof(rx_data));
|
||||
if (tx_payload_buffer != NULL && tx_payload_len > 0)
|
||||
{
|
||||
if (tx_payload_len > len + 1)
|
||||
{
|
||||
tx_payload_len = len + 1;
|
||||
}
|
||||
memcpy(tx_data + 1, tx_payload_buffer, tx_payload_len);
|
||||
}
|
||||
tx_data[0] = cmd;
|
||||
|
||||
t.tx_buffer = tx_data;
|
||||
t.rx_buffer = rx_data;
|
||||
|
||||
sx1262_wait_for_busy();
|
||||
|
||||
ESP_LOGI(TAG_SPIDUMP, "SPI TX (cmd 0x%02X):", cmd);
|
||||
ESP_LOG_BUFFER_HEXDUMP(TAG_SPIDUMP, tx_data, len + 1, ESP_LOG_INFO);
|
||||
|
||||
esp_err_t ret = spi_device_transmit(spiSXko, &t);
|
||||
|
||||
if (ret == ESP_OK)
|
||||
{
|
||||
SX1262_STATUS = rx_data[1];
|
||||
memcpy(rx_buffer, &rx_data[2], len);
|
||||
ESP_LOGI(TAG_SPIDUMP, "SPI RX (cmd 0x%02X):", cmd);
|
||||
ESP_LOG_BUFFER_HEXDUMP(TAG_SPIDUMP, rx_data, len + 2, ESP_LOG_INFO);
|
||||
ESP_LOGV(TAG_SPIDUMP, "SPI read successful, status: 0x%02X", SX1262_STATUS);
|
||||
}
|
||||
else
|
||||
{
|
||||
ESP_LOGE(TAG, "SPI read failed!");
|
||||
}
|
||||
free(rx_data);
|
||||
free(tx_data);
|
||||
}
|
||||
|
||||
void resolve_status_byte(uint8_t status, uint16_t op_error)
|
||||
{
|
||||
const char *chip_modes[] = {
|
||||
"Unused", "RFU", "STBY_RC", "STBY_XOSC",
|
||||
"FS", "RX", "TX", "RFU"};
|
||||
|
||||
const char *command_statuses[] = {
|
||||
"Reserved", "RFU", "Data is available to host", "Command timeout",
|
||||
"Command processing error", "Failure to execute command", "Command TX done", "RFU"};
|
||||
|
||||
uint8_t chip_mode = (status >> 4) & 0x07; // Bits 6:4
|
||||
uint8_t command_status = (status >> 1) & 0x07; // Bits 3:1
|
||||
|
||||
const char *chip_mode_str = chip_modes[chip_mode];
|
||||
const char *command_status_str = command_statuses[command_status];
|
||||
|
||||
const char *op_errors[] = {
|
||||
"RC64k calibration failed",
|
||||
"RC13M calibration failed",
|
||||
"PLL calibration failed",
|
||||
"ADC calibration failed",
|
||||
"IMG calibration failed",
|
||||
"XOSC failed to start",
|
||||
"PLL failed to lock",
|
||||
"RFU",
|
||||
"PA ramping failed"};
|
||||
|
||||
char errorStr[1024];
|
||||
memset(errorStr, 0, sizeof(errorStr));
|
||||
|
||||
if (command_status == 0x05)
|
||||
{
|
||||
strcat(errorStr, "Command error: ");
|
||||
}
|
||||
|
||||
for (int i = 0; i < 9; i++)
|
||||
{
|
||||
if (op_error & (1 << i))
|
||||
{
|
||||
strcat(errorStr, op_errors[i]);
|
||||
strcat(errorStr, ", ");
|
||||
ESP_LOGV(TAG, "OpError: %s", op_errors[i]);
|
||||
}
|
||||
}
|
||||
|
||||
ESP_LOGI(TAG, "Chip Mode: %s(0x%02X), Command Status: %s(0x%02X) %s", chip_mode_str, chip_mode, command_status_str, command_status, errorStr);
|
||||
}
|
||||
|
||||
sx1262_status_t sx1262_get_status()
|
||||
{
|
||||
ESP_LOGV(TAG, "Getting SX1262 status...");
|
||||
sx1262_status_t status;
|
||||
uint8_t buffer[1] = {0};
|
||||
sx1262_read_command(0xC0, NULL, 0, buffer, 1);
|
||||
status.status = buffer[0];
|
||||
status.error = sx1262_getDeviceErrors();
|
||||
sx1262_clearDeviceErrors();
|
||||
resolve_status_byte(status.status, status.error);
|
||||
return status;
|
||||
}
|
||||
|
||||
void sx1262_setSleep(uint8_t sleepCFG)
|
||||
{
|
||||
sx1262_write_command(0x84, &sleepCFG, 1);
|
||||
}
|
||||
|
||||
void sx1262_setStandby(uint8_t standbyConf)
|
||||
{
|
||||
sx1262_write_command(0x80, &standbyConf, 1);
|
||||
}
|
||||
|
||||
void sx1262_setFrequencySynthesis()
|
||||
{
|
||||
sx1262_write_command(0xC1, NULL, 0);
|
||||
}
|
||||
|
||||
void sx1262_setMode(uint8_t mode, uint32_t timeout)
|
||||
{
|
||||
|
||||
uint32_t timeoutUnits = 0;
|
||||
|
||||
if (timeout != 0)
|
||||
{
|
||||
uint64_t timeoutInUs = (uint64_t)timeout * 1000; // Convert ms → us
|
||||
timeoutUnits = (uint32_t)((timeoutInUs * 64) / 1000); // Convert us → SX1262 units
|
||||
}
|
||||
|
||||
uint8_t buffer[4] = {
|
||||
(uint8_t)((timeoutUnits >> 24) & 0xFF),
|
||||
(uint8_t)((timeoutUnits >> 16) & 0xFF),
|
||||
(uint8_t)((timeoutUnits >> 8) & 0xFF),
|
||||
(uint8_t)((timeoutUnits) & 0xFF)};
|
||||
if (mode)
|
||||
{
|
||||
sx1262_write_command(0x83, buffer, 3);
|
||||
}
|
||||
else
|
||||
{
|
||||
sx1262_write_command(0x82, buffer, 3);
|
||||
}
|
||||
}
|
||||
|
||||
void sx1262_stopTimerOnPreamble(uint8_t enable)
|
||||
{
|
||||
sx1262_write_command(0x9F, &enable, 1);
|
||||
}
|
||||
|
||||
void sx1262_setRxDutyCycle(uint32_t rxPeriod, uint32_t sleepPeriod)
|
||||
{
|
||||
uint8_t payload[6];
|
||||
payload[0] = (rxPeriod >> 16) & 0xFF;
|
||||
payload[1] = (rxPeriod >> 8) & 0xFF;
|
||||
payload[2] = rxPeriod & 0xFF;
|
||||
payload[3] = (sleepPeriod >> 16) & 0xFF;
|
||||
payload[4] = (sleepPeriod >> 8) & 0xFF;
|
||||
payload[5] = sleepPeriod & 0xFF;
|
||||
sx1262_write_command(0x94, payload, 6);
|
||||
}
|
||||
|
||||
void sx1262_setChannelActivityDetection(void)
|
||||
{
|
||||
sx1262_write_command(0xC5, NULL, 0);
|
||||
}
|
||||
|
||||
void sx1262_setTxContinuousWave(void)
|
||||
{
|
||||
sx1262_write_command(0xD1, NULL, 0);
|
||||
}
|
||||
|
||||
void sx1262_setTxInfinitePreamble(void)
|
||||
{
|
||||
sx1262_write_command(0xD2, NULL, 0);
|
||||
}
|
||||
|
||||
void sx1262_setRegulatorMode(uint8_t mode)
|
||||
{
|
||||
sx1262_write_command(0x96, &mode, 1);
|
||||
}
|
||||
|
||||
void sx1262_calibrate(uint8_t calibParam)
|
||||
{
|
||||
sx1262_write_command(0x89, &calibParam, 1);
|
||||
}
|
||||
|
||||
void sx1262_calibrateImage(uint8_t freq1, uint8_t freq2)
|
||||
{
|
||||
uint8_t payload[2] = {freq1, freq2};
|
||||
sx1262_write_command(0x98, payload, 2);
|
||||
}
|
||||
|
||||
void sx1262_setRxTXFallbackMode(uint8_t fallbackMode)
|
||||
{
|
||||
sx1262_write_command(0x93, &fallbackMode, 1);
|
||||
}
|
||||
|
||||
// Write to register function
|
||||
void sx1262_writeRegister(uint16_t address, const uint8_t *data, size_t length)
|
||||
{
|
||||
uint8_t payload[length + 2];
|
||||
payload[0] = (address >> 8) & 0xFF;
|
||||
payload[1] = address & 0xFF;
|
||||
for (size_t i = 0; i < length; i++)
|
||||
{
|
||||
payload[i + 2] = data[i];
|
||||
}
|
||||
sx1262_write_command(0x0D, payload, length + 2);
|
||||
}
|
||||
|
||||
// Read from register function
|
||||
void sx1262_readRegister(uint16_t address, uint8_t *data, size_t length)
|
||||
{
|
||||
uint8_t payload[2];
|
||||
payload[0] = (address >> 8) & 0xFF;
|
||||
payload[1] = address & 0xFF;
|
||||
uint8_t rx_payload[2 + length];
|
||||
sx1262_read_command(0x1D, payload, 2, rx_payload, 2 + length);
|
||||
for (size_t i = 0; i < length; i++)
|
||||
{
|
||||
data[i] = rx_payload[i + 2];
|
||||
}
|
||||
}
|
||||
|
||||
// Write to buffer function
|
||||
void sx1262_writeBuffer(uint8_t offset, const uint8_t *data, size_t length)
|
||||
{
|
||||
uint8_t payload[length + 1];
|
||||
payload[0] = offset;
|
||||
for (size_t i = 0; i < length; i++)
|
||||
{
|
||||
payload[i + 1] = data[i];
|
||||
}
|
||||
sx1262_write_command(0x0E, payload, length + 1);
|
||||
}
|
||||
|
||||
// Read from buffer function
|
||||
void sx1262_readBuffer(uint8_t offset, uint8_t *data, size_t length)
|
||||
{
|
||||
uint8_t tx_payload[1];
|
||||
uint8_t payload[1 + length];
|
||||
tx_payload[0] = offset;
|
||||
sx1262_read_command(0x1E, tx_payload, 1, payload, 1 + length);
|
||||
for (size_t i = 0; i < length; i++)
|
||||
{
|
||||
data[i] = payload[i + 1];
|
||||
}
|
||||
}
|
||||
|
||||
void sx1262_setDioIrqParams(uint16_t irqMask, uint16_t dio1Mask, uint16_t dio2Mask, uint16_t dio3Mask)
|
||||
{
|
||||
uint8_t payload[8] = {
|
||||
(uint8_t)((irqMask >> 8) & 0xFF), (uint8_t)((irqMask) & 0xFF),
|
||||
(uint8_t)((dio1Mask >> 8) & 0xFF), (uint8_t)(dio1Mask & 0xFF),
|
||||
(uint8_t)((dio2Mask >> 8) & 0xFF), (uint8_t)(dio2Mask & 0xFF),
|
||||
(uint8_t)((dio3Mask >> 8) & 0xFF), (uint8_t)(dio3Mask & 0xFF)};
|
||||
sx1262_write_command(0x08, payload, 8);
|
||||
}
|
||||
|
||||
uint16_t sx1262_getIrqStatus(void)
|
||||
{
|
||||
uint8_t response[2] = {0};
|
||||
sx1262_read_command(0x12, NULL, 0, response, 2);
|
||||
return (response[0] << 8) | response[1];
|
||||
}
|
||||
|
||||
void sx1262_clearIrqStatus(uint16_t clearIrqParam)
|
||||
{
|
||||
uint8_t payload[2] = {
|
||||
(uint8_t)((clearIrqParam >> 8) & 0xFF),
|
||||
(uint8_t)(clearIrqParam & 0xFF)};
|
||||
sx1262_write_command(0x02, payload, 2);
|
||||
}
|
||||
|
||||
void sx1262_setDIO2AsRfSwitchCtrl(uint8_t enable)
|
||||
{
|
||||
uint8_t buf[1];
|
||||
buf[0] = enable;
|
||||
sx1262_write_command(0x9D, buf, 1);
|
||||
}
|
||||
|
||||
void sx1262_setDIO3AsTCXOCtrl(uint8_t tcxoVoltage, uint32_t delay)
|
||||
{
|
||||
uint8_t payload[4] = {
|
||||
tcxoVoltage,
|
||||
(uint8_t)((delay >> 16) & 0xFF),
|
||||
(uint8_t)((delay >> 8) & 0xFF),
|
||||
(uint8_t)(delay & 0xFF)};
|
||||
sx1262_write_command(0x97, payload, 4);
|
||||
}
|
||||
|
||||
void sx1262_setFrequency(uint32_t frequency)
|
||||
{
|
||||
uint32_t freq_reg = frequency * FREQ_STEP;
|
||||
uint8_t buffer[4] = {
|
||||
(uint8_t)((freq_reg >> 24) & 0xFF),
|
||||
(uint8_t)((freq_reg >> 16) & 0xFF),
|
||||
(uint8_t)((freq_reg >> 8) & 0xFF),
|
||||
(uint8_t)((freq_reg) & 0xFF)};
|
||||
sx1262_write_command(0x86, buffer, 4);
|
||||
}
|
||||
|
||||
void sx1262_setPacketType(uint8_t packetType)
|
||||
{
|
||||
uint8_t data[1];
|
||||
data[0] = packetType;
|
||||
sx1262_write_command(0x8A, data, 1);
|
||||
}
|
||||
|
||||
void sx1262_setLoRaModulationParams(const sx1262_LoRaModulationParams_t *params)
|
||||
{
|
||||
uint8_t payload[4] = {
|
||||
params->spreadingFactor,
|
||||
params->bandwidth,
|
||||
params->codingRate,
|
||||
params->lowDataRateOpt};
|
||||
sx1262_write_command(0x8B, payload, sizeof(payload));
|
||||
}
|
||||
|
||||
void sx1262_setGFSKModulationParams(const sx1262_GFSKModulationParams_t *params)
|
||||
{
|
||||
uint8_t payload[8] = {
|
||||
(uint8_t)((params->bitRate >> 16) & 0xFF),
|
||||
(uint8_t)((params->bitRate >> 8) & 0xFF),
|
||||
(uint8_t)(params->bitRate & 0xFF),
|
||||
params->pulseShape,
|
||||
params->bandwidth,
|
||||
(uint8_t)((params->frequencyDev >> 16) & 0xFF),
|
||||
(uint8_t)((params->frequencyDev >> 8) & 0xFF),
|
||||
(uint8_t)(params->frequencyDev & 0xFF)};
|
||||
sx1262_write_command(0x8B, payload, sizeof(payload));
|
||||
}
|
||||
|
||||
uint8_t sx1262_getPacketType()
|
||||
{
|
||||
uint8_t response;
|
||||
sx1262_read_command(0x11, NULL, 0, &response, 1);
|
||||
return response;
|
||||
}
|
||||
|
||||
void sx1262_configure_tx_power(uint8_t paDutyCycle, uint8_t hpMax, uint8_t paLut, int8_t power, uint8_t rampTime)
|
||||
{
|
||||
if (paDutyCycle > 0x04)
|
||||
paDutyCycle = 0x04;
|
||||
if (rampTime > 0x07)
|
||||
rampTime = 0x07;
|
||||
if (hpMax > 0x07)
|
||||
hpMax = 0x07;
|
||||
|
||||
uint8_t deviceSel;
|
||||
if (power >= -9)
|
||||
{
|
||||
deviceSel = 0x00; // High Power PA
|
||||
if (power > 22)
|
||||
power = 22;
|
||||
if (power < -9)
|
||||
power = -9;
|
||||
}
|
||||
else
|
||||
{
|
||||
deviceSel = 0x01; // Low Power PA
|
||||
if (power > 14)
|
||||
power = 14;
|
||||
if (power < -17)
|
||||
power = -17;
|
||||
}
|
||||
|
||||
uint8_t paConfig[4] = {paDutyCycle, hpMax, deviceSel, paLut};
|
||||
sx1262_write_command(0x95, paConfig, 4);
|
||||
|
||||
// Direct cast keeps correct 2's complement representation
|
||||
uint8_t txPower[2] = {(uint8_t)power, rampTime};
|
||||
sx1262_write_command(0x8E, txPower, 2);
|
||||
}
|
||||
|
||||
void sx1262_setLoRaPacketParams(sx1262_LoRaPacketParams_t *params)
|
||||
{
|
||||
uint8_t payload[6] = {
|
||||
(uint8_t)((params->preambleLength >> 8) & 0xFF),
|
||||
(uint8_t)(params->preambleLength & 0xFF),
|
||||
params->headerType,
|
||||
params->payloadLength,
|
||||
params->crcType,
|
||||
params->invertIQ};
|
||||
sx1262_write_command(0x8C, payload, sizeof(payload));
|
||||
}
|
||||
|
||||
void sx1262_setCadParams(uint8_t cadSymbolNum, uint8_t cadDetPeak, uint8_t cadDetMin, uint8_t cadExitMode, uint32_t cadTimeout)
|
||||
{
|
||||
uint8_t payload[7] = {
|
||||
cadSymbolNum,
|
||||
cadDetPeak,
|
||||
cadDetMin,
|
||||
cadExitMode,
|
||||
(uint8_t)((cadTimeout >> 16) & 0xFF),
|
||||
(uint8_t)((cadTimeout >> 8) & 0xFF),
|
||||
(uint8_t)(cadTimeout & 0xFF)};
|
||||
sx1262_write_command(0x88, payload, sizeof(payload));
|
||||
}
|
||||
|
||||
void sx1262_setBufferBaseAddress(uint8_t txBaseAddr, uint8_t rxBaseAddr)
|
||||
{
|
||||
uint8_t payload[2] = {txBaseAddr, rxBaseAddr};
|
||||
sx1262_write_command(0x8F, payload, sizeof(payload));
|
||||
}
|
||||
|
||||
void sx1262_setLoRaSymbNumTimeout(uint8_t symbNum)
|
||||
{
|
||||
sx1262_write_command(0xA0, &symbNum, 1);
|
||||
}
|
||||
|
||||
void sx1262_getStatus(uint8_t *status)
|
||||
{
|
||||
sx1262_read_command(0xC0, NULL, 0, status, 0);
|
||||
}
|
||||
|
||||
void sx1262_getRxBufferStatus(uint8_t *payloadLengthRx, uint8_t *rxStartBufferPointer)
|
||||
{
|
||||
uint8_t response[2];
|
||||
sx1262_read_command(0x13, NULL, 0, response, sizeof(response));
|
||||
*payloadLengthRx = response[0];
|
||||
*rxStartBufferPointer = response[1];
|
||||
}
|
||||
|
||||
void sx1262_getPacketStatus(uint8_t *rssi, uint8_t *snr, uint8_t *signalRssi)
|
||||
{
|
||||
uint8_t response[3];
|
||||
sx1262_read_command(0x14, NULL, 0, response, sizeof(response));
|
||||
*rssi = response[0];
|
||||
*snr = response[1];
|
||||
*signalRssi = response[2];
|
||||
}
|
||||
|
||||
uint8_t sx1262_getRssiInst(uint8_t *rssiInst)
|
||||
{
|
||||
uint8_t response;
|
||||
sx1262_read_command(0x15, NULL, 0, &response, 1);
|
||||
return response;
|
||||
}
|
||||
|
||||
void sx1262_getStats(uint16_t *pktReceived, uint16_t *pktCrcError, uint16_t *pktHeaderErr)
|
||||
{
|
||||
uint8_t response[6];
|
||||
sx1262_read_command(0x10, NULL, 0, response, sizeof(response));
|
||||
*pktReceived = (response[0] << 8) | response[1];
|
||||
*pktCrcError = (response[2] << 8) | response[3];
|
||||
*pktHeaderErr = (response[4] << 8) | response[5];
|
||||
}
|
||||
|
||||
void sx1262_resetStats(void)
|
||||
{
|
||||
uint8_t payload[6] = {0};
|
||||
sx1262_write_command(0x00, payload, sizeof(payload));
|
||||
}
|
||||
|
||||
uint16_t sx1262_getDeviceErrors()
|
||||
{
|
||||
uint8_t response[2];
|
||||
sx1262_read_command(0x17, NULL, 0, response, sizeof(response));
|
||||
return (((uint16_t)response[0]) << 8) | (uint16_t)response[1];
|
||||
}
|
||||
|
||||
void sx1262_clearDeviceErrors(void)
|
||||
{
|
||||
uint8_t payload[2] = {0x00, 0x00};
|
||||
sx1262_write_command(0x07, payload, sizeof(payload));
|
||||
}
|
330
main/hw/sx1262.h
Normal file
330
main/hw/sx1262.h
Normal file
@@ -0,0 +1,330 @@
|
||||
#ifndef SX1262_H
|
||||
#define SX1262_H
|
||||
|
||||
#include "driver/spi_master.h"
|
||||
#include "driver/gpio.h"
|
||||
#include <stdint.h>
|
||||
#include "buscfg.h"
|
||||
#include "mcp23018.h"
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#include "esp_task.h"
|
||||
|
||||
#define TAG "SX1262"
|
||||
|
||||
#define LOG_LOCAL_LEVEL ESP_LOG_DEBUG
|
||||
#include "esp_log.h"
|
||||
|
||||
#define LOG_LOCAL_LEVEL ESP_LOG_DEBUG
|
||||
|
||||
#define LORA_SPI_HOST SPI3_HOST
|
||||
|
||||
extern spi_device_handle_t spi;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t status;
|
||||
uint16_t error;
|
||||
} sx1262_status_t;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint16_t preambleLength;
|
||||
uint8_t headerType;
|
||||
uint8_t payloadLength;
|
||||
uint8_t crcType;
|
||||
uint8_t invertIQ;
|
||||
} sx1262_LoRaPacketParams_t;
|
||||
|
||||
#define SX126X_DIOX_OUTPUT_ENABLE 0x0580
|
||||
#define SX126X_DIOX_INPUT_ENABLE 0x0583
|
||||
#define SX126X_DIOX_PULL_UP_CONTROL 0x0584
|
||||
#define SX126X_DIOX_PULL_DOWN_CONTROL 0x0585
|
||||
|
||||
#define SX126X_WHITENING_INIT_MSB 0x06B8
|
||||
#define SX126X_WHITENING_INIT_LSB 0x06B9
|
||||
|
||||
#define SX126X_CRC_INIT_MSB 0x06BC
|
||||
#define SX126X_CRC_INIT_LSB 0x06BD
|
||||
|
||||
#define SX126X_CRC_POLY_MSB 0x06BE
|
||||
#define SX126X_CRC_POLY_LSB 0x06BF
|
||||
|
||||
#define SX126X_SYNCWORD_0 0x06C0
|
||||
#define SX126X_SYNCWORD_1 0x06C1
|
||||
#define SX126X_SYNCWORD_2 0x06C2
|
||||
#define SX126X_SYNCWORD_3 0x06C3
|
||||
#define SX126X_SYNCWORD_4 0x06C4
|
||||
#define SX126X_SYNCWORD_5 0x06C5
|
||||
#define SX126X_SYNCWORD_6 0x06C6
|
||||
#define SX126X_SYNCWORD_7 0x06C7
|
||||
|
||||
#define SX126X_NODE_ADDRESS 0x06CD
|
||||
#define SX126X_BROADCAST_ADDRESS 0x06CE
|
||||
|
||||
#define SX126X_IQ_POLARITY_SETUP 0x0736
|
||||
|
||||
#define SX126X_LORA_SYNCWORD_MSB 0x0740
|
||||
#define SX126X_LORA_SYNCWORD_LSB 0x0741
|
||||
|
||||
#define SX126X_RANDOM_NUMBER_0 0x0819
|
||||
#define SX126X_RANDOM_NUMBER_1 0x081A
|
||||
#define SX126X_RANDOM_NUMBER_2 0x081B
|
||||
#define SX126X_RANDOM_NUMBER_3 0x081C
|
||||
|
||||
#define SX126X_TX_MODULATION 0x0889
|
||||
#define SX126X_RX_GAIN 0x08AC
|
||||
|
||||
#define SX126X_TX_CLAMP_CONFIG 0x08D8
|
||||
#define SX126X_OCP_CONFIGURATION 0x08E7
|
||||
|
||||
#define SX126X_RTC_CONTROL 0x0902
|
||||
|
||||
#define SX126X_XTA_TRIM 0x0911
|
||||
#define SX126X_XTB_TRIM 0x0912
|
||||
|
||||
#define SX126X_DIO3_OUTPUT_VOLTAGE 0x0920
|
||||
#define SX126X_EVENT_MASK 0x0944
|
||||
|
||||
// Default values where applicable
|
||||
#define SX126X_RX_GAIN_POWER_SAVING 0x94
|
||||
#define SX126X_RX_GAIN_BOOSTED 0x96
|
||||
|
||||
#define SX126X_LORA_SYNCWORD_PUBLIC 0x3444
|
||||
#define SX126X_LORA_SYNCWORD_PRIVATE 0x1424
|
||||
|
||||
#define SX126X_OCP_LEVEL_SX1262 0x38 // 140mA
|
||||
#define SX126X_OCP_LEVEL_SX1261 0x18 // 60mA
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t spreadingFactor; // LoRa SF: 0x05 (SF5) to 0x0C (SF12)
|
||||
uint8_t bandwidth; // LoRa BW: 0x00 (7.81 kHz) to 0x06 (500 kHz)
|
||||
uint8_t codingRate; // LoRa CR: 0x01 (4/5) to 0x04 (4/8)
|
||||
uint8_t lowDataRateOpt; // LDRO: 0x00 (disabled) or 0x01 (enabled)
|
||||
} sx1262_LoRaModulationParams_t;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint32_t bitRate; // GFSK bitrate (BR), calculated as 32 * Fxtal / BR
|
||||
uint8_t pulseShape; // GFSK filter: 0x00 (none) to 0x0B (Gaussian BT 1)
|
||||
uint8_t bandwidth; // GFSK RX bandwidth: 0x1F (4.8 kHz) to 0x09 (467 kHz)
|
||||
uint32_t frequencyDev; // GFSK frequency deviation (Fdev)
|
||||
} sx1262_GFSKModulationParams_t;
|
||||
|
||||
#include <math.h>
|
||||
|
||||
#define XTAL_FREQ (double)32000000
|
||||
#define FREQ_DIV (double)pow(2.0, 25.0)
|
||||
#define FREQ_STEP (double)(XTAL_FREQ / FREQ_DIV)
|
||||
|
||||
#define SX1262_SLEEPCFG_ColdStart_RTCDisable 0
|
||||
#define SX1262_SLEEPCFG_ColdStart_RTCEnable 1
|
||||
#define SX1262_SLEEPCFG_WarmStart_RTCDisable 4
|
||||
#define SX1262_SLEEPCFG_WarmStart_RTCEnable 5
|
||||
|
||||
#define SX1262_STANDBY_RC 0
|
||||
#define SX1262_STANDBY_XOSC 1
|
||||
|
||||
#define SX1262_TIMEOUT_ONCE 0
|
||||
#define SX1262_TIMEOUT_RX_CONTINOUS 0xFFFFFF
|
||||
|
||||
#define SX1262_RECEIVE_MODE 0
|
||||
#define SX1262_TRANSMIT_MODE 1
|
||||
|
||||
#define SX1262_STOP_TIMER_ON_PREAMBLE_DISABLE 0x00
|
||||
#define SX1262_STOP_TIMER_ON_PREAMBLE_ENABLE 0x01
|
||||
|
||||
#define SX1262_REGULATOR_LDO_ONLY 0x00
|
||||
#define SX1262_REGULATOR_DC_DC_LDO 0x01
|
||||
|
||||
#define SX1262_FALLBACK_FS 0x40
|
||||
#define SX1262_FALLBACK_STANDBY_XOSC 0x30
|
||||
#define SX1262_FALLBACK_RC 0x20
|
||||
|
||||
#define SX1262_IRQ_TXDone (1 << 0)
|
||||
#define SX1262_IRQ_RXDone (1 << 1)
|
||||
#define SX1262_IRQ_PreambleDetected (1 << 2)
|
||||
#define SX1262_IRQ_SyncWordValid (1 << 3)
|
||||
#define SX1262_IRQ_HeaderValid (1 << 4)
|
||||
#define SX1262_IRQ_HeaderError (1 << 5)
|
||||
#define SX1262_IRQ_CRCError (1 << 6)
|
||||
#define SX1262_IRQ_ChannelActivityDetectionDone (1 << 7)
|
||||
#define SX1262_IRQ_ChannelActivityDetected (1 << 8)
|
||||
#define SX1262_IRQ_Timeout (1 << 9)
|
||||
#define SX1262_IRQ_ALL (SX1262_IRQ_TXDone | SX1262_IRQ_RXDone | SX1262_IRQ_PreambleDetected | SX1262_IRQ_SyncWordValid | SX1262_IRQ_HeaderValid | SX1262_IRQ_HeaderError | SX1262_IRQ_CRCError | SX1262_IRQ_ChannelActivityDetectionDone | SX1262_IRQ_ChannelActivityDetected | SX1262_IRQ_Timeout)
|
||||
|
||||
#define SX1262_TCXO_VOLTAGE16dV 0x00
|
||||
#define SX1262_TCXO_VOLTAGE17dV 0x01
|
||||
#define SX1262_TCXO_VOLTAGE18dV 0x02
|
||||
#define SX1262_TCXO_VOLTAGE22dV 0x03
|
||||
#define SX1262_TCXO_VOLTAGE24dV 0x04
|
||||
#define SX1262_TCXO_VOLTAGE27dV 0x05
|
||||
#define SX1262_TCXO_VOLTAGE30dV 0x06
|
||||
#define SX1262_TCXO_VOLTAGE33dV 0x07
|
||||
|
||||
#define SX1262_PACKET_TYPE_GFSK 0x00
|
||||
#define SX1262_PACKET_TYPE_LORA 0x01
|
||||
|
||||
#define SX1262_Ramp_10U (0x00)
|
||||
#define SX1262_Ramp_20U (0x01)
|
||||
#define SX1262_Ramp_40U (0x02)
|
||||
#define SX1262_Ramp_80U (0x03)
|
||||
#define SX1262_Ramp_200U (0x04)
|
||||
#define SX1262_Ramp_800U (0x05)
|
||||
#define SX1262_Ramp_1700U (0x06)
|
||||
#define SX1262_Ramp_3400U (0x07)
|
||||
|
||||
#define SX1262_HEADER_TYPE_VARIABLE 0x00
|
||||
#define SX1262_HEADER_TYPE_FIXED 0x01
|
||||
|
||||
#define SX1262_CRC_OFF 0x00
|
||||
#define SX1262_CRC_ON 0x01
|
||||
|
||||
#define SX1262_STANDARD_IQ 0x00
|
||||
#define SX1262_INVERTED_IQ 0x01
|
||||
|
||||
#define SX1262_CAD_ON_1_SYMB 0x00
|
||||
#define SX1262_CAD_ON_2_SYMB 0x01
|
||||
#define SX1262_CAD_ON_4_SYMB 0x02
|
||||
#define SX1262_CAD_ON_8_SYMB 0x03
|
||||
#define SX1262_CAD_ON_16_SYMB 0x04
|
||||
#define SX1262_CAD_ONLY 0x00
|
||||
#define SX1262_CAD_RX 0x01
|
||||
|
||||
#define SX1262_ERROR_CALIBRATION_RC64K (1 << 0)
|
||||
#define SX1262_ERROR_CALIBRATION_RC13M (1 << 1)
|
||||
#define SX1262_ERROR_CALIBRATION_PLL (1 << 2)
|
||||
#define SX1262_ERROR_CALIBRATION_ADC (1 << 3)
|
||||
#define SX1262_ERROR_CALIBRATION_IMG (1 << 4)
|
||||
#define SX1262_ERROR_CALIBRATION_XOSC (1 << 5)
|
||||
#define SX1262_ERROR_PLL_LOCK (1 << 6)
|
||||
#define SX1262_ERROR_PA_RAMP (1 << 8)
|
||||
|
||||
#define SX1262_CALIB_RC64K (1 << 0) // RC64k calibration enabled
|
||||
#define SX1262_CALIB_RC13M (1 << 1) // RC13M calibration enabled
|
||||
#define SX1262_CALIB_PLL (1 << 2) // PLL calibration enabled
|
||||
#define SX1262_CALIB_ADC_PULSE (1 << 3) // ADC pulse calibration enabled
|
||||
#define SX1262_CALIB_ADC_BULK_N (1 << 4) // ADC bulk N calibration enabled
|
||||
#define SX1262_CALIB_ADC_BULK_P (1 << 5) // ADC bulk P calibration enabled
|
||||
#define SX1262_CALIB_IMAGE (1 << 6) // Image calibration enabled
|
||||
#define SX1262_CALIB_RESERVED (1 << 7) // Reserved bit (RFU)
|
||||
|
||||
// Combined mask for all calibration settings
|
||||
#define SX1262_CALIBRATION_ALL (SX1262_CALIB_RC64K | SX1262_CALIB_RC13M | \
|
||||
SX1262_CALIB_PLL | SX1262_CALIB_ADC_PULSE | \
|
||||
SX1262_CALIB_ADC_BULK_N | SX1262_CALIB_ADC_BULK_P | \
|
||||
SX1262_CALIB_IMAGE)
|
||||
|
||||
// GFSK Pulse Shape
|
||||
#define SX1262_GFSK_NO_FILTER (0x00)
|
||||
#define SX1262_GFSK_BT_0_3 (0x08)
|
||||
#define SX1262_GFSK_BT_0_5 (0x09)
|
||||
#define SX1262_GFSK_BT_0_7 (0x0A)
|
||||
#define SX1262_GFSK_BT_1_0 (0x0B)
|
||||
|
||||
// GFSK Bandwidth
|
||||
#define SX1262_GFSK_RX_BW_4800 (0x1F)
|
||||
#define SX1262_GFSK_RX_BW_5800 (0x17)
|
||||
#define SX1262_GFSK_RX_BW_7300 (0x0F)
|
||||
#define SX1262_GFSK_RX_BW_9700 (0x1E)
|
||||
#define SX1262_GFSK_RX_BW_11700 (0x16)
|
||||
#define SX1262_GFSK_RX_BW_14600 (0x0E)
|
||||
#define SX1262_GFSK_RX_BW_19500 (0x1D)
|
||||
#define SX1262_GFSK_RX_BW_23400 (0x15)
|
||||
#define SX1262_GFSK_RX_BW_29300 (0x0D)
|
||||
#define SX1262_GFSK_RX_BW_39000 (0x1C)
|
||||
#define SX1262_GFSK_RX_BW_46900 (0x14)
|
||||
#define SX1262_GFSK_RX_BW_58600 (0x0C)
|
||||
#define SX1262_GFSK_RX_BW_78200 (0x1B)
|
||||
#define SX1262_GFSK_RX_BW_93800 (0x13)
|
||||
#define SX1262_GFSK_RX_BW_117300 (0x0B)
|
||||
#define SX1262_GFSK_RX_BW_156200 (0x1A)
|
||||
#define SX1262_GFSK_RX_BW_187200 (0x12)
|
||||
#define SX1262_GFSK_RX_BW_234300 (0x0A)
|
||||
#define SX1262_GFSK_RX_BW_312000 (0x19)
|
||||
#define SX1262_GFSK_RX_BW_373600 (0x11)
|
||||
#define SX1262_GFSK_RX_BW_467000 (0x09)
|
||||
|
||||
// LoRa Spreading Factor (SF)
|
||||
#define SX1262_LORA_SF5 (0x05)
|
||||
#define SX1262_LORA_SF6 (0x06)
|
||||
#define SX1262_LORA_SF7 (0x07)
|
||||
#define SX1262_LORA_SF8 (0x08)
|
||||
#define SX1262_LORA_SF9 (0x09)
|
||||
#define SX1262_LORA_SF10 (0x0A)
|
||||
#define SX1262_LORA_SF11 (0x0B)
|
||||
#define SX1262_LORA_SF12 (0x0C)
|
||||
|
||||
// LoRa Bandwidth (BW)
|
||||
#define SX1262_LORA_BW_7 (0x00) // 7.81 kHz
|
||||
#define SX1262_LORA_BW_10 (0x08) // 10.42 kHz
|
||||
#define SX1262_LORA_BW_15 (0x01) // 15.63 kHz
|
||||
#define SX1262_LORA_BW_20 (0x09) // 20.83 kHz
|
||||
#define SX1262_LORA_BW_31 (0x02) // 31.25 kHz
|
||||
#define SX1262_LORA_BW_41 (0x0A) // 41.67 kHz
|
||||
#define SX1262_LORA_BW_62 (0x03) // 62.50 kHz
|
||||
#define SX1262_LORA_BW_125 (0x04) // 125 kHz
|
||||
#define SX1262_LORA_BW_250 (0x05) // 250 kHz
|
||||
#define SX1262_LORA_BW_500 (0x06) // 500 kHz
|
||||
|
||||
// LoRa Coding Rate (CR)
|
||||
#define SX1262_LORA_CR_4_5 (0x01)
|
||||
#define SX1262_LORA_CR_4_6 (0x02)
|
||||
#define SX1262_LORA_CR_4_7 (0x03)
|
||||
#define SX1262_LORA_CR_4_8 (0x04)
|
||||
|
||||
#define SX1262_LORA_SYNC_WORD_MSB (0x0740)
|
||||
#define SX1262_LORA_SYNC_WORD_LSB (0x0741)
|
||||
|
||||
void sx1262_setPacketType(uint8_t packetType);
|
||||
void sx1262_init();
|
||||
void sx1262_reset();
|
||||
void sx1262_wait_for_busy();
|
||||
void sx1262_write_command(uint8_t cmd, uint8_t *data, uint8_t len);
|
||||
void sx1262_read_command(uint8_t cmd, uint8_t *tx_payload_buffer, uint8_t tx_payload_len, uint8_t *rx_buffer, uint8_t len);
|
||||
sx1262_status_t sx1262_get_status();
|
||||
void sx1262_setSleep(uint8_t sleepCFG);
|
||||
void sx1262_setStandby(uint8_t standbyConf);
|
||||
void sx1262_setFrequencySynthesis();
|
||||
void sx1262_setMode(uint8_t mode, uint32_t timeout);
|
||||
void sx1262_stopTimerOnPreamble(uint8_t enable);
|
||||
void sx1262_setRxDutyCycle(uint32_t rxPeriod, uint32_t sleepPeriod);
|
||||
void sx1262_setChannelActivityDetection(void);
|
||||
void sx1262_setTxContinuousWave(void);
|
||||
void sx1262_setTxInfinitePreamble(void);
|
||||
void sx1262_setRegulatorMode(uint8_t mode);
|
||||
void sx1262_calibrate(uint8_t calibParam);
|
||||
void sx1262_calibrateImage(uint8_t freq1, uint8_t freq2);
|
||||
void sx1262_setRxTXFallbackMode(uint8_t fallbackMode);
|
||||
void sx1262_writeRegister(uint16_t address, const uint8_t *data, size_t length);
|
||||
void sx1262_readRegister(uint16_t address, uint8_t *data, size_t length);
|
||||
void sx1262_writeBuffer(uint8_t offset, const uint8_t *data, size_t length);
|
||||
void sx1262_readBuffer(uint8_t offset, uint8_t *data, size_t length);
|
||||
void sx1262_setDioIrqParams(uint16_t irqMask, uint16_t dio1Mask, uint16_t dio2Mask, uint16_t dio3Mask);
|
||||
uint16_t sx1262_getIrqStatus(void);
|
||||
void sx1262_clearIrqStatus(uint16_t clearIrqParam);
|
||||
void sx1262_setDIO2AsRfSwitchCtrl(uint8_t enable);
|
||||
void sx1262_setDIO3AsTCXOCtrl(uint8_t tcxoVoltage, uint32_t delay);
|
||||
void sx1262_setFrequency(uint32_t frequency);
|
||||
uint8_t sx1262_getPacketType();
|
||||
void sx1262_configure_tx_power(uint8_t paDutyCycle, uint8_t hpMax, uint8_t paLut, int8_t power, uint8_t rampTime);
|
||||
void sx1262_setLoRaPacketParams(sx1262_LoRaPacketParams_t *params);
|
||||
void sx1262_setCadParams(uint8_t cadSymbolNum, uint8_t cadDetPeak, uint8_t cadDetMin, uint8_t cadExitMode, uint32_t cadTimeout);
|
||||
void sx1262_setBufferBaseAddress(uint8_t txBaseAddr, uint8_t rxBaseAddr);
|
||||
void sx1262_setLoRaSymbNumTimeout(uint8_t symbNum);
|
||||
void sx1262_getStatus(uint8_t *status);
|
||||
void sx1262_getRxBufferStatus(uint8_t *payloadLengthRx, uint8_t *rxStartBufferPointer);
|
||||
void sx1262_getPacketStatus(uint8_t *rssi, uint8_t *snr, uint8_t *signalRssi);
|
||||
uint8_t sx1262_getRssiInst(uint8_t *rssiInst);
|
||||
void sx1262_getStats(uint16_t *pktReceived, uint16_t *pktCrcError, uint16_t *pktHeaderErr);
|
||||
void sx1262_resetStats(void);
|
||||
uint16_t sx1262_getDeviceErrors();
|
||||
void sx1262_clearDeviceErrors(void);
|
||||
|
||||
void sx1262_setLoRaModulationParams(const sx1262_LoRaModulationParams_t *params);
|
||||
|
||||
void sx1262_setGFSKModulationParams(const sx1262_GFSKModulationParams_t *params);
|
||||
|
||||
#endif
|
Reference in New Issue
Block a user