通过C#上位机串口写入和读取浮点数到stm32实战5(通过串口读取bmp280气压计的数值并在上位机显示)
网上很多代码i2c的连续读函数都不能正确读到bmp280数据,但读得到芯片ID=0x58,原因在于bmp280内置校准值T1-T3,P1-P9是高8位和低8位构成的,不能直接读取,需做处理,详细见下面代码。
文章后有完整 代码和上位机代码下载
通过网盘分享的文件:bmp280.rar
链接: https://pan.baidu.com/s/1giTtMOVrnCl4eUBVCIsFqA 提取码: abcd
bmp280.h
#ifndef __BMP280_H
#define __BMP280_H
//#include "sys.h"
//#include "stdbool.h"//typedef enum {FALSE=0,TRUE=1} bool;#define BMP280_ADDR (0xEC)
#define BMP280_DEFAULT_CHIP_ID (0x58)#define BMP280_CHIP_ID (0xD0) /* Chip ID Register */
#define BMP280_RST_REG (0xE0) /* Softreset Register */
#define BMP280_STAT_REG (0xF3) /* Status Register */
#define BMP280_CTRL_MEAS_REG (0xF4) /* Ctrl Measure Register */
#define BMP280_CONFIG_REG (0xF5) /* Configuration Register */
#define BMP280_PRESSURE_MSB_REG (0xF7) /* Pressure MSB Register */
#define BMP280_PRESSURE_LSB_REG (0xF8) /* Pressure LSB Register */
#define BMP280_PRESSURE_XLSB_REG (0xF9) /* Pressure XLSB Register */
#define BMP280_TEMPERATURE_MSB_REG (0xFA) /* Temperature MSB Reg */
#define BMP280_TEMPERATURE_LSB_REG (0xFB) /* Temperature LSB Reg */
#define BMP280_TEMPERATURE_XLSB_REG (0xFC) /* Temperature XLSB Reg */#define BMP280_SLEEP_MODE (0x00)
#define BMP280_FORCED_MODE (0x01)
#define BMP280_NORMAL_MODE (0x03)#define BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG (0x88)
#define BMP280_PRESSURE_TEMPERATURE_CALIB_DATA_LENGTH (24)
#define BMP280_DATA_FRAME_SIZE (6)#define BMP280_OVERSAMP_SKIPPED (0x00)
#define BMP280_OVERSAMP_1X (0x01)
#define BMP280_OVERSAMP_2X (0x02)
#define BMP280_OVERSAMP_4X (0x03)
#define BMP280_OVERSAMP_8X (0x04)
#define BMP280_OVERSAMP_16X (0x05)//自己补充
#define BMP280_DIG_T1_LSB_REG 0x88
#define BMP280_DIG_T1_MSB_REG 0x89
#define BMP280_DIG_T2_LSB_REG 0x8A
#define BMP280_DIG_T2_MSB_REG 0x8B
#define BMP280_DIG_T3_LSB_REG 0x8C
#define BMP280_DIG_T3_MSB_REG 0x8D
#define BMP280_DIG_P1_LSB_REG 0x8E
#define BMP280_DIG_P1_MSB_REG 0x8F
#define BMP280_DIG_P2_LSB_REG 0x90
#define BMP280_DIG_P2_MSB_REG 0x91
#define BMP280_DIG_P3_LSB_REG 0x92
#define BMP280_DIG_P3_MSB_REG 0x93
#define BMP280_DIG_P4_LSB_REG 0x94
#define BMP280_DIG_P4_MSB_REG 0x95
#define BMP280_DIG_P5_LSB_REG 0x96
#define BMP280_DIG_P5_MSB_REG 0x97
#define BMP280_DIG_P6_LSB_REG 0x98
#define BMP280_DIG_P6_MSB_REG 0x99
#define BMP280_DIG_P7_LSB_REG 0x9A
#define BMP280_DIG_P7_MSB_REG 0x9B
#define BMP280_DIG_P8_LSB_REG 0x9C
#define BMP280_DIG_P8_MSB_REG 0x9D
#define BMP280_DIG_P9_LSB_REG 0x9E
#define BMP280_DIG_P9_MSB_REG 0x9Fbool bmp280Init(void);
void bmp280GetData(float* pressure, float* temperature, float* asl);#endif
bmp280.c
#include <math.h>
//#include "stdbool.h"
#include "delay.h"
#include "i2c.h"
#include "bmp280.h"
//#include "usart.h"/*bmp280 气压和温度过采样 工作模式*/
#define BMP280_PRESSURE_OSR (BMP280_OVERSAMP_8X)
#define BMP280_TEMPERATURE_OSR (BMP280_OVERSAMP_16X)
#define BMP280_MODE (BMP280_PRESSURE_OSR<<2|BMP280_TEMPERATURE_OSR<<5|BMP280_NORMAL_MODE)typedef struct
{u16 dig_T1; /* calibration T1 data */s16 dig_T2; /* calibration T2 data */s16 dig_T3; /* calibration T3 data */u16 dig_P1; /* calibration P1 data */s16 dig_P2; /* calibration P2 data */s16 dig_P3; /* calibration P3 data */s16 dig_P4; /* calibration P4 data */s16 dig_P5; /* calibration P5 data */s16 dig_P6; /* calibration P6 data */s16 dig_P7; /* calibration P7 data */s16 dig_P8; /* calibration P8 data */s16 dig_P9; /* calibration P9 data */s32 t_fine; /* calibration t_fine data */
} bmp280Calib;bmp280Calib bmp280Cal;u8 bmp280ID=0;
static bool isInit=FALSE;
static s32 bmp280RawPressure=0;
static s32 bmp280RawTemperature=0;static void bmp280GetPressure(void);
static void presssureFilter(float* in,float* out);
static float bmp280PressureToAltitude(float* pressure/*, float* groundPressure, float* groundTemp*/);bool bmp280Init(void)
{ if (isInit)return TRUE;//IIC_Init(); /*初始化I2C*/delay_ms(20);bmp280ID=iicDevReadByte(BMP280_ADDR,BMP280_CHIP_ID); /* 读取bmp280 ID*//*if(bmp280ID==BMP280_DEFAULT_CHIP_ID)printf("BMP280 ID IS: 0x%X\n",bmp280ID);elsereturn false;
*//* 读取校准数据 */// iicDevRead(BMP280_ADDR,BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG,24,(u8 *)&bmp280Cal);uint8_t lsb, msb;/* read the temperature calibration parameters */ // 读取校准数据 自己改的,因为连续读函数有问题lsb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_T1_LSB_REG);msb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_T1_MSB_REG);bmp280Cal.dig_T1 = msb << 8 | lsb;lsb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_T2_LSB_REG);msb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_T2_MSB_REG);bmp280Cal.dig_T2 = msb << 8 | lsb;lsb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_T3_LSB_REG);msb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_T3_MSB_REG);bmp280Cal.dig_T3 = msb << 8 | lsb;/* read the pressure calibration parameters */lsb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P1_LSB_REG);msb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P1_MSB_REG);bmp280Cal.dig_P1 = msb << 8 | lsb;lsb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P2_LSB_REG);msb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P2_MSB_REG);bmp280Cal.dig_P2 = msb << 8 | lsb;lsb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P3_LSB_REG);msb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P3_MSB_REG);bmp280Cal.dig_P3 = msb << 8 | lsb;lsb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P4_LSB_REG);msb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P4_MSB_REG);bmp280Cal.dig_P4 = msb << 8 | lsb;lsb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P5_LSB_REG);msb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P5_MSB_REG);bmp280Cal.dig_P5 = msb << 8 | lsb;lsb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P6_LSB_REG);msb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P6_MSB_REG);bmp280Cal.dig_P6 = msb << 8 | lsb;lsb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P7_LSB_REG);msb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P7_MSB_REG);bmp280Cal.dig_P7 = msb << 8 | lsb;lsb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P8_LSB_REG);msb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P8_MSB_REG);bmp280Cal.dig_P8 = msb << 8 | lsb;lsb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P9_LSB_REG);msb = iicDevReadByte(BMP280_ADDR,BMP280_DIG_P9_MSB_REG);bmp280Cal.dig_P9 = msb << 8 | lsb;iicDevWriteByte(BMP280_ADDR,BMP280_CTRL_MEAS_REG,BMP280_MODE);iicDevWriteByte(BMP280_ADDR,BMP280_CONFIG_REG,5<<2); /*配置IIR滤波*/// printf("BMP280 Calibrate Registor Are: \r\n");
// for(i=0;i<24;i++)
// printf("Registor %2d: 0x%X\n",i,p[i]);isInit=TRUE;return TRUE;
}static void bmp280GetPressure(void)
{u8 data[BMP280_DATA_FRAME_SIZE];// read data from sensor//iicDevRead(BMP280_ADDR,BMP280_PRESSURE_MSB_REG,BMP280_DATA_FRAME_SIZE,data);data[0]=iicDevReadByte(BMP280_ADDR,BMP280_PRESSURE_MSB_REG ); //自己改的data[1]=iicDevReadByte(BMP280_ADDR,BMP280_PRESSURE_LSB_REG ); data[2]=iicDevReadByte(BMP280_ADDR,BMP280_PRESSURE_XLSB_REG ); data[3]=iicDevReadByte(BMP280_ADDR,BMP280_TEMPERATURE_MSB_REG ); //自己改的data[4]=iicDevReadByte(BMP280_ADDR,BMP280_TEMPERATURE_LSB_REG ); data[5]=iicDevReadByte(BMP280_ADDR,BMP280_TEMPERATURE_XLSB_REG ); bmp280RawPressure=(s32)((((uint32_t)(data[0]))<<12)|(((uint32_t)(data[1]))<<4)|((uint32_t)data[2]>>4));bmp280RawTemperature=(s32)((((uint32_t)(data[3]))<<12)|(((uint32_t)(data[4]))<<4)|((uint32_t)data[5]>>4));
}// Returns temperature in DegC, resolution is 0.01 DegC. Output value of "5123" equals 51.23 DegC
// t_fine carries fine temperature as global value
static s32 bmp280CompensateT(s32 adcT)
{s32 var1,var2,T;var1=((((adcT>>3)-((s32)bmp280Cal.dig_T1<<1)))*((s32)bmp280Cal.dig_T2))>>11;var2=(((((adcT>>4)-((s32)bmp280Cal.dig_T1))*((adcT>>4)-((s32)bmp280Cal.dig_T1)))>>12)*((s32)bmp280Cal.dig_T3))>>14;bmp280Cal.t_fine=var1+var2;T=(bmp280Cal.t_fine*5+128)>>8;return T;
}// Returns pressure in Pa as unsigned 32 bit integer in Q24.8 format (24 integer bits and 8 fractional bits).
// Output value of "24674867" represents 24674867/256 = 96386.2 Pa = 963.862 hPa
static uint32_t bmp280CompensateP(s32 adcP)
{int64_t var1,var2,p;var1=((int64_t)bmp280Cal.t_fine)-128000;var2=var1*var1*(int64_t)bmp280Cal.dig_P6;var2=var2+((var1*(int64_t)bmp280Cal.dig_P5)<<17);var2=var2+(((int64_t)bmp280Cal.dig_P4)<<35);var1=((var1*var1*(int64_t)bmp280Cal.dig_P3)>>8)+((var1*(int64_t)bmp280Cal.dig_P2)<<12);var1=(((((int64_t)1)<<47)+var1))*((int64_t)bmp280Cal.dig_P1)>>33;if (var1==0)return 0;p=1048576-adcP;p=(((p<<31)-var2)*3125)/var1;var1=(((int64_t)bmp280Cal.dig_P9)*(p>>13)*(p>>13))>>25;var2=(((int64_t)bmp280Cal.dig_P8)*p)>>19;p=((p+var1+var2)>>8)+(((int64_t)bmp280Cal.dig_P7)<<4);return(uint32_t)p;
}#define FILTER_NUM 5
#define FILTER_A 0.1f/*限幅平均滤波法*/
static void presssureFilter(float* in,float* out)
{ static u8 i=0;static float filter_buf[FILTER_NUM]={0.0};double filter_sum=0.0;u8 cnt=0; float deta;if(filter_buf[i]==0.0f){filter_buf[i]=*in;*out=*in;if(++i>=FILTER_NUM) i=0;} else {if(i)deta=*in-filter_buf[i-1];else deta=*in-filter_buf[FILTER_NUM-1];if(fabs(deta)<FILTER_A){filter_buf[i]=*in;if(++i>=FILTER_NUM) i=0;}for(cnt=0;cnt<FILTER_NUM;cnt++){filter_sum+=filter_buf[cnt];}*out=filter_sum /FILTER_NUM;}
}void bmp280GetData(float* pressure,float* temperature,float* asl)
{static float t;static float p;bmp280GetPressure();t=bmp280CompensateT(bmp280RawTemperature)/100.0; p=bmp280CompensateP(bmp280RawPressure)/25600.0; presssureFilter(&p,pressure);*temperature=(float)t; /*单位度*/
// *pressure=(float)p ; /*单位hPa*/ *asl=bmp280PressureToAltitude(pressure); /*转换成海拔*/
}#define CONST_PF 0.1902630958 //(1/5.25588f) Pressure factor
#define FIX_TEMP 25 // Fixed Temperature. ASL is a function of pressure and temperature, but as the temperature changes so much (blow a little towards the flie and watch it drop 5 degrees) it corrupts the ASL estimates.// TLDR: Adjusting for temp changes does more harm than good.
/** Converts pressure to altitude above sea level (ASL) in meters
*/
static float bmp280PressureToAltitude(float* pressure/*, float* groundPressure, float* groundTemp*/)
{if (*pressure>0){return((pow((1015.7f/ *pressure),CONST_PF)-1.0f)*(FIX_TEMP+273.15f))/0.0065f;}else{return 0;}
}
i2c.h
#ifndef _I2C_H
#define _I2C_Htypedef enum {FALSE=0,TRUE=1} bool;void I2C_GPIO_Config(void); //mpu9250 输入定义
void I2C_delay(void);
void delay5ms(void);
bool I2C_Start(void);
void I2C_Stop(void);
void I2C_Ack(void);
void I2C_NoAck(void);
bool I2C_WaitAck(void);
void I2C_SendByte(u8 SendByte); //数据从高位到低位//
unsigned char I2C_RadeByte(void); //数据从高位到低位//
bool Single_Write(unsigned char SlaveAddress,unsigned char REG_Address,unsigned char REG_data);
unsigned char Single_Read(unsigned char SlaveAddress,unsigned char REG_Address);
void WWDG_Configuration(void);
void WWDG_IRQHandler(void);u8 iicDevReadByte(u8 devaddr,u8 addr); /*读一字节*/
void iicDevWriteByte(u8 devaddr,u8 addr,u8 data); /*写一字节*/
void iicDevRead(u8 devaddr,u8 addr,u8 len,u8 *rbuf); /*连续读取多个字节*/
void iicDevWrite(u8 devaddr,u8 addr,u8 len,u8 *wbuf);
/*连续写入多个字节*/#endif
i2c.c
#include "stm32f10x.h"
#include "i2c.h"char test=0; //IIC//************************************
/*模拟IIC端口输出输入定义*/
#define SCL_H GPIOB->BSRR = GPIO_Pin_6
#define SCL_L GPIOB->BRR = GPIO_Pin_6 #define SDA_H GPIOB->BSRR = GPIO_Pin_7
#define SDA_L GPIOB->BRR = GPIO_Pin_7#define SCL_read GPIOB->IDR & GPIO_Pin_6
#define SDA_read GPIOB->IDR & GPIO_Pin_7/*******************************************************************************
* Function Name : I2C_GPIO_Config
* Description : Configration Simulation IIC GPIO
* Input : None
* Output : None
* Return : None
****************************************************************************** */
void I2C_GPIO_Config(void) //mpu9250 输入定义
{GPIO_InitTypeDef GPIO_InitStructure; GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; //GPIO_Speed_50MHz;GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD; GPIO_Init(GPIOB, &GPIO_InitStructure);GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7;GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; //GPIO_Speed_50MHz;GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;GPIO_Init(GPIOB, &GPIO_InitStructure);
}/*******************************************************************************
* Function Name : I2C_delay
* Description : Simulation IIC Timing series delay
* Input : None
* Output : None
* Return : None
****************************************************************************** */
void I2C_delay(void)
{u8 i=8; // 30 这里可以优化速度 ,经测试最低到5还能写入while(i) { i--; }
}void delay5ms(void)
{int i=1000; while(i) { i--; }
}
/*******************************************************************************
* Function Name : I2C_Start
* Description : Master Start Simulation IIC Communication
* Input : None
* Output : None
* Return : Wheather Start
****************************************************************************** */
bool I2C_Start(void)
{SDA_H;SCL_H;I2C_delay();if(!SDA_read)return FALSE; //SDA线为低电平则总线忙,退出SDA_L;I2C_delay();if(SDA_read) return FALSE; //SDA线为高电平则总线出错,退出SDA_L;I2C_delay();return TRUE;
}
/*******************************************************************************
* Function Name : I2C_Stop
* Description : Master Stop Simulation IIC Communication
* Input : None
* Output : None
* Return : None
****************************************************************************** */
void I2C_Stop(void)
{SCL_L;I2C_delay();SDA_L;I2C_delay();SCL_H;I2C_delay();SDA_H;I2C_delay();
}
/*******************************************************************************
* Function Name : I2C_Ack
* Description : Master Send Acknowledge Single
* Input : None
* Output : None
* Return : None
****************************************************************************** */
void I2C_Ack(void)
{ SCL_L;I2C_delay();SDA_L;I2C_delay();SCL_H;I2C_delay();SCL_L;I2C_delay();
}
/*******************************************************************************
* Function Name : I2C_NoAck
* Description : Master Send No Acknowledge Single
* Input : None
* Output : None
* Return : None
****************************************************************************** */
void I2C_NoAck(void)
{ SCL_L;I2C_delay();SDA_H;I2C_delay();SCL_H;I2C_delay();SCL_L;I2C_delay();
}
/*******************************************************************************
* Function Name : I2C_WaitAck
* Description : Master Reserive Slave Acknowledge Single
* Input : None
* Output : None
* Return : Wheather Reserive Slave Acknowledge Single
****************************************************************************** */
bool I2C_WaitAck(void) //返回为:=1有ACK,=0无ACK
{SCL_L;I2C_delay();SDA_H; I2C_delay();SCL_H;I2C_delay();if(SDA_read){SCL_L;I2C_delay();return FALSE;}SCL_L;I2C_delay();return TRUE;
}
/*******************************************************************************
* Function Name : I2C_SendByte
* Description : Master Send a Byte to Slave
* Input : Will Send Date
* Output : None
* Return : None
****************************************************************************** */
void I2C_SendByte(u8 SendByte) //数据从高位到低位//
{u8 i=8;while(i--){SCL_L;I2C_delay();if(SendByte&0x80)SDA_H; else SDA_L; SendByte<<=1;I2C_delay();SCL_H;I2C_delay();}SCL_L;
}
/*******************************************************************************
* Function Name : I2C_RadeByte
* Description : Master Reserive a Byte From Slave
* Input : None
* Output : None
* Return : Date From Slave
****************************************************************************** */
unsigned char I2C_RadeByte(void) //数据从高位到低位//
{ u8 i=8;u8 ReceiveByte=0;SDA_H; while(i--){ReceiveByte<<=1; SCL_L;I2C_delay();SCL_H;I2C_delay(); if(SDA_read){ReceiveByte|=0x01;}}SCL_L;return ReceiveByte;
}
//ZRX
//?????*******************************************bool Single_Write(unsigned char SlaveAddress,unsigned char REG_Address,unsigned char REG_data) //void
{if(!I2C_Start())return FALSE;I2C_SendByte(SlaveAddress); //发送设备地址+写信号//I2C_SendByte(((REG_Address & 0x0700) >>7) | SlaveAddress & 0xFFFE);//设置高起始地址+器件地址 if(!I2C_WaitAck()){I2C_Stop(); return FALSE;}I2C_SendByte(REG_Address ); //设置低起始地址 I2C_WaitAck(); I2C_SendByte(REG_data);I2C_WaitAck(); I2C_Stop(); delay5ms();return TRUE;
}//单字节读取*****************************************
unsigned char Single_Read(unsigned char SlaveAddress,unsigned char REG_Address)
{ unsigned char REG_data; if(!I2C_Start())return FALSE;I2C_SendByte(SlaveAddress); //I2C_SendByte(((REG_Address & 0x0700) >>7) | REG_Address & 0xFFFE);//设置高起始地址+器件地址 if(!I2C_WaitAck()){I2C_Stop();test=1; return FALSE;}I2C_SendByte((u8) REG_Address); //设置高起始地址+器件地址 I2C_WaitAck();I2C_Start();I2C_SendByte(SlaveAddress+1);I2C_WaitAck();REG_data= I2C_RadeByte();I2C_NoAck();I2C_Stop();//return TRUE;return REG_data;} u8 iicDevReadByte(u8 devaddr,u8 addr) /*读一字节*/
{u8 data; data=Single_Read(devaddr,addr);return data;
}
void iicDevWriteByte(u8 devaddr,u8 addr,u8 data) /*写一字节*/
{Single_Write(devaddr,addr,data);
}
void iicDevRead(u8 devaddr,u8 addr,u8 len,u8 *rbuf)/*连续读取多个字节*/
{}
void iicDevWrite(u8 devaddr,u8 addr,u8 len,u8 *wbuf)
{}/*
********************************************************************************
** 函数名称 : WWDG_Configuration(void)
** 函数功能 : 看门狗初始化
** 输 入 : 无
** 输 出 : 无
** 返 回 : 无
********************************************************************************
*/
void WWDG_Configuration(void)
{RCC_APB1PeriphClockCmd(RCC_APB1Periph_WWDG, ENABLE); WWDG_SetPrescaler(WWDG_Prescaler_8); // WWDG clock counter = (PCLK1/4096)/8 = 244 Hz (~4 ms) WWDG_SetWindowValue(0x41); // Set Window value to 0x41WWDG_Enable(0x50); // Enable WWDG and set counter value to 0x7F, WWDG timeout = ~4 ms * 64 = 262 ms WWDG_ClearFlag(); // Clear EWI flagWWDG_EnableIT(); // Enable EW interrupt
}/*
********************************************************************************
** 函数名称 : WWDG_IRQHandler(void)
** 函数功能 : 窗口提前唤醒中断
** 输 入 : 无
** 输 出 : 无
** 返 回 : 无
********************************************************************************
*/ void WWDG_IRQHandler(void)
{/* Update WWDG counter */WWDG_SetCounter(0x50);/* Clear EWI flag */WWDG_ClearFlag();
}//************************************************