Other Parts Discussed in Thread: BQSTUDIO, EV2400,
我使用的bq76952支持CRC,但是开启后无法通信;如果不开启,通信仍无法进行,串口打印的是初始值
#include "main.h"
#include "i2c.h"
#include "tim.h"
#include "usart.h"
#include "gpio.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include"led.h"
#include"bq76952.h"
#include "BQ769x2Header.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
uint8_t receive_buff[255];
uint8_t receive_buff2[255];
extern uint8_t data_len ;
struct BAT{
float Vbat;//电池端电压
float IBAT;
float Vpack;//充电端电压
float T;
float soc;
float CELL_T;//电池温度
float FET_T;//电池温度
uint16_t battery_capacity;
}BAT1;
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
int _write(int file, char *ptr, int len)
{
HAL_UART_Transmit(&huart1, (uint8_t *)ptr, len, HAL_MAX_DELAY);
return len;
}
uint8_t times_1000ms_flag=0;
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef*htim)
{
static uint16_t times_1000ms_cnt=0;
if(htim==&htim2)
{
times_1000ms_cnt++; // 每次中断计数器加1
if(times_1000ms_cnt>999)//1s
{
times_1000ms_cnt=0;
times_1000ms_flag=1;
}
}
}
/* USER CODE END 0 */
/**
* @brief The application entry point.
* @retval int
*/
int main(void)
{
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
/* MCU Configuration--------------------------------------------------------*/
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
HAL_Init();
/* USER CODE BEGIN Init */
/* USER CODE END Init */
/* Configure the system clock */
SystemClock_Config();
/* USER CODE BEGIN SysInit */
/* USER CODE END SysInit */
/* Initialize all configured peripherals */
MX_GPIO_Init();
MX_I2C1_Init();
MX_TIM1_Init();
MX_TIM2_Init();
MX_USART1_UART_Init();
MX_USART3_UART_Init();
/* USER CODE BEGIN 2 */
// __HAL_UART_ENABLE_IT(&huart1, UART_IT_IDLE); // 使能串口空闲中断
HAL_Delay(1000);
// HAL_TIM_Base_Start_IT(&htim1);
HAL_TIM_Base_Start_IT(&htim2);
BQ769x2_Init();
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
while (1)
{
BQ769x2_ReadPassQ();
BQ769x2_ReadSafetyStatus();
if(times_1000ms_flag==1)
{
LED_A0_INV();
if(AccumulatedCharge_Int > 0 )
{
if(AccumulatedCharge_Int > BAT1.battery_capacity)
{
BAT1.battery_capacity = AccumulatedCharge_Int;
}
BAT1.soc = 100.0f*((float)AccumulatedCharge_Int / (float)BAT1.battery_capacity);
}
else if((-1)*AccumulatedCharge_Int > BAT1.battery_capacity)
{
if((-1)*AccumulatedCharge_Int > BAT1.battery_capacity)
{
BAT1.battery_capacity = (-1)*AccumulatedCharge_Int;
}
BAT1.soc = 100.0f*((-1.0)*(float)AccumulatedCharge_Int / (float)BAT1.battery_capacity);
}
BAT1.CELL_T = BQ769x2_ReadTemperature(TS1Temperature);
BAT1.FET_T = BQ769x2_ReadTemperature(TS3Temperature);
BAT1.Vbat = BQ769x2_ReadVoltage(StackVoltage)*0.001f;
BAT1.IBAT = BQ769x2_ReadCurrent()*0.001f;
BAT1.Vpack = BQ769x2_ReadVoltage(PACKPinVoltage)*0.001f;
BQ769x2_ReadFETStatus();
printf("{\"cell1\":%d ,\"cell2\":%d ,\"cell3\":%d,\"cell4\":%d}\r\n", CellVoltage[0], CellVoltage[1], CellVoltage[2], CellVoltage[3]);
printf("{\"StkV\":%f ,\"Ibat_\":%f ,\"PKV\":%f,\"SOC\":%f,\"CELL_T\":%f,\"FET_T\":%f}\r\n",BAT1.Vbat,BAT1.IBAT,BAT1.Vpack, BAT1.soc,BAT1.CELL_T,BAT1.FET_T);
printf("\r\n");
times_1000ms_flag=0;
}
/* USER CODE END WHILE */
/* USER CODE BEGIN 3 */
}
/* USER CODE END 3 */
}
/**
* @brief System Clock Configuration
* @retval None
*/
void SystemClock_Config(void)
{
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
/** Initializes the RCC Oscillators according to the specified parameters
* in the RCC_OscInitTypeDef structure.
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.HSEPredivValue = RCC_HSE_PREDIV_DIV1;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL6;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
Error_Handler();
}
/** Initializes the CPU, AHB and APB buses clocks
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK)
{
Error_Handler();
}
}
/* USER CODE BEGIN 4 */
/* USER CODE END 4 */
/**
* @brief This function is executed in case of error occurrence.
* @retval None
*/
void Error_Handler(void)
{
/* USER CODE BEGIN Error_Handler_Debug */
/* User can add his own implementation to report the HAL error return state */
__disable_irq();
while (1)
{
}
/* USER CODE END Error_Handler_Debug */
}
#include "main.h"
#include "i2c.h"
#include "tim.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include <stdio.h>
#include "bq76952.h"
#include "BQ769x2Header.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
uint8_t RX_data [2] = {0x00, 0x00}; // used in several functions to store data read from BQ769x2
uint8_t RX_32Byte [32] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
//used in Subcommands read function
// Global Variables for cell voltages, temperatures, Stack voltage, PACK Pin voltage, LD Pin voltage, CC2 current
uint16_t CellVoltage [16] = {0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00};
float Temperature [3] = {0,0,0};
float Stack_Voltage = 0;
uint16_t Pack_Voltage = 0x00;
uint16_t LD_Voltage = 0x00;
uint16_t Pack_Current = 0x00;
uint16_t AlarmBits = 0x00;
uint8_t value_SafetyStatusA; // Safety Status Register A
uint8_t value_SafetyStatusB; // Safety Status Register B
uint8_t value_SafetyStatusC; // Safety Status Register C
uint8_t value_PFStatusA; // Permanent Fail Status Register A
uint8_t value_PFStatusB; // Permanent Fail Status Register B
uint8_t value_PFStatusC; // Permanent Fail Status Register C
uint8_t FET_Status; // FET Status register contents - Shows states of FETs
uint16_t CB_ActiveCells; // Cell Balancing Active Cells
uint8_t UV_Fault = 0; // under-voltage fault state
uint8_t OV_Fault = 0; // over-voltage fault state
uint8_t SCD_Fault = 0; // short-circuit fault state
uint8_t OCD_Fault = 0; // over-current fault state
uint8_t ProtectionsTriggered = 0; // Set to 1 if any protection triggers
uint8_t LD_ON = 0; // Load Detect status bit
uint8_t DSG = 0; // discharge FET state
uint8_t CHG = 0; // charge FET state
uint8_t PCHG = 0; // pre-charge FET state
uint8_t PDSG = 0; // pre-discharge FET state
uint32_t AccumulatedCharge_Int; // in BQ769x2_READPASSQ func
uint32_t AccumulatedCharge_Frac;// in BQ769x2_READPASSQ func
uint32_t AccumulatedCharge_Time;// in BQ769x2_READPASSQ func
//自定义变量
float soc[12] = {0}; //各节电芯的soc
float battery_capacity = 0; //电池最大容量
float pack_current = 0; //每个电池的电压
float cell_voltage[12] = {0}; //每个电池的电压
float sys_soc = 0;
const char *status;
/* USER CODE END PV */
/* USER CODE BEGIN PFP */
void delayUS(uint32_t us) { // Sets the delay in microseconds.,将改定时器的计数值放大,不然会卡在此处
__HAL_TIM_SET_COUNTER(&htim1,0); // set the counter value a 0
__HAL_TIM_ENABLE(&htim1); //
while (__HAL_TIM_GET_COUNTER(&htim1) < us); // wait for the counter to reach the us input in the parameter
}
void CopyArray(uint8_t *source, uint8_t *dest, uint8_t count)
{
uint8_t copyIndex = 0;
for (copyIndex = 0; copyIndex < count; copyIndex++)
{
dest[copyIndex] = source[copyIndex];
}
}
unsigned char Checksum(unsigned char *ptr, unsigned char len)
// Calculates the checksum when writing to a RAM register. The checksum is the inverse of the sum of the bytes.
{
unsigned char i;
unsigned char checksum = 0;
for(i=0; i<len; i++)
checksum += ptr[i];
checksum = 0xff & ~checksum;
return(checksum);
}
unsigned char CRC8(unsigned char *ptr, unsigned char len)
//Calculates CRC8 for passed bytes. Used in i2c read and write functions
{
unsigned char i;
unsigned char crc=0;
while(len--!=0)
{
for(i=0x80; i!=0; i/=2)
{
if((crc & 0x80) != 0)
{
crc *= 2;
crc ^= 0x107;
}
else
crc *= 2;
if((*ptr & i)!=0)
crc ^= 0x107;
}
ptr++;
}
return(crc);
}
void I2C_WriteReg(uint8_t reg_addr, uint8_t *reg_data, uint8_t count)
{
uint8_t TX_Buffer [MAX_BUFFER_SIZE] = {0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00};
#if CRC_Mode
{
uint8_t crc_count = 0;
crc_count = count * 2;
uint8_t crc1stByteBuffer [3] = {0x10, reg_addr, reg_data[0]};
unsigned int j;
unsigned int i;
uint8_t temp_crc_buffer [3];
TX_Buffer[0] = reg_data[0];
TX_Buffer[1] = CRC8(crc1stByteBuffer,3);
j = 2;
for(i=1; i<count; i++)
{
TX_Buffer[j] = reg_data[i];
j = j + 1;
temp_crc_buffer[0] = reg_data[i];
TX_Buffer[j] = CRC8(temp_crc_buffer,1);
j = j + 1;
}
HAL_I2C_Mem_Write(&hi2c1, DEV_ADDR, reg_addr, 1, TX_Buffer, crc_count, 1000);
}
#else
HAL_I2C_Mem_Write(&hi2c2, DEV_ADDR, reg_addr, 1, reg_data, count, 1000);
#endif
}
int I2C_ReadReg(uint8_t reg_addr, uint8_t *reg_data, uint8_t count)
{
unsigned int RX_CRC_Fail = 0; // reset to 0. If in CRC Mode and CRC fails, this will be incremented.
uint8_t RX_Buffer [MAX_BUFFER_SIZE] = {0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00};
#if CRC_Mode
{
uint8_t crc_count = 0;
uint8_t ReceiveBuffer [10] = {0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00};
crc_count = count * 2;
unsigned int j;
unsigned int i;
unsigned char CRCc = 0;
uint8_t temp_crc_buffer [3];
HAL_I2C_Mem_Read(&hi2c1, DEV_ADDR, reg_addr, 1, ReceiveBuffer, crc_count, 1000);
uint8_t crc1stByteBuffer [4] = {0x10, reg_addr, 0x11, ReceiveBuffer[0]};
CRCc = CRC8(crc1stByteBuffer,4);
if (CRCc != ReceiveBuffer[1])
{
RX_CRC_Fail += 1;
}
RX_Buffer[0] = ReceiveBuffer[0];
j = 2;
for (i=1; i<count; i++)
{
RX_Buffer[i] = ReceiveBuffer[j];
temp_crc_buffer[0] = ReceiveBuffer[j];
j = j + 1;
CRCc = CRC8(temp_crc_buffer,1);
if (CRCc != ReceiveBuffer[j])
RX_CRC_Fail += 1;
j = j + 1;
}
CopyArray(RX_Buffer, reg_data, crc_count);
}
#else
HAL_I2C_Mem_Read(&hi2c2, DEV_ADDR, reg_addr, 1, reg_data, count, 1000);
#endif
return 0;
}
void BQ769x2_SetRegister(uint16_t reg_addr, uint32_t reg_data, uint8_t datalen)
{
uint8_t TX_Buffer[2] = {0x00, 0x00};
uint8_t TX_RegData[6] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
//TX_RegData in little endian format
TX_RegData[0] = reg_addr & 0xff;
TX_RegData[1] = (reg_addr >> 8) & 0xff;
TX_RegData[2] = reg_data & 0xff; //1st byte of data
switch(datalen)
{
//在3.器件配置中介绍
case 1: //1 byte datalength
I2C_WriteReg(0x3E, TX_RegData, 3);
// delayUS(2000);
TX_Buffer[0] = Checksum(TX_RegData, 3);
TX_Buffer[1] = 0x05; //combined length of register address and data
I2C_WriteReg(0x60, TX_Buffer, 2); // Write the checksum and length
// delayUS(2000);
break;
case 2: //2 byte datalength
TX_RegData[3] = (reg_data >> 8) & 0xff;
I2C_WriteReg(0x3E, TX_RegData, 4);
// delayUS(2000);
TX_Buffer[0] = Checksum(TX_RegData, 4);
TX_Buffer[1] = 0x06; //combined length of register address and data
I2C_WriteReg(0x60, TX_Buffer, 2); // Write the checksum and length
// delayUS(2000);
break;
case 4: //4 byte datalength, Only used for CCGain and Capacity Gain
TX_RegData[3] = (reg_data >> 8) & 0xff;
TX_RegData[4] = (reg_data >> 16) & 0xff;
TX_RegData[5] = (reg_data >> 24) & 0xff;
I2C_WriteReg(0x3E, TX_RegData, 6);
// delayUS(2000);
TX_Buffer[0] = Checksum(TX_RegData, 6);
TX_Buffer[1] = 0x08; //combined length of register address and data
I2C_WriteReg(0x60, TX_Buffer, 2); // Write the checksum and length
// delayUS(2000);
break;
}
}
void CommandSubcommands(uint16_t command) //For Command only Subcommands 用于触发芯片操作而不涉及数据传输
// See the TRM or the BQ76952 header file for a full list of Command-only subcommands
{ //For DEEPSLEEP/SHUTDOWN subcommand you will need to call this function twice consecutively
uint8_t TX_Reg[2] = {0x00, 0x00};
//TX_Reg in little endian format
TX_Reg[0] = command & 0xff;
TX_Reg[1] = (command >> 8) & 0xff;
I2C_WriteReg(0x3E,TX_Reg,2);
// delayUS(2000);
}
void Subcommands(uint16_t command, uint16_t data, uint8_t type) //用于读取或写入数据的子命令,完成复杂指令
// See the TRM or the BQ76952 header file for a full list of Subcommands
{
//security keys and Manu_data writes dont work with this function (reading these commands works)
//max readback size is 32 bytes i.e. DASTATUS, CUV/COV snapshot
uint8_t TX_Reg[4] = {0x00, 0x00, 0x00, 0x00};
uint8_t TX_Buffer[2] = {0x00, 0x00};
//TX_Reg in little endian format
TX_Reg[0] = command & 0xff;
TX_Reg[1] = (command >> 8) & 0xff;
if (type == R) {//read
I2C_WriteReg(0x3E,TX_Reg,2);
delayUS(2000);
I2C_ReadReg(0x40, RX_32Byte, 32); //RX_32Byte is a global variable
}
else if (type == W) {
//FET_Control, REG12_Control
TX_Reg[2] = data & 0xff;
I2C_WriteReg(0x3E,TX_Reg,3);
delayUS(1000);
TX_Buffer[0] = Checksum(TX_Reg, 3);
TX_Buffer[1] = 0x05; //combined length of registers address and data
I2C_WriteReg(0x60, TX_Buffer, 2);
delayUS(1000);
}
else if (type == W2){ //write data with 2 bytes
//CB_Active_Cells, CB_SET_LVL
TX_Reg[2] = data & 0xff;
TX_Reg[3] = (data >> 8) & 0xff;
I2C_WriteReg(0x3E,TX_Reg,4);
delayUS(1000);
TX_Buffer[0] = Checksum(TX_Reg, 4);
TX_Buffer[1] = 0x06; //combined length of registers address and data
I2C_WriteReg(0x60, TX_Buffer, 2);
delayUS(1000);
}
}
void DirectCommands(uint8_t command, uint16_t data, uint8_t type) //用于执行直接命令直接读取寄存器
// See the TRM or the BQ76952 header file for a full list of Direct Commands
{ //type: R = read, W = write
uint8_t TX_data[2] = {0x00, 0x00};
//little endian format
TX_data[0] = data & 0xff;
TX_data[1] = (data >> 8) & 0xff;
if (type == R) {//Read
I2C_ReadReg(command, RX_data, 2); //RX_data is a global variable
// delayUS(2000);
}
if (type == W) {//write
//Control_status, alarm_status, alarm_enable all 2 bytes long
I2C_WriteReg(command,TX_data,2);
// delayUS(2000);
}
}
void BQ769x2_Init() {
// Configures all parameters in device RAM
// Enter CONFIGUPDATE mode (Subcommand 0x0090) - It is required to be in CONFIG_UPDATE mode to program the device RAM settings
// See TRM for full description of CONFIG_UPDATE mode
CommandSubcommands(SET_CFGUPDATE); //进入config_update模式修改固件,以确保安全
// After entering CONFIG_UPDATE mode, RAM registers can be programmed. When programming RAM, checksum and length must also be
// programmed for the change to take effect. All of the RAM registers are described in detail in the BQ769x2 TRM.
// An easier way to find the descriptions is in the BQStudio Data Memory screen. When you move the mouse over the register name,
// a full description of the register and the bits will pop up on the screen.
// 'Power Config' - 0x9234 = 0x2D80
// Setting the DSLP_LDO bit allows the LDOs to remain active when the device goes into Deep Sleep mode
// Set wake speed bits to 00 for best performance
BQ769x2_SetRegister(PowerConfig, 0x2D80, 2); //设置为高速模式,,存疑
// 'REG0 Config' - set REG0_EN bit to enable pre-regulator
BQ769x2_SetRegister(REG0Config, 0x01, 1); //板子为外部供电,应清除此位
// 'REG12 Config' - Enable REG1 with 3.3V output (0x0D for 3.3V, 0x0F for 5V)
BQ769x2_SetRegister(REG12Config, 0x0D, 1); //将reg1设置为3.3 注意手册中只有三位,最低为为使能位,如3.3v为0x7即110,四位为1101即0xd
// Set DFETOFF pin to control BOTH CHG and DSG FET - 0x92FB = 0x42 (set to 0x00 to disable)
BQ769x2_SetRegister(DFETOFFPinConfig, 0x42, 1); //配置多功能引脚,配置为bothoff模式,可以通过发送逻辑信号同时控制俩个fet
// Set up ALERT Pin - 0x92FC = 0x2A
// This configures the ALERT pin to drive high (REG1 voltage) when enabled.
// The ALERT pin can be used as an interrupt to the MCU when a protection has triggered or new measurements are available
BQ769x2_SetRegister(ALERTPinConfig, 0x2A, 1); //板子allert引脚悬空,无需理会
// Set TS1 to measure Cell Temperature - 0x92FD = 0x07
BQ769x2_SetRegister(TS1Config, 0x07, 1);
// Set TS3 to measure FET Temperature - 0x92FF = 0x0F
BQ769x2_SetRegister(TS3Config, 0x0F, 1);
// Set HDQ to measure Cell Temperature - 0x9300 = 0x07
BQ769x2_SetRegister(HDQPinConfig, 0x00, 1); // No thermistor installed on EVM HDQ pin, so set to 0x00
// 'VCell Mode' - Enable 16 cells - 0x9304 = 0x0000; Writing 0x0000 sets the default of 16 cells
BQ769x2_SetRegister(VCellMode, 0x0000, 2);
// Enable protections in 'Enabled Protections A' 0x9261 = 0xBC
// Enables SCD (short-circuit), OCD1 (over-current in discharge), ocd2(disable) ,OCC (over-current in charge),
// COV (over-voltage), CUV (under-voltage) oxbc = 1011 1100
BQ769x2_SetRegister(EnabledProtectionsA, 0xBC, 1);
// Enable all protections in 'Enabled Protections B' 0x9262 = 0xF7
// Enables OTF (over-temperature FET), OTINT (internal over-temperature), OTD (over-temperature in discharge),
// OTC (over-temperature in charge), UTINT (internal under-temperature), UTD (under-temperature in discharge), UTC (under-temperature in charge)
BQ769x2_SetRegister(EnabledProtectionsB, 0xF7, 1);
// 'Default Alarm Mask' - 0x..82 Enables the FullScan and ADScan bits, default value = 0xF800
BQ769x2_SetRegister(DefaultAlarmMask, 0xF882, 2);
// Set up Cell Balancing Configuration - 0x9335 = 0x03 - Automated balancing while in Relax or Charge modes
// Also see "Cell Balancing with BQ769x2 Battery Monitors" document on ti.com
BQ769x2_SetRegister(BalancingConfiguration, 0x03, 1);
// Set up CUV (under-voltage) Threshold - 0x9275 = 0x31 (2479 mV)
// CUV Threshold is this value multiplied by 50.6mV
BQ769x2_SetRegister(CUVThreshold, 0x31, 1); //将CUV(电池欠压)的阈值从默认值修改为其他值。
// Set up COV (over-voltage) Threshold - 0x9278 = 0x55 (4301 mV)
// COV Threshold is this value multiplied by 50.6mV
BQ769x2_SetRegister(COVThreshold, 0x55, 1); //将cov过压阈值修改
// Set up OCC (over-current in charge) Threshold - 0x9280 = 0x05 (10 mV = 10A across 1mOhm sense resistor) Units in 2mV
BQ769x2_SetRegister(OCCThreshold, 0x05, 1); // 修改电池的过流充电阈值(指的是SRP和SRN上的电流)
// Set up OCD1 Threshold - 0x9282 = 0x0A (20 mV = 20A across 1mOhm sense resistor) units of 2mV
BQ769x2_SetRegister(OCD1Threshold, 0x0A, 1); //OCD(over current in discharge)过流放电阈值,1的阈值比2低 此处设置为20mA
// Set up SCD Threshold - 0x9286 = 0x05 (100 mV = 100A across 1mOhm sense resistor) 0x05=100mV
BQ769x2_SetRegister(SCDThreshold, 0x05, 1); //SCD(short-circuit in discharge)放电短路保护,比ocd1和ocd2高的多
// Set up SCD Delay - 0x9287 = 0x03 (30 us) Enabled with a delay of (value - 1) * 15 µs; min value of 1
BQ769x2_SetRegister(SCDDelay, 0x03, 1); //SCD DELAY设置延迟参数,防止由于错误的检测而导致不必要的误警报
// Set up SCDL Latch Limit to 1 to set SCD recovery only with load removal 0x9295 = 0x01
// If this is not set, then SCD will recover based on time (SCD Recovery Time parameter).
BQ769x2_SetRegister(SCDLLatchLimit, 0x01, 1); //放电短路保护的恢复方式,未查到其寄存器 。only with load removal表示只有负载移除后才恢复
// Exit CONFIGUPDATE mode - Subcommand 0x0092
CommandSubcommands(EXIT_CFGUPDATE); //发送此命令,恢复固件正常运行
}
void my_BQ769x2_INIT()
{
CommandSubcommands(SET_CFGUPDATE); //进入config_update模式编辑固件,确保安全
BQ769x2_SetRegister(ALERTPinConfig, 0x21, 1); //将elert引脚设置为输出引脚指示mosfet开启完毕
CommandSubcommands(ALERT_HI); //开始设置ALERT引脚高电平
// CommandSubcommands(PF_RESET); //重启PF
CommandSubcommands(SLEEP_DISABLE); //关闭sleep mode
CommandSubcommands(FET_ENABLE); //使能MOSFET
CommandSubcommands(ALERT_LO); //开始设置ALERT引脚高电平
BQ769x2_SetRegister(ProtectionConfiguration,0x0000,1); //关闭pf模式
// BQ769x2_SetRegister(FETOptions,0x0f,1); //sleep模式下开启mosfet
BQ769x2_SetRegister(VCellMode, 0x0FFF, 1); //初始化为12节电池
BQ769x2_SetRegister(ALERTPinConfig, 0x2A, 1); //将Alert引脚设置为异常状态高电平
BQ769x2_SetRegister(REG12Config, 0xDD, 1); //reg1和2都设置3.3
// Set TS1 to measure FET Temperature = 0x0F
BQ769x2_SetRegister(TS1Config, 0x0F, 1);
// Set TS2 to measure AFE Temperature = 0x0B
BQ769x2_SetRegister(TS2Config, 0x0B, 1);
// Set TS3 to measure CELL Temperature = 0x07
BQ769x2_SetRegister(TS3Config, 0x07, 1);
// // Set DFETOFF pin to control BOTH CHG and DSG FET - 0x92FB = 0x42 (set to 0x00 to disable)
// BQ769x2_SetRegister(DFETOFFPinConfig, 0x42, 1); //配置多功能引脚,配置为bothoff模式,可以通过发送逻辑信号同时控制俩个fet
// Enable protections in 'Enabled Protections A' 0x9261 = 0xBC
// Enables SCD (short-circuit), OCD1 (over-current in discharge), OCC (over-current in charge),
// COV (over-voltage), CUV (under-voltage)
BQ769x2_SetRegister(EnabledProtectionsA, 0xBC, 1);
// // Enable all protections in 'Enabled Protections B' 0x9262 = 0xF7
// // Enables OTF (over-temperature FET), OTINT (internal over-temperature), OTD (over-temperature in discharge),
// // OTC (over-temperature in charge), UTINT (internal under-temperature), UTD (under-temperature in discharge), UTC (under-temperature in charge)
// BQ769x2_SetRegister(EnabledProtectionsB, 0xF7, 1);
//
BQ769x2_SetRegister(EnabledProtectionsB, 0x00, 1);
// // Set TS1 to measure Cell Temperature - 0x92FD = 0x07
// BQ769x2_SetRegister(TS1Config, 0x07, 1);
//
// // Set TS3 to measure FET Temperature - 0x92FF = 0x0F
// BQ769x2_SetRegister(TS3Config, 0x0F, 1);
//未找到此寄存器,可在EV2400查看
// Set up Cell Balancing Configuration - 0x9335 = 0x03 - Automated balancing while in Relax or Charge modes
// Also see "Cell Balancing with BQ769x2 Battery Monitors" document on ti.com
BQ769x2_SetRegister(BalancingConfiguration, 0x03, 1);
// Set up CUV (cell-under-voltage) 50.6* 45(0x2D) (2277 mV) 更改欠压阈值,设置较高的欠压阈值,可以减少电池的深度放电,这里设置为每节2.2V
// CUV Threshold is this value multiplied by 50.6mV
BQ769x2_SetRegister(CUVThreshold, 0x2D, 1);
// Set up COV (cell-over-voltage) Threshold - 0x9278 = 0x55 (4301 mV)
// COV Threshold is this value multiplied by 50.6mV
//71*50.6 每节电池的过压阈值改为3.5V
BQ769x2_SetRegister(COVThreshold, 0x47, 1);
// Set up OCC (over-current in charge) Threshold - 0x9280 = 0x07 (14 mV = 14A across 1mOhm sense resistor) Units in 2mV
BQ769x2_SetRegister(OCCThreshold, 0x07, 1); // 修改电池的过流阈值(指的是SRP和SRN上的电流) 此处修改为14mV
// Set up OCD1 Threshold - 0x9282 = 0x0A (20 mV = 20A across 1mOhm sense resistor) units of 2mV
BQ769x2_SetRegister(OCD1Threshold, 0x08, 1); //OCD1(over current in discharge)过流放电阈值,1的阈值比2低 此处设置为16mV
BQ769x2_SetRegister(OCD2Threshold, 0x07, 1); //此,OCD2未使能,无需设置OCD2(over current in discharge)过流放电阈值,1的阈值比2低 此处设置为14mV
// Set up SCD Threshold - 0x9286 = 0x05 (100 mV = 100A across 1mOhm sense resistor) 0x05=100mV
BQ769x2_SetRegister(SCDThreshold, 0x05, 1); //SCD(short-circuit in discharge)放电短路保护,比ocd1和ocd2高的多,此处设置为100mV
// Set up SCD Delay - 0x9287 = 0x03 (30 us) Enabled with a delay of (value - 1) * 15 µs; min value of 1
BQ769x2_SetRegister(SCDDelay, 0x03, 1); //SCD DELAY设置延迟参数,防止由于错误的检测而导致不必要的误警报
// BQ769x2_SetRegister(LoadDetectActiveTime,0x01,1);
// BQ769x2_SetRegister(LoadDetectRetryDelay,0x00,1);
// Set up SCDL Latch Limit to 1 to set SCD recovery only with load removal 0x9295 = 0x01
// If this is not set, then SCD will recover based on time (SCD Recovery Time parameter).
BQ769x2_SetRegister(SCDLLatchLimit, 0x01, 1); //放电短路保护的恢复方式,未查到其寄存器,可在EV2400查看 。only with load removal表示只有负载移除后才恢复
CommandSubcommands(EXIT_CFGUPDATE); //发送此命令,恢复固件正常运行
}
// ********************************* FET Control Commands ***************************************
void BQ769x2_BOTHOFF () {
// Disables all FETs using the DFETOFF (BOTHOFF) pin
// The DFETOFF pin on the BQ76952EVM should be connected to the MCU board to use this function
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_8, GPIO_PIN_SET); // DFETOFF pin (BOTHOFF) set high
}
void BQ769x2_RESET_BOTHOFF () {
// Resets DFETOFF (BOTHOFF) pin
// The DFETOFF pin on the BQ76952EVM should be connected to the MCU board to use this function
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_8, GPIO_PIN_RESET); // DFETOFF pin (BOTHOFF) set low
}
void BQ769x2_ReadFETStatus() {
// Read FET Status to see which FETs are enabled
DirectCommands(FETStatus, 0x00, R);
FET_Status = (RX_data[1]*256 + RX_data[0]);
DSG = ((0x4 & RX_data[0])>>2);// discharge FET state
CHG = (0x1 & RX_data[0]);// charge FET state
PCHG = ((0x2 & RX_data[0])>>1);// pre-charge FET state
PDSG = ((0x8 & RX_data[0])>>3);// pre-discharge FET state
}
// ********************************* End of FET Control Commands *********************************
// ********************************* BQ769x2 Power Commands *****************************************
//陈氏动力板子通过按键连接RST_SHUT,且无引出排针,故此为可通过按键控制,无需通过主机的gpio口控制
void BQ769x2_ShutdownPin() {
// Puts the device into SHUTDOWN mode using the RST_SHUT pin
// The RST_SHUT pin on the BQ76952EVM should be connected to the MCU board to use this function
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_9, GPIO_PIN_SET); // Sets RST_SHUT pin
}
void BQ769x2_ReleaseShutdownPin() {
// Releases the RST_SHUT pin
// The RST_SHUT pin on the BQ76952EVM should be connected to the MCU board to use this function
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_9, GPIO_PIN_RESET); // Resets RST_SHUT pin
}
// ********************************* End of BQ769x2 Power Commands *****************************************
// ********************************* BQ769x2 Status and Fault Commands *****************************************
uint16_t BQ769x2_ReadAlarmStatus() {
// Read this register to find out why the ALERT pin was asserted
DirectCommands(AlarmStatus, 0x00, R);
return (RX_data[1]*256 + RX_data[0]);
}
void BQ769x2_ReadSafetyStatus() { //good example functions
// Read Safety Status A/B/C and find which bits are set
// This shows which primary protections have been triggered
DirectCommands(SafetyStatusA, 0x00, R);
value_SafetyStatusA = (RX_data[1]*256 + RX_data[0]);
//Example Fault Flags
UV_Fault = ((0x4 & RX_data[0])>>2);
OV_Fault = ((0x8 & RX_data[0])>>3);
SCD_Fault = ((0x8 & RX_data[1])>>3);
OCD_Fault = ((0x2 & RX_data[1])>>1);
DirectCommands(SafetyStatusB, 0x00, R);
value_SafetyStatusB = (RX_data[1]*256 + RX_data[0]);
DirectCommands(SafetyStatusC, 0x00, R);
value_SafetyStatusC = (RX_data[1]*256 + RX_data[0]);
if ((value_SafetyStatusA + value_SafetyStatusB + value_SafetyStatusC) > 1) {
ProtectionsTriggered = 1; }
else {
ProtectionsTriggered = 0; }
}
void BQ769x2_ReadPFStatus() {//读取PF寄存器,永久故障寄存器
// Read Permanent Fail Status A/B/C and find which bits are set
// This shows which permanent failures have been triggered
DirectCommands(PFStatusA, 0x00, R);
value_PFStatusA = (RX_data[1]*256 + RX_data[0]);
DirectCommands(PFStatusB, 0x00, R);
value_PFStatusB = (RX_data[1]*256 + RX_data[0]);
DirectCommands(PFStatusC, 0x00, R);
value_PFStatusC = (RX_data[1]*256 + RX_data[0]);
}
// ********************************* End of BQ769x2 Status and Fault Commands *****************************************
// ********************************* BQ769x2 Measurement Commands *****************************************
uint32_t BQ769x2_ReadVoltage(uint8_t command)
// This function can be used to read a specific cell voltage or stack / pack / LD voltage
{
//RX_data is global var
DirectCommands(command, 0x00, R);
if(command >= Cell1Voltage && command <= Cell16Voltage) {//Cells 1 through 16 (0x14 to 0x32)
return (RX_data[1]*256 + RX_data[0]); //voltage is reported in mV
}
else {//stack, Pack, LD
return 10 * (RX_data[1]*256 + RX_data[0]); //voltage is reported in 0.01V units
}
}
void BQ769x2_ReadAllVoltages() //陈氏动力只接了12节电池
// Reads all cell voltages, Stack voltage, PACK pin voltage, and LD pin voltage
{
int cellvoltageholder = Cell1Voltage; //Cell1Voltage is 0x14
for (int x = 0; x < 16; x++){//Reads all cell voltages
CellVoltage[x] = BQ769x2_ReadVoltage(cellvoltageholder);
cellvoltageholder = cellvoltageholder + 2;
}
//感觉没啥用,可看4.1
Stack_Voltage = (float)BQ769x2_ReadVoltage(StackVoltage) * 0.001f; //单位修改为V
Pack_Voltage = BQ769x2_ReadVoltage(PACKPinVoltage);
LD_Voltage = BQ769x2_ReadVoltage(LDPinVoltage);
}
int BQ769x2_ReadCurrent()
// Reads PACK current
{
// 原函数无法转化负数的电流值,这里使用if进行判断
DirectCommands(CC2Current, 0x00, R);
// 组合 16 位数据(小端模式)
uint16_t raw_value = (RX_data[1] << 8) | RX_data[0];
// 判断是否为负数(最高位 MSB 是否为 1)
if (raw_value & 0x8000)
{
// 负数,进行补码转换(还原原码)
int current = -((~raw_value + 1) & 0xFFFF);
return current;
}
else
{
// 正数,直接返回
return raw_value;
}
// 看4.3 在 NORMAL 模式下运行时每 3ms 生成一个输出,
//return (int16_t)((RX_data[1]<<8) + RX_data[0]); // current is reported in mA
}
//看4.7,4.8
float BQ769x2_ReadTemperature(uint8_t command)
{
DirectCommands(command, 0x00, R);
//RX_data is a global var
return (0.1 * (float)(RX_data[1]*256 + RX_data[0])) - 273.15; // converts from 0.1K to Celcius
}
void BQ769x2_ReadPassQ(){ // Read Accumulated Charge and Time from DASTATUS6 通过移位和加法操作组成一个浮点数。详看4.3的库伦计数器
Subcommands(DASTATUS6, 0x00, R);
AccumulatedCharge_Int = ((RX_32Byte[3]<<24) + (RX_32Byte[2]<<16) + (RX_32Byte[1]<<8) + RX_32Byte[0]); //Bytes 0-3
AccumulatedCharge_Frac = ((RX_32Byte[7]<<24) + (RX_32Byte[6]<<16) + (RX_32Byte[5]<<8) + RX_32Byte[4]); //Bytes 4-7
AccumulatedCharge_Time = ((RX_32Byte[11]<<24) + (RX_32Byte[10]<<16) + (RX_32Byte[9]<<8) + RX_32Byte[8]); //Bytes 8-11 充电时间
}