diff --git a/Makefile b/Makefile index 3d37689..e537e7c 100644 --- a/Makefile +++ b/Makefile @@ -250,6 +250,8 @@ INCLUDES := \ -Iapps/earphone/xtell_Sensor \ -Iapps/earphone/xtell_Sensor/calculate \ -Iapps/earphone/xtell_Sensor/ano \ + -Iapps/earphone/xtell_Sensor/sensor/ \ + -Iapps/earphone/xtell_Sensor/sensor/ \ -I$(SYS_INC_DIR) \ @@ -622,6 +624,8 @@ c_SRC_FILES := \ apps/earphone/xtell_Sensor/sensor/SC7U22.c \ apps/earphone/xtell_Sensor/calculate/skiing_tracker.c \ apps/earphone/xtell_Sensor/ano/ano_protocol.c \ + apps/earphone/xtell_Sensor/sensor/MMC56.c \ + apps/earphone/xtell_Sensor/sensor/BMP280.c \ # 需要编译的 .S 文件 diff --git a/apps/common/device/gSensor/gSensor_manage.c b/apps/common/device/gSensor/gSensor_manage.c index abe9ad5..53ab6b6 100644 --- a/apps/common/device/gSensor/gSensor_manage.c +++ b/apps/common/device/gSensor/gSensor_manage.c @@ -212,6 +212,42 @@ void write_gsensor_data_handle(void) } } +// 临时的设备扫描诊断函数 +void i2c_scanner_probe(void) +{ + printf("Starting I2C bus scan...\n"); + int devices_found = 0; + + // I2C地址范围是 0x08 到 0x77 + for (uint8_t addr_7bit = 0x00; addr_7bit < 0x7F; addr_7bit++) + { + // 构建8位的写地址 + uint8_t write_addr_8bit = (addr_7bit << 1); + + iic_start(gSensor_info->iic_hdl); + + // 尝试发送写地址,并检查返回值 + // iic_tx_byte 返回 1 表示收到了 ACK + if (iic_tx_byte(gSensor_info->iic_hdl, write_addr_8bit)) + { + printf("=====================================================================\n"); + printf("I2C device found at 7-bit address: 0x%02X\n", addr_7bit); + printf("I2C device found at 8-bit address: 0x%02X\n", write_addr_8bit); + printf("=====================================================================\n"); + devices_found++; + } + + iic_stop(gSensor_info->iic_hdl); + delay(gSensor_info->iic_delay); // 短暂延时 + } + + if (devices_found == 0) { + printf("Scan finished. No I2C devices found.\n"); + } else { + printf("Scan finished. Found %d device(s).\n", devices_found); + } +} + char w_log_buffer_1[100]; char w_log_buffer_2[100]; char w_log_buffer_3[100]; @@ -222,7 +258,10 @@ u8 gravity_sensor_command(u8 w_chip_id, u8 register_address, u8 function_command // spin_lock(&sensor_iic); /* os_mutex_pend(&SENSOR_IIC_MUTEX,0); */ u8 ret = 1; + // xlog("iic_start\n"); iic_start(gSensor_info->iic_hdl); + + // xlog("iic_tx_byte id\n"); if (0 == iic_tx_byte(gSensor_info->iic_hdl, w_chip_id)) { ret = 0; xlog("\n gsen iic wr err 0\n"); @@ -230,8 +269,10 @@ u8 gravity_sensor_command(u8 w_chip_id, u8 register_address, u8 function_command goto __gcend; } + // xlog("iic delay\n"); delay(gSensor_info->iic_delay); + // xlog("iic_tx_byte: address\n"); if (0 == iic_tx_byte(gSensor_info->iic_hdl, register_address)) { ret = 0; xlog("\n gsen iic wr err 1\n"); @@ -241,6 +282,7 @@ u8 gravity_sensor_command(u8 w_chip_id, u8 register_address, u8 function_command delay(gSensor_info->iic_delay); + // xlog("iic_tx_byte: command\n"); if (0 == iic_tx_byte(gSensor_info->iic_hdl, function_command)) { ret = 0; xlog("\n gsen iic wr err 2\n"); @@ -249,6 +291,7 @@ u8 gravity_sensor_command(u8 w_chip_id, u8 register_address, u8 function_command } strcpy(&w_log_buffer_4, "gsen iic wr sucess\n"); + // xlog("\n gsen iic wr sucess\n"); __gcend: iic_stop(gSensor_info->iic_hdl); @@ -304,6 +347,7 @@ u8 _gravity_sensor_get_ndata(u8 r_chip_id, u8 register_address, u8 *buf, u8 data *buf = iic_rx_byte(gSensor_info->iic_hdl, 0); read_len ++; strcpy(&sen_log_buffer_4, "gsen iic rd success\n"); + // xlog("\n gsen iic rd success\n"); __gdend: diff --git a/apps/earphone/xtell_Sensor/ano/ano_protocol.c b/apps/earphone/xtell_Sensor/ano/ano_protocol.c index 344d9b5..e0720b8 100644 --- a/apps/earphone/xtell_Sensor/ano/ano_protocol.c +++ b/apps/earphone/xtell_Sensor/ano/ano_protocol.c @@ -1,8 +1,12 @@ +/* + 发送数据给上位机的,需要将log打印出口关闭 +*/ + #include "ano_protocol.h" #include "asm/uart_dev.h" -#include "app_config.h" // 需要包含这个头文件来获取 TCFG_ONLINE_TX_PORT 等宏定义 +#include "app_config.h" -// 定义匿名协议常量 +// 定义协议常量 #define ANO_FRAME_HEADER 0xAA #define ANO_TO_COMPUTER_ADDR 0xFF @@ -10,7 +14,7 @@ static const uart_bus_t *ano_uart_dev = NULL; /** - * @brief 计算并填充匿名协议的校验和 + * @brief 计算并填充协议的校验和 * @param frame_buffer 指向数据帧缓冲区的指针 */ static void ano_calculate_checksum(u8 *frame_buffer) { @@ -35,7 +39,7 @@ static void ano_calculate_checksum(u8 *frame_buffer) { } /** - * @brief 初始化用于匿名上位机通信的串口 + * @brief 初始化用于上位机通信的串口 */ int ano_protocol_init(u32 baudrate) { #if TCFG_UART0_ENABLE==0 @@ -47,7 +51,6 @@ int ano_protocol_init(u32 baudrate) { struct uart_platform_data_t ut_arg = {0}; // TCFG_ONLINE_TX_PORT 和 TCFG_ONLINE_RX_PORT 通常在 app_config.h 中定义 - // 请确保您的 app_config.h 中有正确的引脚配置 ut_arg.tx_pin = TCFG_ONLINE_TX_PORT; ut_arg.rx_pin = (u8)-1; // -1 表示不使用该引脚,因为我们只发送数据 ut_arg.baud = baudrate; diff --git a/apps/earphone/xtell_Sensor/send_data.c b/apps/earphone/xtell_Sensor/send_data.c index b17cf47..dfbab79 100644 --- a/apps/earphone/xtell_Sensor/send_data.c +++ b/apps/earphone/xtell_Sensor/send_data.c @@ -21,6 +21,8 @@ #include "calculate/skiing_tracker.h" #include "xtell.h" #include "./ano/ano_protocol.h" +#include "./sensor/MMC56.h" +#include "./sensor/BMP280.h" /////////////////////////////////////////////////////////////////////////////////////////////////// //宏定义 #define ENABLE_XLOG 1 @@ -460,56 +462,66 @@ void xt_hw_iic_test(){ void sensor_measure(void){ // xlog("=======sensor_read_data START\n"); - static signed short combined_raw_data[6]; - static int initialized = 0; - static int calibration_done = 0; - char status = 0; + // static signed short combined_raw_data[6]; + // static int initialized = 0; + // static int calibration_done = 0; + // char status = 0; - if(count_test1 >= 100){ - count_test1 = 0; - xlog("count_test1\n"); - } - count_test1++; + // if(count_test1 >= 100){ + // count_test1 = 0; + // xlog("count_test1\n"); + // } + // count_test1++; - static sensor_data_t tmp; - SL_SC7U22_RawData_Read(tmp.acc_data,tmp.gyr_data); - // xlog("=======sensor_read_data middle 1\n"); - memcpy(&combined_raw_data[0], tmp.acc_data, 3 * sizeof(signed short)); - memcpy(&combined_raw_data[3], tmp.gyr_data, 3 * sizeof(signed short)); + // static sensor_data_t tmp; + // SL_SC7U22_RawData_Read(tmp.acc_data,tmp.gyr_data); + // // xlog("=======sensor_read_data middle 1\n"); + // memcpy(&combined_raw_data[0], tmp.acc_data, 3 * sizeof(signed short)); + // memcpy(&combined_raw_data[3], tmp.gyr_data, 3 * sizeof(signed short)); - if (!calibration_done) { //第1次启动,开启零漂检测 - // status = SL_SC7U22_Angle_Output(1, combined_raw_data, tmp.angle, 0); - // status = SIX_SL_SC7U22_Angle_Output(1, combined_raw_data, tmp.angle, 0); - // status = Original_SL_SC7U22_Angle_Output(1, combined_raw_data, tmp.angle, 0); - status = Q_SL_SC7U22_Angle_Output(1, combined_raw_data, tmp.angle, 0, tmp.quaternion_output); + // if (!calibration_done) { //第1次启动,开启零漂检测 + // // status = SL_SC7U22_Angle_Output(1, combined_raw_data, tmp.angle, 0); + // // status = SIX_SL_SC7U22_Angle_Output(1, combined_raw_data, tmp.angle, 0); + // // status = Original_SL_SC7U22_Angle_Output(1, combined_raw_data, tmp.angle, 0); + // status = Q_SL_SC7U22_Angle_Output(1, combined_raw_data, tmp.angle, 0, tmp.quaternion_output); - int count = 0; - if(count > 100){ - count = 0; - char log_buffer[100]; - // snprintf( log_buffer, sizeof(log_buffer),"status:%d\n",status); - // send_data_to_ble_client(&log_buffer,strlen(log_buffer)); - xlog("status:%d\n", status); - } - count++; + // int count = 0; + // if(count > 100){ + // count = 0; + // char log_buffer[100]; + // // snprintf( log_buffer, sizeof(log_buffer),"status:%d\n",status); + // // send_data_to_ble_client(&log_buffer,strlen(log_buffer)); + // xlog("status:%d\n", status); + // } + // count++; - if (status == 1) { - calibration_done = 1; - printf("Sensor calibration successful! Skiing mode is active.\n"); - } - } else { - // printf("Calculate the time interval =============== start\n"); - // status = SL_SC7U22_Angle_Output(0, combined_raw_data, tmp.angle, 0); - // status = SIX_SL_SC7U22_Angle_Output(0, combined_raw_data, tmp.angle, 0); - // status = Original_SL_SC7U22_Angle_Output(0, combined_raw_data, tmp.angle, 0); - status = Q_SL_SC7U22_Angle_Output(0, combined_raw_data, tmp.angle, 0, tmp.quaternion_output); - memcpy(tmp.acc_data, &combined_raw_data[0], 3 * sizeof(signed short)); - memcpy(tmp.gyr_data, &combined_raw_data[3], 3 * sizeof(signed short)); - BLE_send_data_t data_by_calculate = sensor_processing_task(tmp.acc_data, tmp.gyr_data,tmp.angle, tmp.quaternion_output); - extern void ano_send_attitude_data(float rol, float pit, float yaw, uint8_t fusion_sta) ; - ano_send_attitude_data(tmp.angle[0],tmp.angle[1],tmp.angle[2], 1); - } + // if (status == 1) { + // calibration_done = 1; + // printf("Sensor calibration successful! Skiing mode is active.\n"); + // } + // } else { + // // printf("Calculate the time interval =============== start\n"); + // // status = SL_SC7U22_Angle_Output(0, combined_raw_data, tmp.angle, 0); + // // status = SIX_SL_SC7U22_Angle_Output(0, combined_raw_data, tmp.angle, 0); + // // status = Original_SL_SC7U22_Angle_Output(0, combined_raw_data, tmp.angle, 0); + // status = Q_SL_SC7U22_Angle_Output(0, combined_raw_data, tmp.angle, 0, tmp.quaternion_output); + // memcpy(tmp.acc_data, &combined_raw_data[0], 3 * sizeof(signed short)); + // memcpy(tmp.gyr_data, &combined_raw_data[3], 3 * sizeof(signed short)); + // BLE_send_data_t data_by_calculate = sensor_processing_task(tmp.acc_data, tmp.gyr_data,tmp.angle, tmp.quaternion_output); + // extern void ano_send_attitude_data(float rol, float pit, float yaw, uint8_t fusion_sta) ; + // ano_send_attitude_data(tmp.angle[0],tmp.angle[1],tmp.angle[2], 1); + + // } + + mmc5603nj_mag_data_t mag_data; + // mmc5603nj_read_mag_data(&mag_data); + + // if(count_test2 > 100){ + // count_test2++; + printf("Mag X: %.4f, Y: %.4f, Z: %.4f Gauss\n", mag_data.x, mag_data.y, mag_data.z); + // } + // count_test2++; // xlog("=======sensor_read_data END\n"); } @@ -539,8 +551,27 @@ void xtell_task_create(void){ // delay_2ms(10); SL_SC7U22_Config(); - // extern u8 LIS2DH12_Config(void); - // LIS2DH12_Config(); + // if (mmc5603nj_init() != 0) { + // xlog("MMC5603NJ initialization failed!\n"); + // } + // xlog("MMC5603NJ PID: 0x%02X\n", mmc5603nj_get_pid()); + // // 启用连续测量模式 + // mmc5603nj_enable_continuous_mode(); + // xlog("Continuous measurement mode enabled.\n"); + + //iic总线设备扫描 + extern void i2c_scanner_probe(void); + i2c_scanner_probe(); + + if(bmp280_init() != 0){ + xlog("bmp280 init error\n"); + } + float temp, press; + bmp280_read_data(&temp, &press); + xlog("get temp: %d, get press: %d\n",temp, press); + + + xlog("xtell_task_create\n"); // 初始化环形缓冲区 @@ -548,7 +579,7 @@ void xtell_task_create(void){ ano_protocol_init(115200); - create_process(&calculate_data_id, "calculate",NULL, sensor_measure, 10); + create_process(&calculate_data_id, "calculate",NULL, sensor_measure, 2000); circle_buffer_init(&sensor_read, sensor_read_buffer, SENSOR_DATA_BUFFER_SIZE, sizeof(sensor_data_t)); diff --git a/apps/earphone/xtell_Sensor/sensor/BMP280.c b/apps/earphone/xtell_Sensor/sensor/BMP280.c new file mode 100644 index 0000000..2b217f5 --- /dev/null +++ b/apps/earphone/xtell_Sensor/sensor/BMP280.c @@ -0,0 +1,178 @@ +/* + 气压计 +*/ +#include "BMP280.h" +#include +#include "os/os_api.h" +#include "gSensor/gSensor_manage.h" + +/*==================================================================================*/ +/* BMP280 内部定义 */ +/*==================================================================================*/ + +// 存储校准参数的静态全局变量 +static uint16_t t1; +static int16_t t2, t3; +static uint16_t p1; +static int16_t p2, p3, p4, p5, p6, p7, p8, p9; +static int32_t t_fine; + +/*==================================================================================*/ +/* 封装的底层I2C读写函数 */ +/*==================================================================================*/ + +/** + * @brief 写入单个字节到BMP280寄存器 + */ +static uint8_t bmp280_write_reg(uint8_t reg, uint8_t data) { + gravity_sensor_command(BMP_IIC_WRITE_ADDRESS, reg, data); + return 0; +} + +/** + * @brief 从BMP280读取多个字节 + */ +static uint8_t bmp280_read_regs(uint8_t reg, uint8_t *buf, uint16_t len) { + return _gravity_sensor_get_ndata(BMP_IIC_READ_ADDRESS, reg, buf, len); +} + +/*==================================================================================*/ +/* 核心算法 */ +/*==================================================================================*/ + +/** + * @brief 温度补偿计算 + * @param adc_T - 原始温度数据 + * @return 补偿后的温度值 (单位: °C) + */ +static float compensate_temperature(int32_t adc_T) { + float var1, var2, temperature; + + var1 = (((float)adc_T) / 16384.0f - ((float)t1) / 1024.0f) * ((float)t2); + var2 = ((((float)adc_T) / 131072.0f - ((float)t1) / 8192.0f) * + (((float)adc_T) / 131072.0f - ((float)t1) / 8192.0f)) * + ((float)t3); + t_fine = (int32_t)(var1 + var2); + temperature = (var1 + var2) / 5120.0f; + + if (temperature < -40.0f) return -40.0f; + if (temperature > 85.0f) return 85.0f; + + return temperature; +} + +/** + * @brief 气压补偿计算 + * @param adc_P - 原始气压数据 + * @return 补偿后的气压值 (单位: Pa) + */ +static float compensate_pressure(int32_t adc_P) { + float var1, var2, pressure; + + var1 = ((float)t_fine / 2.0f) - 64000.0f; + var2 = var1 * var1 * ((float)p6) / 32768.0f; + var2 = var2 + var1 * ((float)p5) * 2.0f; + var2 = (var2 / 4.0f) + (((float)p4) * 65536.0f); + var1 = (((float)p3) * var1 * var1 / 524288.0f + ((float)p2) * var1) / 524288.0f; + var1 = (1.0f + var1 / 32768.0f) * ((float)p1); + + if (var1 == 0.0f) { + return 0; // 避免除以零 + } + + pressure = 1048576.0f - (float)adc_P; + pressure = (pressure - (var2 / 4096.0f)) * 6250.0f / var1; + var1 = ((float)p9) * pressure * pressure / 2147483648.0f; + var2 = pressure * ((float)p8) / 32768.0f; + pressure = pressure + (var1 + var2 + ((float)p7)) / 16.0f; + + if (pressure < 30000.0f) return 30000.0f; + if (pressure > 110000.0f) return 110000.0f; + + return pressure; +} + +/*==================================================================================*/ +/* 外部接口函数实现 */ +/*==================================================================================*/ + + + + +uint8_t bmp280_init(void) { + uint8_t id; + uint8_t calib_data[24]; + + // 1. 检查芯片ID + if (bmp280_read_regs(BMP280_REG_ID, &id, 1) == 0) { + printf("bmp280 get id error:%d\n",id ); + return 1; // I2C读取失败 + } + if (id != 0x58) { + printf("bmp280 check diff:%d\n",id ); + return 1; // ID不匹配 + } + + // 2. 软复位 + bmp280_write_reg(BMP280_REG_RESET, 0xB6); + os_time_dly(10); // 等待复位完成 + + // 3. 一次性读取所有校准参数 + if (bmp280_read_regs(BMP280_REG_CALIB_START, calib_data, 24) != 0) { + return 2; // 读取校准数据失败 + } + + // 4. 解析校准参数 + t1 = (uint16_t)(((uint16_t)calib_data[1] << 8) | calib_data[0]); + t2 = (int16_t)(((int16_t)calib_data[3] << 8) | calib_data[2]); + t3 = (int16_t)(((int16_t)calib_data[5] << 8) | calib_data[4]); + p1 = (uint16_t)(((uint16_t)calib_data[7] << 8) | calib_data[6]); + p2 = (int16_t)(((int16_t)calib_data[9] << 8) | calib_data[8]); + p3 = (int16_t)(((int16_t)calib_data[11] << 8) | calib_data[10]); + p4 = (int16_t)(((int16_t)calib_data[13] << 8) | calib_data[12]); + p5 = (int16_t)(((int16_t)calib_data[15] << 8) | calib_data[14]); + p6 = (int16_t)(((int16_t)calib_data[17] << 8) | calib_data[16]); + p7 = (int16_t)(((int16_t)calib_data[19] << 8) | calib_data[18]); + p8 = (int16_t)(((int16_t)calib_data[21] << 8) | calib_data[20]); + p9 = (int16_t)(((int16_t)calib_data[23] << 8) | calib_data[22]); + + // 5. 配置传感器 (推荐设置: 正常模式,高精度) + // t_standby=0.5ms, filter=16, spi_en=0 + uint8_t config_reg = (0 << 5) | (4 << 2) | (0 << 0); + bmp280_write_reg(BMP280_REG_CONFIG, config_reg); + + // osrs_t=x2, osrs_p=x16, mode=normal + uint8_t ctrl_meas_reg = (2 << 5) | (5 << 2) | (3 << 0); + bmp280_write_reg(BMP280_REG_CTRL_MEAS, ctrl_meas_reg); + + os_time_dly(10); // 等待配置生效 + + return 0; // 初始化成功 +} + +uint8_t bmp280_read_data(float *temperature, float *pressure) { + uint8_t data[6]; + int32_t adc_P, adc_T; + + // 一次性读取6个字节的温度和气压原始数据 + if (bmp280_read_regs(BMP280_REG_PRESS_MSB, data, 6) != 0) { + return 1; // 读取失败 + } + + // 组合原始数据 (20位) + adc_P = (int32_t)((((uint32_t)(data[0])) << 12) | (((uint32_t)(data[1])) << 4) | (((uint32_t)(data[2])) >> 4)); + adc_T = (int32_t)((((uint32_t)(data[3])) << 12) | (((uint32_t)(data[4])) << 4) | (((uint32_t)(data[5])) >> 4)); + + // 如果没有数据,直接返回错误 (ADC读数为0x80000是未测量状态) + if (adc_T == 0x80000 || adc_P == 0x80000) { + *temperature = 0.0f; + *pressure = 0.0f; + return 1; + } + + // 进行补偿计算 + *temperature = compensate_temperature(adc_T); + *pressure = compensate_pressure(adc_P); + + return 0; // 成功 +} \ No newline at end of file diff --git a/apps/earphone/xtell_Sensor/sensor/BMP280.h b/apps/earphone/xtell_Sensor/sensor/BMP280.h new file mode 100644 index 0000000..c1683e5 --- /dev/null +++ b/apps/earphone/xtell_Sensor/sensor/BMP280.h @@ -0,0 +1,48 @@ +#ifndef BMP280_DRIVER_H +#define BMP280_DRIVER_H + +#include + + +#define BMP_PULL_UP 0 //外部是否接的上拉 + +// I2C 从设备地址 +#if BMP_PULL_UP == 1 //外部接的高 +#define BMP_IIC_7BIT_ADDRESS 0x77 //7位,外部接高为0x77 +#define BMP_IIC_WRITE_ADDRESS (BMP_IIC_7BIT_ADDRESS<<1) //8位地址 +#define BMP_IIC_READ_ADDRESS (BMP_IIC_WRITE_ADDRESS | 0x01) +#else +#define BMP_IIC_7BIT_ADDRESS 0x76 //7位,外部接低为0x76 +#define BMP_IIC_WRITE_ADDRESS (BMP_IIC_7BIT_ADDRESS<<1) //8位地址 +#define BMP_IIC_READ_ADDRESS (BMP_IIC_WRITE_ADDRESS | 0x01) +#endif + +// BMP280 I2C 地址 (SDO/ADO 引脚接地) +#define BMP280_I2C_ADDR_LOW (0x76*2) +//7位地址:76, 8位地址:EC (接地) + +// BMP280 寄存器地址 +#define BMP280_REG_CALIB_START 0x88 +#define BMP280_REG_ID 0xD0 +#define BMP280_REG_RESET 0xE0 +#define BMP280_REG_STATUS 0xF3 +#define BMP280_REG_CTRL_MEAS 0xF4 +#define BMP280_REG_CONFIG 0xF5 +#define BMP280_REG_PRESS_MSB 0xF7 + +/** + * @brief 初始化BMP280传感器 + * @return 0: 成功, 1: 芯片ID错误, 2: 读取校准参数失败 + * @note 此函数会完成ID检查、软复位、读取校准参数,并设置传感器为连续测量模式。 + */ +uint8_t bmp280_init(void); + +/** + * @brief 从BMP280读取温度和气压数据 + * @param[out] temperature - 指向浮点数变量的指针,用于存储温度值 (单位: °C) + * @param[out] pressure - 指向浮点数变量的指针,用于存储气压值 (单位: Pa) + * @return 0: 成功, 1: 读取数据失败 + */ +uint8_t bmp280_read_data(float *temperature, float *pressure); + +#endif // BMP280_DRIVER_H \ No newline at end of file diff --git a/apps/earphone/xtell_Sensor/sensor/MMC56.c b/apps/earphone/xtell_Sensor/sensor/MMC56.c new file mode 100644 index 0000000..ac9e344 --- /dev/null +++ b/apps/earphone/xtell_Sensor/sensor/MMC56.c @@ -0,0 +1,157 @@ +/* + 三轴磁力计 - MMC5603NJ +*/ + +#include "MMC56.h" +#include "math.h" +#include "os/os_api.h" +#include "../xtell.h" +#include "gSensor/gSensor_manage.h" +#include "printf.h" + + +#define ENABLE_XLOG 1 +#ifdef xlog +#undef xlog +#endif +#if ENABLE_XLOG + #define xlog(format, ...) printf("[XT:%s] " format, __func__, ##__VA_ARGS__) +#else + #define xlog(format, ...) ((void)0) +#endif + +/*==================================================================================*/ +/* MMC5603NJ 内部定义 */ +/*==================================================================================*/ + +// 用于跟踪当前是否处于连续测量模式 +static u8 g_continuous_mode_enabled = 0; + +/*==================================================================================*/ +/* 封装的底层I2C读写函数 */ +/*==================================================================================*/ + +/** + * @brief 写入单个字节到MMC5603NJ寄存器 + */ +static void mmc5603nj_write_reg(uint8_t reg, uint8_t data) { + gravity_sensor_command(MMC_IIC_WRITE_ADDRESS, reg, data); +} + +/** + * @brief 从MMC5603NJ读取多个字节 + */ +static uint32_t mmc5603nj_read_regs(uint8_t reg, uint8_t *buf, uint8_t len) { + return _gravity_sensor_get_ndata(MMC_IIC_READ_ADDRESS, reg, buf, len); +} + +/*==================================================================================*/ +/* 外部接口函数实现 */ +/*==================================================================================*/ + +uint8_t mmc5603nj_get_pid(void) { + uint8_t pid = 0; + mmc5603nj_read_regs(MMC_PID, &pid, 1); + return pid; +} + +int mmc5603nj_init(void) { + // 检查产品ID是否正确 + if (mmc5603nj_get_pid() != 0x10) { + xlog("init error: check id error %d\n", mmc5603nj_get_pid()); + return -1; // 设备ID不匹配 + } + + // 对传感器执行软件复位 (将 INCTRL0 寄存器的 Do_reset 位置1) + mmc5603nj_write_reg(MMC_INCTRL0, 0x08); + os_time_dly(20); // 等待复位完成 + + g_continuous_mode_enabled = 0; + return 0; // 初始化成功 +} + +void mmc5603nj_set_data_rate(uint8_t rate) { + mmc5603nj_write_reg(MMC_ODR, rate); +} + +void mmc5603nj_enable_continuous_mode(void) { + uint8_t reg_val; + + // 启用连续模式需要设置 INCTRL0 和 INCTRL2 寄存器 + // 1. 设置 INCTRL0 的 Cmm_en 位 (bit 7) + mmc5603nj_read_regs(MMC_INCTRL0, ®_val, 1); + reg_val |= 0x80; + mmc5603nj_write_reg(MMC_INCTRL0, reg_val); + + // 2. 设置 INCTRL2 的 Cmm_freq_en 位 (bit 4) + mmc5603nj_read_regs(MMC_INCTRL2, ®_val, 1); + reg_val |= 0x10; + mmc5603nj_write_reg(MMC_INCTRL2, reg_val); + + g_continuous_mode_enabled = 1; +} + +void mmc5603nj_disable_continuous_mode(void) { + uint8_t reg_val; + + // 禁用连续模式只需要清除 INCTRL2 的 Cmm_freq_en 位 + mmc5603nj_read_regs(MMC_INCTRL2, ®_val, 1); + reg_val &= ~0x10; // 清除 bit 4 + mmc5603nj_write_reg(MMC_INCTRL2, reg_val); + + g_continuous_mode_enabled = 0; +} + +float mmc5603nj_get_temperature(void) { + uint8_t status = 0; + uint8_t temp_raw = 0; + + // 1. 触发一次温度测量 (写入 0x02 到 INCTRL0 寄存器) + mmc5603nj_write_reg(MMC_INCTRL0, 0x02); + + // 2. 等待测量完成 (轮询 STATUS1 寄存器的 Meas_T_done 位) + do { + os_time_dly(10); // 等待一下,避免过于频繁的I2C读取 + mmc5603nj_read_regs(MMC_STATUS1, &status, 1); + } while ((status & 0x80) == 0); + + // 3. 读取温度原始值 + mmc5603nj_read_regs(MMC_TOUT, &temp_raw, 1); + + // 4. 根据公式计算实际温度: Temp(°C) = -75 + 0.8 * TOUT + return ((float)temp_raw * 0.8f) - 75.0f; +} + +void mmc5603nj_read_mag_data(mmc5603nj_mag_data_t *mag_data) { + uint8_t buffer[9]; + + if (g_continuous_mode_enabled) { + // 连续模式下,直接读取数据即可 + mmc5603nj_read_regs(MMC_XOUT0, buffer, 9); + } else { + // 单次测量模式 + uint8_t status = 0; + // 1. 触发一次磁场测量 (写入 0x01 到 INCTRL0 寄存器) + mmc5603nj_write_reg(MMC_INCTRL0, 0x01); + + // 2. 等待测量完成 (轮询 STATUS1 寄存器的 Meas_M_done 位) + do { + os_time_dly(10); // 等待一下 + mmc5603nj_read_regs(MMC_STATUS1, &status, 1); + } while ((status & 0x40) == 0); + + // 3. 读取9个字节的原始数据 + mmc5603nj_read_regs(MMC_XOUT0, buffer, 9); + } + + // 解析数据 (20位分辨率) + // 零点偏置: 2^19 = 524288, 灵敏度: 2^14 = 16384 LSB/Gauss + int32_t raw_x = (buffer[0] << 12) | (buffer[1] << 4) | (buffer[6] >> 4); + int32_t raw_y = (buffer[2] << 12) | (buffer[3] << 4) | (buffer[7] >> 4); + int32_t raw_z = (buffer[4] << 12) | (buffer[5] << 4) | (buffer[8] >> 4); + + // 应用偏置和灵敏度进行转换 + mag_data->x = ((float)raw_x - 524288.0f) / 16384.0f; + mag_data->y = ((float)raw_y - 524288.0f) / 16384.0f; + mag_data->z = ((float)raw_z - 524288.0f) / 16384.0f; +} \ No newline at end of file diff --git a/apps/earphone/xtell_Sensor/sensor/MMC56.h b/apps/earphone/xtell_Sensor/sensor/MMC56.h new file mode 100644 index 0000000..8733121 --- /dev/null +++ b/apps/earphone/xtell_Sensor/sensor/MMC56.h @@ -0,0 +1,89 @@ +#ifndef MMC5603NJ_DRIVER_H +#define MMC5603NJ_DRIVER_H + +#include + + +//该芯片的iic地址是固定的, 没法通过外部上下拉来改变 +#define BMP_IIC_7BIT_ADDRESS 0x30 //0110000 手册第12页 +//8位地址: +#define MMC_IIC_WRITE_ADDRESS (BMP_IIC_7BIT_ADDRESS <<1) // 0x60 : 01100000 +#define MMC_IIC_READ_ADDRESS (MMC_IIC_WRITE_ADDRESS | 0x01) // 0x61 : 01100001 + + + +// 寄存器地址定义 -- 数据手册第6页 +#define MMC_XOUT0 0x00 +#define MMC_XOUT1 0x01 +#define MMC_YOUT0 0x02 +#define MMC_YOUT1 0x03 +#define MMC_ZOUT0 0x04 +#define MMC_ZOUT1 0x05 +#define MMC_XOUT2 0x06 +#define MMC_YOUT2 0x07 +#define MMC_ZOUT2 0x08 +#define MMC_TOUT 0x09 +#define MMC_STATUS1 0x18 +#define MMC_ODR 0x1A +#define MMC_INCTRL0 0x1B +#define MMC_INCTRL1 0x1C +#define MMC_INCTRL2 0x1D +#define MMC_ST_X_TH 0x1E +#define MMC_ST_Y_TH 0x1F +#define MMC_ST_Z_TH 0x20 +#define MMC_ST_X 0x27 +#define MMC_ST_Y 0x28 +#define MMC_ST_Z 0x29 +#define MMC_PID 0x39 + +// 定义一个结构体来存放三轴磁场数据(单位:高斯 Gauss) +typedef struct { + float x; + float y; + float z; +} mmc5603nj_mag_data_t; + + +/** + * @brief 初始化MMC5603NJ传感器 + * 该函数会对传感器进行软件复位,并检查设备ID。 + * @return 0 表示成功, -1 表示失败 (设备ID不匹配). + */ +int mmc5603nj_init(void); + +/** + * @brief 设置传感器的数据输出速率 (ODR - Output Data Rate) + * @param rate 速率值,具体含义请参考datasheet ODR寄存器说明。 + */ +void mmc5603nj_set_data_rate(uint8_t rate); + +/** + * @brief 启用连续测量模式 + */ +void mmc5603nj_enable_continuous_mode(void); + +/** + * @brief 禁用连续测量模式 + */ +void mmc5603nj_disable_continuous_mode(void); + +/** + * @brief 获取产品ID + * @return 产品的ID值,对于MMC5603NJ,应为0x10. + */ +uint8_t mmc5603nj_get_pid(void); + +/** + * @brief 读取传感器的温度 + * @return 温度值 (单位: 摄氏度 °C). + */ +float mmc5603nj_get_temperature(void); + +/** + * @brief 读取三轴磁场数据 + * 此函数会根据当前是连续模式还是单次模式来读取数据。 + * @param mag_data 指向 mmc5603nj_mag_data_t 结构体的指针,用于存放结果。 + */ +void mmc5603nj_read_mag_data(mmc5603nj_mag_data_t *mag_data); + +#endif // MMC5603NJ_DRIVER_H \ No newline at end of file diff --git a/apps/earphone/xtell_Sensor/sensor/SC7U22.c b/apps/earphone/xtell_Sensor/sensor/SC7U22.c index 771c379..93d182c 100644 --- a/apps/earphone/xtell_Sensor/sensor/SC7U22.c +++ b/apps/earphone/xtell_Sensor/sensor/SC7U22.c @@ -1,4 +1,6 @@ - +/* + 六轴 +*/ #include "SC7U22.h" #include "math.h" #include "os/os_api.h" @@ -68,9 +70,12 @@ char iic_write_result; unsigned char SL_SC7U22_Check(void) { unsigned char reg_value=0; - xlog("SL_SC7U22_Check\n"); + iic_write_result = SL_SC7U22_I2c_Spi_Write(SL_SPI_IIC_INTERFACE, 0x7F, 0x00);//goto 0x00 + // xlog("SL_SC7U22_Check write: %d\n", iic_write_result); + iic_read_len = SL_SC7U22_I2c_Spi_Read(SL_SPI_IIC_INTERFACE, SC7U22_WHO_AM_I, 1, ®_value); + // xlog("SL_SC7U22_Check read : %d\n", iic_write_result); xlog("0x%x=0x%x\r\n",SC7U22_WHO_AM_I,reg_value); if(reg_value==0x6A) //设备的id return 0x01;//SC7U22 @@ -1007,10 +1012,6 @@ unsigned char SL_SC7U22_Angle_Output(unsigned char calibration_en, signed short /** * @brief 姿态角解算函数 (基于一阶互补滤波) * @details - * 该函数主要完成两项工作: - * 1. 静态校准:在初始阶段,检测传感器是否处于静止状态。如果是,则计算加速度计和陀螺仪的零点偏移(误差),用于后续的数据补偿。 - * 2. 姿态解算:使用一阶互补滤波器融合经过校准后的加速度计和陀螺仪数据,计算出物体的俯仰角(Pitch)、横滚角(Roll)和偏航角(Yaw)。 - * * @param calibration_en 传入:外部校准使能标志。如果为0,则强制认为已经校准完成。 * @param acc_gyro_input 传入和传出:包含6轴原始数据的数组指针,顺序为 [ACC_X, ACC_Y, ACC_Z, GYR_X, GYR_Y, GYR_Z]。该函数会对其进行原地修改,填充为校准后的数据。 * @param Angle_output 传出:滤波后的结果,顺序为 [Pitch, Roll, Yaw]。 @@ -1172,13 +1173,10 @@ unsigned char get_calibration_state(void){ ///////////////////////////////////////////////////////////////////////////////////////////////////////////////// -// 如果没有定义 PI,请取消下面的注释 -// #define PI 3.14159265358979323846f // ================================================================================================= // Mahony AHRS (Attitude and Heading Reference System) 相关变量定义 -// Mahony滤波器是一种高效的互补滤波器,它使用四元数来表示姿态,从而避免了万向节死锁问题。 -// 它通过一个PI控制器来校正陀ar螺仪的积分漂移。 +// 通过一个PI控制器来校正陀ar螺仪的积分漂移。 // ------------------------------------------------------------------------------------------------- // --- 滤波器参数 --- // Kp: 比例增益,决定了加速度计数据校正陀螺仪的权重。值越大,对加速度计的响应越快,但对运动加速度更敏感。 @@ -1204,7 +1202,7 @@ static float exInt = 0.0f, eyInt = 0.0f, ezInt = 0.0f; * 该函数主要完成两项工作: * 1. 静态校准:在初始阶段,检测传感器是否处于静止状态。如果是,则计算加速度计和陀螺仪的零点偏移(误差),用于后续的数据补偿。 * 2. 姿态解算:使用基于四元数的Mahony互补滤波器融合经过校准后的加速度计和陀螺仪数据,计算出物体的俯仰角(Pitch)、横滚角(Roll)和偏航角(Yaw)。 -* 这种方法精度高,且能避免万向节死锁问题。 +* 能避免万向节死锁问题。 * * @param calibration_en 传入:外部校准使能标志。如果为0,则强制认为已经校准完成。 * @param acc_gyro_input 传入和传出:包含6轴原始数据的数组指针,顺序为 [ACC_X, ACC_Y, ACC_Z, GYR_X, GYR_Y, GYR_Z]。该函数会对其进行原地修改,填充为校准后的数据。 diff --git a/apps/earphone/xtell_Sensor/sensor/WF282A.c b/apps/earphone/xtell_Sensor/sensor/WF282A.c new file mode 100644 index 0000000..41e795c --- /dev/null +++ b/apps/earphone/xtell_Sensor/sensor/WF282A.c @@ -0,0 +1,181 @@ +/* + 气压计 - WF282A +*/ +#include "wf282a.h" +#include +#include // 推荐使用标准类型 +#include "gSensor/gSensor_manage.h" + +/*==================================================================================*/ +/* WF282A 内部定义 */ +/*==================================================================================*/ + +// 存储校准系数的静态全局变量 +static int16_t c0, c1, c01, c11, c20, c21, c30; +static int32_t c00, c10; + +/*==================================================================================*/ +/* 封装的底层I2C读写函数 */ +/*==================================================================================*/ + +/** + * @brief 写入单个字节到WF282A寄存器 + */ +static void wf282a_write_reg(uint8_t reg, uint8_t data) { + gravity_sensor_command(WF_IIC_WRITE_ADDRESS, reg, data); +} + +/** + * @brief 从WF282A读取多个字节 + */ +static uint32_t wf282a_read_regs(uint8_t reg, uint8_t *buf, uint8_t len) { + return _gravity_sensor_get_ndata(WF_IIC_READ_ADDRESS, reg, buf, len); +} + +/*==================================================================================*/ +/* 内部辅助函数 */ +/*==================================================================================*/ + +/** + * @brief 从缓冲区中解析所有校准系数 + * @param buf 包含从寄存器0x10开始读取的18个字节的校准数据 + */ +static void parse_calibration_data(const uint8_t *buf) { + // c0 (12-bit) + c0 = ((int16_t)buf[0] << 4) | (buf[1] >> 4); + if (c0 & (1 << 11)) c0 |= 0xF000; + + // c1 (12-bit) + c1 = (((int16_t)buf[1] & 0x0F) << 8) | buf[2]; + if (c1 & (1 << 11)) c1 |= 0xF000; + + // c00 (20-bit) + c00 = ((int32_t)buf[3] << 12) | ((int32_t)buf[4] << 4) | (buf[5] >> 4); + if (c00 & (1 << 19)) c00 |= 0xFFF00000; + + // c10 (20-bit) + c10 = (((int32_t)buf[5] & 0x0F) << 16) | ((int32_t)buf[6] << 8) | buf[7]; + if (c10 & (1 << 19)) c10 |= 0xFFF00000; + + // c01, c11, c20, c21, c30 (16-bit) + c01 = (int16_t)((uint16_t)buf[8] << 8 | buf[9]); + c11 = (int16_t)((uint16_t)buf[10] << 8 | buf[11]); + c20 = (int16_t)((uint16_t)buf[12] << 8 | buf[13]); + c21 = (int16_t)((uint16_t)buf[14] << 8 | buf[15]); + c30 = (int16_t)((uint16_t)buf[16] << 8 | buf[17]); +} + +/** + * @brief 获取原始温度值 (ADC) + */ +static int32_t Get_Traw() { + uint8_t buff[3]; + int32_t Traw; + // 从 MSB 寄存器 WF_TMP_B2 (0x03) 开始连续读取3个字节 + wf282a_read_regs(WF_TMP_B2, buff, 3); + // buff[0] = B2 (MSB), buff[1] = B1, buff[2] = B0 (LSB) + Traw = (int32_t)buff[0] << 16 | (int32_t)buff[1] << 8 | (int32_t)buff[2]; + // 24位二进制补码转32位 + if (Traw & (1 << 23)) { + Traw |= 0xFF000000; + } + return Traw; +} + +/** + * @brief 获取原始气压值 (ADC) + */ +static int32_t Get_Praw() { + uint8_t buff[3]; + int32_t Praw; + // 从 MSB 寄存器 WF_PRS_B2 (0x00) 开始连续读取3个字节 + wf282a_read_regs(WF_PRS_B2, buff, 3); + // buff[0] = B2 (MSB), buff[1] = B1, buff[2] = B0 (LSB) + Praw = (int32_t)buff[0] << 16 | (int32_t)buff[1] << 8 | (int32_t)buff[2]; + // 24位二进制补码转32位 + if (Praw & (1 << 23)) { + Praw |= 0xFF000000; + } + return Praw; +} + +/*==================================================================================*/ +/* 4. 外部接口函数实现 */ +/*==================================================================================*/ + +uint8_t WF_Init() { + uint8_t calib_buf[18]; + uint8_t check_cfg; + + // 1. 配置传感器工作模式 + // 推荐配置:压力8次过采样,温度1次过采样,测量速率16Hz + wf282a_write_reg(WF_PRS_CFG, (PM_RATE_16 << 4) | PM_PRC_8); + wf282a_write_reg(WF_TMP_CFG, (TMP_RATE_16 << 4) | TMP_PRC_1 | TMP_INT_SENSOR); + wf282a_write_reg(WF_MEAS_CFG, 0x07); // 启动连续压力和温度测量 + wf282a_write_reg(WF_CFG_REG, 0x00); // 无中断或FIFO移位配置 + + // 2. 一次性读取所有校准系数 (从0x10到0x21,共18字节) + if (wf282a_read_regs(COEF_C0, calib_buf, 18) != 0) { + return 2; // 读取校准数据失败 + } + parse_calibration_data(calib_buf); + + // 3. 检查配置是否写入成功 + wf282a_read_regs(WF_MEAS_CFG, &check_cfg, 1); + if (check_cfg != 0x07) { + return 1; // 错误 + } else { + return 0; // 成功 + } +} + +void WF_Sleep() { + wf282a_write_reg(WF_MEAS_CFG, 0x00); // 待机模式 +} + +void WF_Wakeup() { + wf282a_write_reg(WF_MEAS_CFG, 0x07); // 恢复连续测量 +} + +uint8_t WF_GetID() { + uint8_t id; + wf282a_read_regs(WF_ID_REG, &id, 1); + return id; +} + +float WF_Temperature_Calculate() { + float Traw_sc; + int32_t Traw = Get_Traw(); + + Traw_sc = (float)Traw / KT; // 缩放原始温度值 + return (float)c0 * 0.5f + (float)c1 * Traw_sc; +} + +float WF_Pressure_Calculate() { + float Traw_sc, Praw_sc, Pcomp; + int32_t Traw = Get_Traw(); + int32_t Praw = Get_Praw(); + + Traw_sc = (float)Traw / KT; // 缩放原始温度值 + Praw_sc = (float)Praw / KP; // 缩放原始压力值 + + // 公式: 手册给出 + Pcomp = (float)c00 + + Praw_sc * ((float)c10 + Praw_sc * ((float)c20 + Praw_sc * (float)c30)) + + Traw_sc * (float)c01 + + Traw_sc * Praw_sc * ((float)c11 + Praw_sc * (float)c21); + + return Pcomp; +} + +float WF_Altitude_Calculate() { + float pressure_pa = WF_Pressure_Calculate(); + // 使用标准大气压公式计算海拔 + // P = P0 * (1 - L*h / T0)^(g*M / (R*L)) + // 简化公式: h = 44330 * (1 - (P/P0)^(1/5.255)) + // 1/5.255 ≈ 0.1903 + if (pressure_pa <= 0) { + return 0.0f; // 避免无效计算 + } + return 44330.0f * (1.0f - powf(pressure_pa / 101325.0f, 0.1902949f)); +} \ No newline at end of file diff --git a/apps/earphone/xtell_Sensor/sensor/WF282A.h b/apps/earphone/xtell_Sensor/sensor/WF282A.h new file mode 100644 index 0000000..8503907 --- /dev/null +++ b/apps/earphone/xtell_Sensor/sensor/WF282A.h @@ -0,0 +1,148 @@ +#ifndef _WF282A_H_ +#define _WF282A_H_ + +#include // 使用标准整数类型 + +// 标定值 +#define KT 524288.0f +#define KP 1572864.0f + + +#define WF_PULL_UP 1 //外部是否接的上拉 + +// I2C 从设备地址 +#if WF_PULL_UP == 1 //外部接的高 +#define WF_IIC_7BIT_ADDRESS 0x77 //7位,外部接高为0x77 +#define WF_IIC_WRITE_ADDRESS (WF_IIC_7BIT_ADDRESS<<1) //8位地址 +#define WF_IIC_READ_ADDRESS (WF_IIC_WRITE_ADDRESS | 0x01) +#else +#define WF_IIC_7BIT_ADDRESS 0x76 //7位,外部接低为0x76 +#define WF_IIC_WRITE_ADDRESS (WF_IIC_7BIT_ADDRESS<<1) //8位地址 +#define WF_IIC_READ_ADDRESS (WF_IIC_WRITE_ADDRESS | 0x01) +#endif + +#define WF_CHIP_ID 0X10 + +// 寄存器映射 +// 压力数据 +#define WF_PRS_B2 0x00 +#define WF_PRS_B1 0x01 +#define WF_PRS_B0 0x02 +// 温度数据 +#define WF_TMP_B2 0x03 +#define WF_TMP_B1 0x04 +#define WF_TMP_B0 0x05 +// 配置寄存器 +#define WF_PRS_CFG 0x06 +#define WF_TMP_CFG 0x07 +#define WF_MEAS_CFG 0x08 +#define WF_CFG_REG 0x09 +#define WF_INT_STS 0x0A +#define WF_FIFO_STS 0x0B +#define WF_RESET_REG 0x0C +// ID寄存器 +#define WF_ID_REG 0x0D +// 校准系数寄存器 +#define COEF_C0 0x10 +#define COEF_C0_C1 0x11 +#define COEF_C1 0x12 +#define COEF_C00_H 0x13 +#define COEF_C00_L 0x14 +#define COEF_C00_C10 0x15 +#define COEF_C10_M 0x16 +#define COEF_C10_L 0x17 +#define COEF_C01_H 0x18 +#define COEF_C01_L 0x19 +#define COEF_C11_H 0x1A +#define COEF_C11_L 0x1B +#define COEF_C20_H 0x1C +#define COEF_C20_L 0x1D +#define COEF_C21_H 0x1E +#define COEF_C21_L 0x1F +#define COEF_C30_H 0x20 +#define COEF_C30_L 0x21 + +// --- 配置宏 --- + +// 压力配置 (PRS_CFG[6:4]) - 测量速率 +#define PM_RATE_1 0x00 // 1 次/秒 +#define PM_RATE_2 0x01 // 2 次/秒 +#define PM_RATE_4 0x02 // 4 次/秒 +#define PM_RATE_8 0x03 // 8 次/秒 +#define PM_RATE_16 0x04 // 16 次/秒 +#define PM_RATE_32 0x05 // 32 次/秒 +#define PM_RATE_64 0x06 // 64 次/秒 +#define PM_RATE_128 0x07 // 128 次/秒 +// 压力配置 (PRS_CFG[3:0]) - 过采样率 +#define PM_PRC_1 0x00 // 1 次 (单次) +#define PM_PRC_2 0x01 // 2 次 (低功耗) +#define PM_PRC_4 0x02 // 4 次 +#define PM_PRC_8 0x03 // 8 次 (标准) +#define PM_PRC_16 0x04 // 16 次 (需要移位) +#define PM_PRC_32 0x05 // 32 次 (需要移位) +#define PM_PRC_64 0x06 // 64 次 (高精度, 需要移位) +#define PM_PRC_128 0x07 // 128 次 (需要移位) + +// 温度配置 (TMP_CFG[7]) - 传感器源 +#define TMP_EXT_SENSOR 0x80 // 使用外部传感器 +#define TMP_INT_SENSOR 0x00 // 使用内部传感器 +// 温度配置 (TMP_CFG[6:4]) - 测量速率 +#define TMP_RATE_1 0x00 // 1 次/秒 +#define TMP_RATE_2 0x01 // 2 次/秒 +#define TMP_RATE_4 0x02 // 4 次/秒 +#define TMP_RATE_8 0x03 // 8 次/秒 +#define TMP_RATE_16 0x04 // 16 次/秒 +#define TMP_RATE_32 0x05 // 32 次/秒 +#define TMP_RATE_64 0x06 // 64 次/秒 +#define TMP_RATE_128 0x07 // 128 次/秒 +// 温度配置 (TMP_CFG[3:0]) - 过采样率 +#define TMP_PRC_1 0x00 // 1 次 +#define TMP_PRC_2 0x01 // 2 次 +#define TMP_PRC_4 0x02 // 4 次 +#define TMP_PRC_8 0x03 // 8 次 +#define TMP_PRC_16 0x04 // 16 次 +#define TMP_PRC_32 0x05 // 32 次 +#define TMP_PRC_64 0x06 // 64 次 +#define TMP_PRC_128 0x07 // 128 次 + +/** + * @brief 初始化WF282A传感器 + * @return 0: 成功, 1: 失败 + */ +uint8_t WF_Init(void); + +/** + * @brief 使传感器进入休眠/待机模式 + */ +void WF_Sleep(void); + +/** + * @brief 唤醒传感器,开始连续测量 + */ +void WF_Wakeup(void); + +/** + * @brief 获取传感器芯片ID + * @return 芯片ID (应为 0x10) + */ +uint8_t WF_GetID(void); + +/** + * @brief 计算并返回当前海拔高度 + * @return 海拔高度 (单位: 米) + */ +float WF_Altitude_Calculate(void); + +/** + * @brief 计算并返回补偿后的压力值 + * @return 压力 (单位: Pa) + */ +float WF_Pressure_Calculate(void); + +/** + * @brief 计算并返回补偿后的温度值 + * @return 温度 (单位: °C) + */ +float WF_Temperature_Calculate(void); + +#endif // _WF282A_H_ \ No newline at end of file