Compare commits

..

No commits in common. "master" and "home" have entirely different histories.
master ... home

43 changed files with 1723 additions and 5191 deletions

View File

@ -40,8 +40,6 @@
"usart.h": "c", "usart.h": "c",
"w25qxx.h": "c", "w25qxx.h": "c",
"w25q256.h": "c", "w25q256.h": "c",
"gpio.h": "c", "gpio.h": "c"
"bl_usart.h": "c",
"soc.h": "c"
} }
} }

View File

@ -7,7 +7,7 @@
#include "parameter.h" #include "parameter.h"
#include "FM_TIM.h" #include "FM_TIM.h"
#include "inFlash.h" #include "inFlash.h"
#include "SOE.h"
void startInfo(void) void startInfo(void)
{ {
@ -59,13 +59,6 @@ void startInfo(void)
void start(void) void start(void)
{ {
Init(); Init();
uartCommonInit();
// setDutyRatio(0.0001f);
// EN_PWMOUT_Eable();
task_Init(); task_Init();
startInfo(); startInfo();
@ -75,8 +68,6 @@ void start(void)
// cfgTest(); // cfgTest();
// HAL_Delay(1000); // HAL_Delay(1000);
// } // }
/* 启动事件 */
// insertEventsOrderRecord(startEvent);
TimeSliceOffset_Start(); TimeSliceOffset_Start();
} }

View File

@ -12,8 +12,6 @@ void eventsOrderRecordStartInit(void);
void setEventsOrderRecord(void); void setEventsOrderRecord(void);
void readEventsOrderRecord(uint16_t offset, uint8_t *data); void readEventsOrderRecord(uint16_t offset, uint8_t *data);
void insertEventsOrderRecord(eventsOrderRecordMode mode); void insertEventsOrderRecord(eventsOrderRecordMode mode);
void cleanEventsOrderRecord(void);
uint16_t getSoeDataInfoSize(void); uint16_t getSoeDataInfoSize(void);

View File

@ -28,6 +28,6 @@ void checkAbnormal(void);
void WORK_VOLT_Interrupt(void); void WORK_VOLT_Interrupt(void);
void DSG_PROT_Interrupt(void); void DSG_PROT_Interrupt(void);
void EXCHG_PROT_Interrupt(void);
#endif #endif

View File

@ -5,8 +5,8 @@
#include "FM_TIM.h" #include "FM_TIM.h"
#include "comm_types.h" #include "comm_types.h"
#define PI_CONTROL_MAX 0.03f #define PI_CONTROL_MAX 0.1f
#define PI_CONTROL_MIN -0.03f #define PI_CONTROL_MIN -0.1f
BOOL getChargControlFlag(void); BOOL getChargControlFlag(void);
void setChargControlFlag(BOOL state); void setChargControlFlag(BOOL state);

View File

@ -7,23 +7,18 @@
#include "chargControlTypes.h" #include "chargControlTypes.h"
#include "uart_dev.h" #include "uart_dev.h"
/* 是否使能充电控制盒的HY协议 */
#define HY_ChargeControlBox_PROTOCOL_ENABLE
/* SL协议读取寄存器最大地址 */ /* SL协议读取寄存器最大地址 */
#define maxReadRegAddrMacro 0x0150 #define maxReadRegAddrMacro 0x0120
/* SL协议读取寄存器最小地址 */ /* SL协议读取寄存器最小地址 */
#define minReadRegAddrMacro 0x0100 #define minReadRegAddrMacro 0x0100
/* SL协议读取寄存器最大长度 */ /* SL协议读取寄存器最大长度 */
#define maxReadRegAddrNumMacro 80 #define maxReadRegAddrNumMacro 10
/* SL协议写入寄存器最大地址 */ /* SL协议写入寄存器最大地址 */
#define maxWriteRegAddrMacro 0x0150 #define maxWriteRegAddrMacro 0x0120
/* SL协议写入寄存器最小地址 */ /* SL协议写入寄存器最小地址 */
#define minWriteRegAddrMacro 0x0100 #define minWriteRegAddrMacro 0x0100
/* SL协议写入寄存器最大长度 */ /* SL协议写入寄存器最大长度 */
@ -35,19 +30,11 @@
/* SL协议下发配置文件内容最长长度 */ /* SL协议下发配置文件内容最长长度 */
#define maxDistributionCfgLen 230 #define maxDistributionCfgLen 230
/* SL协议读取配置文件内容最长长度 */ /* SL协议读取配置文件内容最长长度 */
#define maxReadCfgLen 80 #define maxReadCfgLen 32
#define floatMagnification 10.0f #define floatMagnification 10.0f
#ifdef HY_ChargeControlBox_PROTOCOL_ENABLE
#define maxDataLenHY 50
#endif
void uartCommonInit(void);
uint16_t checkModebusCrc(uint8_t *arr_buff, uint8_t len); uint16_t checkModebusCrc(uint8_t *arr_buff, uint8_t len);

View File

@ -113,7 +113,6 @@ typedef struct _config_info{
float constantVoltageChargeV; /* 恒压充电时的输出电压(V) */ float constantVoltageChargeV; /* 恒压充电时的输出电压(V) */
float FloatChargeV; /* 浮充充电时的输出电压(V) */ float FloatChargeV; /* 浮充充电时的输出电压(V) */
uint16_t collectOpenCircuitVoltageTime; /* 充电时采集开路电压的间隔时间 */ uint16_t collectOpenCircuitVoltageTime; /* 充电时采集开路电压的间隔时间 */
float reverseChargProtectionCurr; /* 反向充电保护电流 */
uint16_t crc; /* 校验 */ uint16_t crc; /* 校验 */
}config_info; }config_info;
@ -149,8 +148,8 @@ void config_info_start(void);
void readFlashContent(config_info *configInfo); void readFlashContent(config_info *configInfo);
void cfgTest(void); void cfgTest(void);
void saveLoopImpedance(float *loopImpedance); void saveLoopImpedance();
void readLoopImpedance(float *loopImpedance); BOOL readLoopImpedance();
void savetotalElectricityConsumption(float *totalElectricityConsumption); void savetotalElectricityConsumption(float *totalElectricityConsumption);
void readtotalElectricityConsumption(float *totalElectricityConsumption); void readtotalElectricityConsumption(float *totalElectricityConsumption);
void savetotalChargCapacity(float *totalChargCapacity); void savetotalChargCapacity(float *totalChargCapacity);

View File

@ -14,7 +14,7 @@ typedef struct _config_parameter{
uint32_t gw485_Baud; /* 串口波特率 */ uint32_t gw485_Baud; /* 串口波特率 */
uint32_t bat485_Baud; /* 串口波特率,为0代表bms不支持通信 */ uint32_t bat485_Baud; /* 串口波特率,为0代表bms不支持通信 */
uint8_t powerBoxType; /* 是否只充当电源板0x00:不是0xFF:是*/ uint8_t powerBoxType; /* 是否只充当电源板0x00:不是0x01:是*/
float constantVoltageV; /* 恒压充电阈值电压(V) */ float constantVoltageV; /* 恒压充电阈值电压(V) */
float floatI; /* 浮充充电阈值电流(A) */ float floatI; /* 浮充充电阈值电流(A) */
float startSolarOpenCircuitV; /* 启动充电太阳能板开路电压(V) */ float startSolarOpenCircuitV; /* 启动充电太阳能板开路电压(V) */
@ -28,7 +28,7 @@ typedef struct _config_parameter{
uint16_t firstStageProtectionValue; /* 第一段保护ADC值 */ uint16_t firstStageProtectionValue; /* 第一段保护ADC值 */
uint16_t secondStageProtectionDelay; /* 第二段保护延时(100uS) */ uint16_t secondStageProtectionDelay; /* 第二段保护延时(100uS) */
float secondStageProtectionCurr; /* 第二段保护电流(A) */ float secondStageProtectionCurr; /* 第二段保护电流(A) */
uint32_t thirdStageProtectionDelay; /* 第三段保护延时(100uS) */ uint16_t thirdStageProtectionDelay; /* 第三段保护延时(100uS) */
float thirdStageProtectionCurr; /* 第三段保护电流(A) */ float thirdStageProtectionCurr; /* 第三段保护电流(A) */
uint16_t inputPowerLowDetectionDelay; /* 前端输入功率不足检测延时(100uS) */ uint16_t inputPowerLowDetectionDelay; /* 前端输入功率不足检测延时(100uS) */
float inputPowerLowDetectionVolt; /* 前端输入功率不足检测电压(V) */ float inputPowerLowDetectionVolt; /* 前端输入功率不足检测电压(V) */
@ -41,13 +41,13 @@ typedef struct _config_parameter{
float constantVoltageChargeV; /* 恒压充电时的输出电压(V) */ float constantVoltageChargeV; /* 恒压充电时的输出电压(V) */
float FloatChargeV; /* 浮充充电时的输出电压(V) */ float FloatChargeV; /* 浮充充电时的输出电压(V) */
uint16_t collectOpenCircuitVoltageTime; /* 充电时采集开路电压的间隔时间 */ uint16_t collectOpenCircuitVoltageTime; /* 充电时采集开路电压的间隔时间 */
float reverseChargProtectionCurr; /* 反向充电保护电流 */
/* SL */ /* SL */
uint16_t Access_Node_Type; /* 接入节点类型 */ uint16_t Access_Node_Type; /* 接入节点类型 */
uint16_t Communication_Methods; /* 通信方式 */ uint16_t Communication_Methods; /* 通信方式 */
uint8_t startFlagSL[2]; /* 起始标志 */ uint8_t startFlagSL[2]; /* 起始标志 */
uint8_t endFlagSL; /* 结束标志 */ uint8_t endFlagSL; /* 结束标志 */
} config_parameter; } config_parameter;
extern config_parameter g_cfgParameter; extern config_parameter g_cfgParameter;
typedef struct _otherParameter{ typedef struct _otherParameter{
@ -85,7 +85,6 @@ uint8_t getMosTemperState(void);
void setMosTemperState(uint8_t state); void setMosTemperState(uint8_t state);
BOOL getCheckImpedanceState(void); BOOL getCheckImpedanceState(void);
void setCheckImpedanceState(void); void setCheckImpedanceState(void);
void resetCheckImpedanceState(void);
void setLastTime(timeInfo time); void setLastTime(timeInfo time);
timeInfo getLastTime(void); timeInfo getLastTime(void);
@ -125,7 +124,5 @@ BOOL setLoopImpedance(float loopImpedance);
uint16_t getRegistrationStatus(void); uint16_t getRegistrationStatus(void);
void setRegistrationStatus(uint16_t status); void setRegistrationStatus(uint16_t status);
void setExChargeCurr(void);
float getExChargeCurr(void);
#endif #endif

View File

@ -1,8 +0,0 @@
#ifndef BL_SOC_H_
#define BL_SOC_H_
int find_soc(float voltage);
#endif

View File

@ -17,7 +17,6 @@ void startShortCircuitProtection(void);
void stopShortCircuitProtection(void); void stopShortCircuitProtection(void);
void startExcessiveLoadProtection(void); void startExcessiveLoadProtection(void);
void startSoftShortCircuitProtection(void); void startSoftShortCircuitProtection(void);
void startEXCHGSCProtection(void);
void chargRunLed(uint8_t mode); void chargRunLed(uint8_t mode);

View File

@ -23,9 +23,6 @@ void Init(void)
// HAL_Delay(10000); // HAL_Delay(10000);
config_info_start(); config_info_start();
Init_debug_uart();
ADC_Capture_Init(); ADC_Capture_Init();
proportionalInt(g_cfgParameter.powerBoxType); proportionalInt(g_cfgParameter.powerBoxType);
@ -35,6 +32,7 @@ void Init(void)
tim_Init(); tim_Init();
FM_RTC_Init(); FM_RTC_Init();
Init_debug_uart();
Init_BAT485_uart(g_cfgParameter.bat485_Baud); Init_BAT485_uart(g_cfgParameter.bat485_Baud);
Init_GW485_uart(g_cfgParameter.gw485_Baud); Init_GW485_uart(g_cfgParameter.gw485_Baud);
// Init_BAT485_uart(115200); // Init_BAT485_uart(115200);
@ -50,16 +48,7 @@ void Init(void)
HAL_Delay(100); HAL_Delay(100);
setPowerOutput(TRUE); setPowerOutput(TRUE);
// /* 判断有无电池 */ // EN_PWMOUT_Eable();
// if (getOutputVoltage() > 11.0f) {
// setBatteryState(TRUE);
// setPowerOutput(TRUE);
// } else {
// setBatteryState(FALSE);
// }
resetCheckImpedanceState();
// setDutyRatio(0.5); // setDutyRatio(0.5);
// while (1) { // while (1) {
// log_info("Init_debug_uart \n"); // log_info("Init_debug_uart \n");

View File

@ -4,7 +4,6 @@
#include "parameter.h" #include "parameter.h"
#include "FM_RTC.h" #include "FM_RTC.h"
#include "flash.h" #include "flash.h"
#include "capture.h"
#define eventsOrderRecordStartAddr 4096 #define eventsOrderRecordStartAddr 4096
@ -84,8 +83,6 @@ void eventsOrderRecordStartInit(void)
| overTemperature | mos管温度 | | overTemperature | mos管温度 |
| stopTemperature | mos管温度 | | stopTemperature | mos管温度 |
| overchargCurr | | | overchargCurr | |
| hardwareShortCircuitProtection| |
| abnormalControl | |
*/ */
void insertEventsOrderRecord(eventsOrderRecordMode mode) void insertEventsOrderRecord(eventsOrderRecordMode mode)
{ {
@ -130,26 +127,6 @@ void insertEventsOrderRecord(eventsOrderRecordMode mode)
soeInfo.insertData->temp = getSolarInCircuitVoltage(); soeInfo.insertData->temp = getSolarInCircuitVoltage();
} }
else if (mode == hardwareShortCircuitProtection) {
soeInfo.insertData->temp = getDischargCurrent();
}
else if (mode == hardwareInputProtection) {
soeInfo.insertData->temp = get_EXCHG_CURR();
}
else if (mode == InputProtection) {
soeInfo.insertData->temp = get_EXCHG_CURR();
}
else if (mode == startEvent) {
soeInfo.insertData->temp = 0;
}
else if (mode == abnormalControl) {
soeInfo.insertData->temp = getSolarInCircuitVoltage();
}
else { else {
soeInfo.count++; soeInfo.count++;
return; return;
@ -180,16 +157,7 @@ void setEventsOrderRecord(void)
return; return;
} }
write_Flash((uint8_t *)(soeInfo.outData), soeParameters.pos, soeDataInfoSize); write_Flash((uint8_t *)(&soeInfo.outData), soeParameters.pos, soeDataInfoSize);
// read_Flash((uint8_t *)(soeInfo.outData), eventsOrderRecordStartAddr, sizeof(soeStorageParameters));
// debug_printf("mode = %d \n", soeInfo.outData->mode);
// debug_printf("year = %d \n", soeInfo.outData->time.year);
// debug_printf("month = %d \n", soeInfo.outData->time.month);
// debug_printf("day = %d \n", soeInfo.outData->time.day);
// debug_printf("hour = %d \n", soeInfo.outData->time.hour);
// debug_printf("minute = %d \n", soeInfo.outData->time.minute);
// debug_printf("second = %d \n", soeInfo.outData->time.second);
soeParameters.len++; soeParameters.len++;
if (soeParameters.len >= 100) { if (soeParameters.len >= 100) {
@ -225,26 +193,15 @@ void readEventsOrderRecord(uint16_t offset, uint8_t *data)
{ {
uint16_t addr; uint16_t addr;
if (soeParameters.len - offset < 0) { if (soeParameters.len + 1 - offset < 0) {
addr = eventsOrderRecordStartAddr + sizeof(soeStorageParameters) addr = eventsOrderRecordStartAddr + sizeof(soeStorageParameters)
+ (100 + soeParameters.len - offset) * soeDataInfoSize; + (100 + soeParameters.len + 1 - offset) * soeDataInfoSize;
} else { } else {
addr = eventsOrderRecordStartAddr + sizeof(soeStorageParameters) addr = eventsOrderRecordStartAddr + sizeof(soeStorageParameters)
+ (soeParameters.len - offset) * soeDataInfoSize; + (soeParameters.len + 1 - offset) * soeDataInfoSize;
} }
read_Flash(data, addr, soeDataInfoSize); read_Flash(data, addr, soeDataInfoSize);
} }
/**
* @brief SOE所有事件
* @param
*/
void cleanEventsOrderRecord(void)
{
erase_Sector_Flash((eventsOrderRecordStartAddr / 4096));
soeParameters.len = 0;
soeParameters.pos = eventsOrderRecordStartAddr + sizeof(soeParameters);
write_Flash((uint8_t *)(&soeParameters), eventsOrderRecordStartAddr, sizeof(soeParameters));
}

View File

@ -62,7 +62,6 @@ void setDisChargOverLoad(void)
/* 过载时间过长关闭输出 */ /* 过载时间过长关闭输出 */
if (num2 >= g_cfgParameter.secondStageProtectionDelay) { if (num2 >= g_cfgParameter.secondStageProtectionDelay) {
num2 = 0; num2 = 0;
// debug_printf("in secondStageProtection \n");
setPowerOutput(FALSE); setPowerOutput(FALSE);
disChargOverLoad = TRUE; disChargOverLoad = TRUE;
insertEventsOrderRecord(secondStageProtection); insertEventsOrderRecord(secondStageProtection);
@ -95,14 +94,11 @@ void setSoftShortCircuit(uint16_t disChargCurrAdcNum)
/* 20uS内都短路则关闭输出 */ /* 20uS内都短路则关闭输出 */
if (num >= g_cfgParameter.firstStageProtectionDelay) { if (num >= g_cfgParameter.firstStageProtectionDelay) {
num = 0;
setPowerOutput(FALSE); setPowerOutput(FALSE);
// shortCircuitFlag = TRUE; shortCircuitFlag = TRUE;
// shortCircuit++; shortCircuit++;
// debug_printf("in firstStageProtection %d \n", g_cfgParameter.firstStageProtectionValue);
// debug_printf("in firstStageProtection %d \n", disChargCurrAdcNum);
insertEventsOrderRecord(firstStageProtection); insertEventsOrderRecord(firstStageProtection);
// startSoftShortCircuitProtection(); startSoftShortCircuitProtection();
} }
} }
void setSoftShortCircuit1(void) void setSoftShortCircuit1(void)
@ -299,23 +295,12 @@ void checkFFMOS_CON(void)
// FFMOS_CON_Close(); // FFMOS_CON_Close();
// } // }
static uint8_t num = 100; if (getChargCurrent() > 5.0f && FALSE == FFMOS_CON_read()) {
if (getChargCurrent() > 8.0f && FALSE == FFMOS_CON_read()) {
num--;
if (!num) {
FFMOS_CON_Open(); FFMOS_CON_Open();
} }
}
else if (getChargCurrent() < 2.0f && TRUE == FFMOS_CON_read()) { else if (getChargCurrent() < 2.0f && TRUE == FFMOS_CON_read()) {
// num--;
// if (!num) {
// FFMOS_CON_Close();
// }
FFMOS_CON_Close(); FFMOS_CON_Close();
} }
else {
num = 100;
}
} }
// /** // /**
@ -357,7 +342,7 @@ void setOverLoad(void)
} }
/* 多次进入输出过载,关闭输出 */ /* 多次进入输出过载,关闭输出 */
if (getExcessiveLoad() >= 2) { if (getExcessiveLoad() > 2) {
zeroExcessiveLoad(); zeroExcessiveLoad();
insertEventsOrderRecord(lowInputLoad); insertEventsOrderRecord(lowInputLoad);
} }
@ -373,19 +358,14 @@ void lowInputLoadDetection(void)
{ {
static int num = 0; static int num = 0;
if (excessiveLoadInterruptFlag == TRUE if (excessiveLoadInterruptFlag == TRUE && getOutputVoltage() < g_cfgParameter.inputPowerLowDetectionVolt) {
&& getOutputVoltage() < g_cfgParameter.inputPowerLowDetectionVolt
&& getDischargCurrent() < g_cfgParameter.thirdStageProtectionCurr) {
num++; num++;
// setOverLoad();
} else { } else {
num = 0; num = 0;
excessiveLoadInterruptFlag = FALSE; excessiveLoadInterruptFlag = FALSE;
} }
if (excessiveLoadInterruptFlag == TRUE && num == g_cfgParameter.inputPowerLowDetectionDelay) { if (excessiveLoadInterruptFlag == TRUE && num == g_cfgParameter.inputPowerLowDetectionDelay) {
num = 0;
excessiveLoadInterruptFlag = FALSE;
setOverLoad(); setOverLoad();
} }
} }
@ -399,15 +379,7 @@ void lowInputLoadDetection(void)
*/ */
void judgeChargCurr(void) void judgeChargCurr(void)
{ {
static uint16_t num = 0;
if (getChargCurrent() > g_cfgParameter.maxChargCurr) { if (getChargCurrent() > g_cfgParameter.maxChargCurr) {
num++;
} else {
num = 0;
}
if (num > 500) {
num = 0;
stopChargWork(); stopChargWork();
insertEventsOrderRecord(overchargCurr); insertEventsOrderRecord(overchargCurr);
} }
@ -469,41 +441,23 @@ void WORK_VOLT_Interrupt(void)
void DSG_PROT_Interrupt(void) void DSG_PROT_Interrupt(void)
{ {
setShortCircuit(); setShortCircuit();
setPowerOutput(FALSE);
/* 第一次进入输出短路,启动短路任务 */ /* 第一次进入输出短路,启动短路任务 */
if (getShortCircuit() == 1) { if (getShortCircuit() == 1) {
setShortCircuitFlag(TRUE);
startShortCircuitProtection(); startShortCircuitProtection();
} }
/* 一定时间内第二次进入输出短路保护,关闭输出 */ /* 一定时间内第二次进入输出短路保护,关闭输出 */
else if (getShortCircuit() >= 2) { else if (getShortCircuit() >= 2) {
stopShortCircuitProtection(); stopShortCircuitProtection();
// setPowerOutput(FALSE);
zeroShortCircuit();
insertEventsOrderRecord(hardwareShortCircuitProtection);
}
}
/**
* @brief
* @param
* @retval
*
*/
void EXCHG_PROT_Interrupt(void)
{
setShortCircuit();
setPowerOutput(FALSE); setPowerOutput(FALSE);
/* 第一次进入输出短路,启动短路任务 */ zeroShortCircuit();
if (getShortCircuit() == 1) {
startEXCHGSCProtection();
}
/* 一定时间内第二次进入输出短路保护,关闭输出 */
else if (getShortCircuit() >= 2) {
stopShortCircuitProtection();
insertEventsOrderRecord(hardwareInputProtection);
} }
} }

View File

@ -4,7 +4,6 @@
#include "comm_types.h" #include "comm_types.h"
#include "FM_GPIO.h" #include "FM_GPIO.h"
#include "task.h" #include "task.h"
#include "SOE.h"
static BOOL stopChargConditions(void); static BOOL stopChargConditions(void);
@ -103,7 +102,7 @@ void mppt_constantVoltageO(float OutVoltage)
// static float lastVolt = 0; // static float lastVolt = 0;
// static float lastStepPwm = 0; // static float lastStepPwm = 0;
static float lastDutyRatio = 0; static float lastDutyRatio = 0;
static float kp = 0.002; static float kp = 0.005;
static float ki = 0.00001; static float ki = 0.00001;
static float outVolt; static float outVolt;
static float error; static float error;
@ -335,34 +334,20 @@ void mppt_readJust(void)
// return; // return;
/* 调节电压,两个电压步调节 */ /* 调节电压,两个电压步调节 */
static float stepV1 = 0.2;
static float stepV2 = 0.05;
static float Power = 0; static float Power = 0;
// static float totalPower = 0; static float totalPower = 0;
// static float powerData[50] = {0}; static float powerData[50] = {0};
// static uint8_t powerIndex = 0; static uint8_t powerIndex = 0;
static float totalChargeCurr = 0; /* 获取50次的平均值 */
static float chargeCurrData[50] = {0}; totalPower -= powerData[powerIndex];
static uint8_t chargeCurrIndex = 0; powerData[powerIndex] = getOutputVoltage() * getChargCurrent();
totalPower += powerData[powerIndex];
/* 获取50次值的和 */ powerIndex++;
totalChargeCurr -= chargeCurrData[chargeCurrIndex]; if (powerIndex >= 50) {
chargeCurrData[chargeCurrIndex] = getChargCurrent(); powerIndex = 0;
totalChargeCurr += chargeCurrData[chargeCurrIndex];
chargeCurrIndex++;
if (chargeCurrIndex >= 50) {
chargeCurrIndex = 0;
} }
// totalPower -= powerData[powerIndex];
// powerData[powerIndex] = getOutputVoltage() * getChargCurrent();
// totalPower += powerData[powerIndex];
// powerIndex++;
// if (powerIndex >= 50) {
// powerIndex = 0;
// }
static float lPower = 0; static float lPower = 0;
static float lLPower = 0; static float lLPower = 0;
// static float lLLPower = 0; // static float lLLPower = 0;
@ -371,6 +356,9 @@ void mppt_readJust(void)
// static float kp = 0.005; // static float kp = 0.005;
// static float ki = 0.00001; // static float ki = 0.00001;
static float stepV1 = 0.2;
static float stepV2 = 0.1;
static uint8_t flag1 = 0; //表明上次运算是加还是减 static uint8_t flag1 = 0; //表明上次运算是加还是减
/* 延时一段时间才判断 */ /* 延时一段时间才判断 */
@ -390,14 +378,12 @@ void mppt_readJust(void)
} }
if (getMosTemperState() == mosTemperReduce) { if (getMosTemperState() == mosTemperReduce) {
SolarInCircuitV = 20; SolarInCircuitV = 16;
} }
flag = 0; flag = 0;
// Power = totalPower / 30.0f; Power = totalPower / 50.0f;
// Power = totalPower;
Power = totalChargeCurr * getOutputVoltage();
static float powerT = 0; static float powerT = 0;
powerT = Power - lPower; powerT = Power - lPower;
@ -405,89 +391,10 @@ void mppt_readJust(void)
powerT = -powerT; powerT = -powerT;
} }
/* 滞环值 */
float hysteresisValue1;
float hysteresisValue2;
/* 一段时间内电流都很小则固定电压输出 */
static uint8_t currMinFlag = 0;
static uint8_t currMinFlag1 = 0;
// if (getChargCurrent() < 0.8f) {
if (totalChargeCurr < 120) {
// hysteresisValue1 = getChargCurrent() * 1.7f;
// hysteresisValue2 = getChargCurrent() * 12;
currMinFlag++;
if (currMinFlag == 8) {
currMinFlag = 0;
SolarInCircuitV = 18.0f;
currMinFlag1 = 1;
}
return;
}
// else if (getChargCurrent() < 3 && currMinFlag1) {
else if (totalChargeCurr < 150 && currMinFlag1) {
currMinFlag1 = 0;
currMinFlag = 0;
return;
}
// else if (getChargCurrent() < 7) {
else if (totalChargeCurr < 350) {
currMinFlag1 = 0;
currMinFlag = 0;
// hysteresisValue1 = getChargCurrent() * 1.1f;
// hysteresisValue2 = getChargCurrent() * 10;
hysteresisValue1 = totalChargeCurr / 40.0f;
hysteresisValue2 = totalChargeCurr / 4.0f;
}
// else if (getChargCurrent() < 20) {
else if (totalChargeCurr < 1000) {
currMinFlag1 = 0;
currMinFlag = 0;
// hysteresisValue1 = getChargCurrent() * 0.7f;
// hysteresisValue2 = getChargCurrent() * 7;
hysteresisValue1 = totalChargeCurr / 60.0f;
hysteresisValue2 = totalChargeCurr / 6.0f;
}
// else if (getChargCurrent() < 25) {
else if (totalChargeCurr < 1250) {
currMinFlag1 = 0;
currMinFlag = 0;
// hysteresisValue1 = getChargCurrent() * 0.5f;
// hysteresisValue2 = getChargCurrent() * 5;
hysteresisValue1 = totalChargeCurr / 90.0f;
hysteresisValue2 = totalChargeCurr / 9.0f;
}
else {
currMinFlag1 = 0;
currMinFlag = 0;
// hysteresisValue1 = getChargCurrent() * 0.3f;
// hysteresisValue2 = getChargCurrent() * 3;
hysteresisValue1 = totalChargeCurr / 140.0f;
hysteresisValue2 = totalChargeCurr / 14.0f;
}
// else {
// currMinFlag1 = 0;
// currMinFlag = 0;
// hysteresisValue1 = 120;
// hysteresisValue2 = 100;
// }
static uint8_t numFlag = 0;
// if ((lPower + 0.8f < Power) && (lLPower + 0.8f < Power) && (lLLPower + 0.8f < Power)) { // if ((lPower + 0.8f < Power) && (lLPower + 0.8f < Power) && (lLLPower + 0.8f < Power)) {
// if ((lPower + 0.1f < Power) && (lLPower + 0.1f < Power)) { if ((lPower + 0.1f < Power) && (lLPower + 0.1f < Power)) {
if ((lPower + hysteresisValue1 < Power) && (lLPower + hysteresisValue1 < Power)) {
numFlag = 0;
// if ((lPower + 0.3f < Power)) { // if ((lPower + 0.3f < Power)) {
if (powerT > hysteresisValue2) { if (powerT > 5) {
if (flag1) { if (flag1) {
SolarInCircuitV += stepV1; SolarInCircuitV += stepV1;
flag1 = 1; flag1 = 1;
@ -505,11 +412,9 @@ void mppt_readJust(void)
} }
} }
// } else if ((lPower - 0.8f > Power) && (lLPower - 0.8f > Power) && (lLLPower - 0.8f > Power)) { // } else if ((lPower - 0.8f > Power) && (lLPower - 0.8f > Power) && (lLLPower - 0.8f > Power)) {
} else if ((lPower - hysteresisValue1 > Power) && (lLPower - hysteresisValue1 > Power)) { } else if ((lPower - 0.1f > Power) && (lLPower - 0.1f > Power)) {
// } else if ((lPower - 0.3f > Power)) { // } else if ((lPower - 0.3f > Power)) {
numFlag = 0; if (powerT > 5) {
if (powerT > hysteresisValue2) {
numFlag = 0;
if (flag1) { if (flag1) {
SolarInCircuitV -= stepV1; SolarInCircuitV -= stepV1;
flag1 = 0; flag1 = 0;
@ -526,30 +431,11 @@ void mppt_readJust(void)
flag1 = 1; flag1 = 1;
} }
} }
} else {
numFlag++;
} }
/* 一段时间内都未调节 */ if (SolarInCircuitV > 20.0f) {
if (numFlag == 10) { SolarInCircuitV = 20.0f;
if (Power < 300) {
SolarInCircuitV = 17.0f;
} }
else if (flag1) {
SolarInCircuitV -= stepV2;
flag1 = 0;
}
else {
SolarInCircuitV += stepV2;
flag1 = 1;
}
}
if (SolarInCircuitV > 19.0f) {
SolarInCircuitV = 19.0f;
}
else if (SolarInCircuitV < 16.0f) { else if (SolarInCircuitV < 16.0f) {
SolarInCircuitV = 16.0f; SolarInCircuitV = 16.0f;
} }
@ -571,7 +457,6 @@ void endChargWork(void)
setDutyRatioToZero(); setDutyRatioToZero();
setMPPT_Mode(noWork); setMPPT_Mode(noWork);
beginStartControlTask(); beginStartControlTask();
EN_PWMOUT_Diseable();
} }
/** /**
@ -585,7 +470,6 @@ void stopChargWork(void)
setChargControlFlag(FALSE); setChargControlFlag(FALSE);
setDutyRatioToZero(); setDutyRatioToZero();
setMPPT_Mode(noWork); setMPPT_Mode(noWork);
EN_PWMOUT_Diseable();
} }
/** /**
@ -597,7 +481,6 @@ void stopChargWork(void)
void beginChargWork(void) void beginChargWork(void)
{ {
beginStartControlTask(); beginStartControlTask();
EN_PWMOUT_Eable();
} }
/** /**
@ -609,7 +492,6 @@ void beginChargWork(void)
void startChargWork(void) void startChargWork(void)
{ {
beginSoftStartTask(); beginSoftStartTask();
EN_PWMOUT_Eable();
} }
@ -624,34 +506,6 @@ BOOL stopChargConditions(void)
{ {
if (getSolarInCircuitVoltage() < g_cfgParameter.stopSolarOutputCircuitV if (getSolarInCircuitVoltage() < g_cfgParameter.stopSolarOutputCircuitV
&& getChargCurrent() < 1) { && getChargCurrent() < 1) {
// log_info("in stopChargConditions stopChargWork");
return TRUE;
}
/* 异常情况关闭充电 */
static uint16_t flag = 0;
if ((getSolarInCircuitVoltage() < (g_cfgParameter.stopSolarOutputCircuitV + 1)
|| getSolarInCircuitVoltage() > 18.5f)
&& getChargCurrent() < 0.1f
&& getMPPT_Mode() == MPPT) {
// return TRUE;
flag++;
}
// if ((getSolarInCircuitVoltage() < 17.8f
// || getSolarInCircuitVoltage() > 20)
// && getChargCurrent() < 0.1f
// && getMPPT_Mode() == MPPT) {
// // return TRUE;
// flag++;
// }
// else {
// flag = 0;
// }
if (flag > 20000) {
flag = 0;
insertEventsOrderRecord(abnormalControl);
return TRUE; return TRUE;
} }
@ -684,7 +538,7 @@ BOOL floatChargConditions(void)
BOOL mpptChargConditions(void) BOOL mpptChargConditions(void)
{ {
if (((g_cfgParameter.constantVoltageChargeV - 0.2f) > getBatteryVoltage()) if (((g_cfgParameter.constantVoltageChargeV - 0.2f) > getBatteryVoltage())
&& (getChargCurrent() > 0.05f)) { && (getChargCurrent() > 0.1f)) {
return TRUE; return TRUE;
} }
@ -811,8 +665,7 @@ void BatteryChargControl(void)
case MPPT: case MPPT:
mpptCharge(); mpptCharge();
// mppt_constantVoltage(17.5f); // mppt_constantVoltage(17.0f);
// setDutyRatio(0.1f);
break; break;
case constantVoltage: case constantVoltage:
@ -825,8 +678,7 @@ void BatteryChargControl(void)
default: default:
setMPPT_Mode(noWork); setMPPT_Mode(noWork);
// stopChargWork(); stopChargWork();
endChargWork();
break; break;
} }
} }
@ -847,15 +699,12 @@ void setChargControlFlag(BOOL state)
{ {
if (state == TRUE || state == FALSE) { if (state == TRUE || state == FALSE) {
chargControlFlag = state; chargControlFlag = state;
// debug_printf("chargControlFlag : %d", state);
} }
if (state == TRUE) { if (state == TRUE) {
chargRunLed(runLedChargMode); chargRunLed(runLedChargMode);
// debug_printf("setChargControlFlag is true");
} else if (state == FALSE) { } else if (state == FALSE) {
chargRunLed(runLedOtherMode); chargRunLed(runLedOtherMode);
// debug_printf("setChargControlFlag is false");
} }
} }
@ -887,6 +736,5 @@ void bl_chargControl(void)
} else { } else {
noBatteryChargControl(); noBatteryChargControl();
} }
// noBatteryChargControl();
} }

View File

@ -2,7 +2,6 @@
#include "bl_comm.h" #include "bl_comm.h"
#include "uart_dev.h" #include "uart_dev.h"
#include "interruptSend.h" #include "interruptSend.h"
#include "SOE.h"
uint8_t rs485_buff[buffLen]={0x00}; uint8_t rs485_buff[buffLen]={0x00};

File diff suppressed because it is too large Load Diff

View File

@ -155,7 +155,7 @@ void readFlashContent(config_info *configInfo)
configInfo->gw485_Baud = 115200; configInfo->gw485_Baud = 115200;
configInfo->bat485_Baud = 115200; configInfo->bat485_Baud = 115200;
configInfo->powerBoxType = 0xFF; configInfo->powerBoxType = 0x01;
configInfo->constantVoltageV = 14; configInfo->constantVoltageV = 14;
configInfo->floatI = 0.1f; configInfo->floatI = 0.1f;
@ -190,8 +190,6 @@ void readFlashContent(config_info *configInfo)
configInfo->FloatChargeV = 14.2f; configInfo->FloatChargeV = 14.2f;
configInfo->collectOpenCircuitVoltageTime = 1800; configInfo->collectOpenCircuitVoltageTime = 1800;
configInfo->reverseChargProtectionCurr = 2;
// configInfo->firstStageProtectionCurr = firstStageProtectionCurrMacro; // configInfo->firstStageProtectionCurr = firstStageProtectionCurrMacro;
// configInfo->firstStageProtectionDelay = firstStageProtectionDelayMacro; // configInfo->firstStageProtectionDelay = firstStageProtectionDelayMacro;
// configInfo->firstStageProtectionValue = firstStageProtectionValueMacro; // configInfo->firstStageProtectionValue = firstStageProtectionValueMacro;
@ -229,9 +227,6 @@ void config_info_start(void)
g_cfgParameter.gw485_Baud = temp_configInfo.gw485_Baud; g_cfgParameter.gw485_Baud = temp_configInfo.gw485_Baud;
g_cfgParameter.bat485_Baud = temp_configInfo.bat485_Baud; g_cfgParameter.bat485_Baud = temp_configInfo.bat485_Baud;
// g_cfgParameter.bat485_Baud = 115200;
// static volatile uint32_t tempBatBaud;
// tempBatBaud = temp_configInfo.bat485_Baud;
g_cfgParameter.uniqueDeviceID[0] = temp_configInfo.uniqueDeviceID[0]; g_cfgParameter.uniqueDeviceID[0] = temp_configInfo.uniqueDeviceID[0];
g_cfgParameter.uniqueDeviceID[1] = temp_configInfo.uniqueDeviceID[1]; g_cfgParameter.uniqueDeviceID[1] = temp_configInfo.uniqueDeviceID[1];
@ -274,28 +269,22 @@ void config_info_start(void)
g_cfgParameter.constantVoltageChargeV = temp_configInfo.constantVoltageChargeV; g_cfgParameter.constantVoltageChargeV = temp_configInfo.constantVoltageChargeV;
g_cfgParameter.FloatChargeV = temp_configInfo.FloatChargeV; g_cfgParameter.FloatChargeV = temp_configInfo.FloatChargeV;
g_cfgParameter.collectOpenCircuitVoltageTime= temp_configInfo.collectOpenCircuitVoltageTime; g_cfgParameter.collectOpenCircuitVoltageTime= temp_configInfo.collectOpenCircuitVoltageTime;
g_cfgParameter.reverseChargProtectionCurr = temp_configInfo.reverseChargProtectionCurr;
/* 读取的回路阻抗无效则回路阻抗设置为0 */ /* 读取的回路阻抗无效则回路阻抗设置为0 */
float fTemp; if (readLoopImpedance() == FALSE) {
// fTemp = 0.01f;
// saveLoopImpedance(&fTemp);
readLoopImpedance(&fTemp);
// setLoopImpedance(fTemp);
// if (getLoopImpedance() < 0 || getLoopImpedance() > 0.3f) {
if (!setLoopImpedance(fTemp)) {
setLoopImpedance(0); setLoopImpedance(0);
fTemp = getLoopImpedance(); saveLoopImpedance();
saveLoopImpedance(&fTemp);
} }
// readtotalElectricityConsumption(&fTemp); float fTemp;
// totalElectricityConsumptionInt(fTemp); readtotalElectricityConsumption(&fTemp);
// readtotalChargCapacity(&fTemp); totalElectricityConsumptionInt(fTemp);
// totalChargCapacityInt(fTemp); readtotalChargCapacity(&fTemp);
// timeInfo time; totalChargCapacityInt(fTemp);
// readTime(&time);
// setLastTime(time); timeInfo time;
readTime(&time);
setLastTime(time);
} }
@ -304,18 +293,22 @@ void config_info_start(void)
* @brief flash中 * @brief flash中
* @param * @param
*/ */
void saveLoopImpedance(float *loopImpedance) void saveLoopImpedance(void)
{ {
write_Flash((uint8_t *)loopImpedance, LoopImpedance_SAVE_addr, sizeof(float)); float loopImpedance;
loopImpedance = getLoopImpedance();
write_Flash((uint8_t *)&loopImpedance, LoopImpedance_SAVE_addr, sizeof(float));
} }
/** /**
* @brief flash中的回路阻抗 * @brief flash中的回路阻抗
* @param * @param
*/ */
void readLoopImpedance(float *loopImpedance) BOOL readLoopImpedance(void)
{ {
read_Flash((uint8_t *)loopImpedance, LoopImpedance_SAVE_addr, sizeof(float)); float loopImpedance;
read_Flash((uint8_t *)&loopImpedance, LoopImpedance_SAVE_addr, sizeof(float));
return setLoopImpedance(loopImpedance);
} }
/** /**

View File

@ -1,6 +1,5 @@
#include "interruptSend.h" #include "interruptSend.h"
#include "bl_usart.h"
#define RS485_MAX_PACK_DATA_LEN 256 #define RS485_MAX_PACK_DATA_LEN 256
@ -169,14 +168,6 @@ void setSendOverStateGw(void)
NVIC_SystemReset(); NVIC_SystemReset();
} }
#ifdef HY_ChargeControlBox_PROTOCOL_ENABLE
/* HY复位指令 */
if (uart_send.sendDataGw->data[11] = 0x66
&& uart_send.sendDataGw->data[14] == 0xFF) {
NVIC_SystemReset();
}
#endif
uart_send.sendOverStateGw = TRUE; uart_send.sendOverStateGw = TRUE;
uart_send.sendStateGw = FALSE; uart_send.sendStateGw = FALSE;
uart_send.sendDataGw->dataState = FALSE; uart_send.sendDataGw->dataState = FALSE;

View File

@ -4,8 +4,6 @@
#include "FM_GPIO.h" #include "FM_GPIO.h"
#include "capture.h" #include "capture.h"
#include "bl_chargControl.h" #include "bl_chargControl.h"
#include <math.h>
#include "soc.h"
config_parameter g_cfgParameter = {0}; config_parameter g_cfgParameter = {0};
static otherParameter g_otherParameter = {0}; static otherParameter g_otherParameter = {0};
@ -16,8 +14,6 @@ static uint8_t mosTemperState = mosTemperFull; /* mos管温度状态 */
static BOOL checkImpedanceState = FALSE; /* 启动后是否进行了回路阻抗检测 */ static BOOL checkImpedanceState = FALSE; /* 启动后是否进行了回路阻抗检测 */
static timeInfo lastTime = {0}; /* 上次读取充放电量参数的时间 */ static timeInfo lastTime = {0}; /* 上次读取充放电量参数的时间 */
static float exChargeCurr = 0;
/** /**
* @brief * @brief
* @param * @param
@ -60,8 +56,8 @@ float getDutyRatio(void)
*/ */
void setDutyRatio(float DutyRatio) void setDutyRatio(float DutyRatio)
{ {
if (DutyRatio > 0.9f) { if (DutyRatio > 0.95f) {
dutyRatio = 0.9f; dutyRatio = 0.95f;
} }
else if (DutyRatio < 0.05f) { else if (DutyRatio < 0.05f) {
dutyRatio = 0.05f; dutyRatio = 0.05f;
@ -80,9 +76,9 @@ void setDutyRatio(float DutyRatio)
*/ */
void setDutyRatioToZero(void) void setDutyRatioToZero(void)
{ {
EN_PWMOUT_Diseable();
dutyRatio = 0; dutyRatio = 0;
set_pwmDutyRatio(dutyRatio); set_pwmDutyRatio(dutyRatio);
EN_PWMOUT_Diseable();
} }
/** /**
@ -129,16 +125,6 @@ void setCheckImpedanceState(void)
checkImpedanceState = TRUE; checkImpedanceState = TRUE;
} }
/**
* @brief
* @param
* @retval
*
*/
void resetCheckImpedanceState(void)
{
checkImpedanceState = FALSE;
}
/** /**
* @brief * @brief
@ -179,9 +165,7 @@ float getBatteryVoltage(void)
*/ */
void setBatteryVoltage(void) void setBatteryVoltage(void)
{ {
// g_otherParameter.Battery_Voltage = g_otherParameter.Output_Voltage g_otherParameter.Battery_Voltage = g_otherParameter.Output_Voltage
// - getChargBatteryCurrent() * getLoopImpedance();
g_otherParameter.Battery_Voltage = getOutputVoltage()
- getChargBatteryCurrent() * getLoopImpedance(); - getChargBatteryCurrent() * getLoopImpedance();
} }
@ -402,7 +386,7 @@ float getSOC(void)
*/ */
void setSOC(void) void setSOC(void)
{ {
g_otherParameter.SOC = find_soc(getBatteryVoltage()) / 100.0f;
} }
/** /**
@ -511,10 +495,6 @@ BOOL setLoopImpedance(float loopImpedance)
return FALSE; return FALSE;
} }
if (fpclassify(loopImpedance) == FP_NAN) {
return FALSE;
}
g_otherParameter.loopImpedance = loopImpedance; g_otherParameter.loopImpedance = loopImpedance;
return TRUE; return TRUE;
} }
@ -540,24 +520,3 @@ void setRegistrationStatus(uint16_t status)
g_otherParameter.Registration_Status = status; g_otherParameter.Registration_Status = status;
} }
} }
/**
* @brief
* @param
* @retval
*/
void setExChargeCurr(void)
{
exChargeCurr = get_EXCHG_CURR();
}
/**
* @brief
* @param
* @retval
*/
float getExChargeCurr(void)
{
return exChargeCurr;
}

View File

@ -1,119 +0,0 @@
#include "soc.h"
// const float ocv_table[101] = {
// 2.80, 2.85, 2.90, 2.95, 3.00, 3.05, 3.10, 3.12, 3.14, 3.16, // 0-9%
// 3.18, 3.19, 3.20, 3.20, 3.20, 3.20, 3.21, 3.21, 3.21, 3.21, // 10-19%
// 3.22, 3.22, 3.22, 3.22, 3.22, 3.22, 3.23, 3.23, 3.23, 3.23, // 20-29%
// 3.23, 3.23, 3.23, 3.23, 3.23, 3.23, 3.23, 3.24, 3.24, 3.24, // 30-39%
// 3.24, 3.24, 3.25, 3.25, 3.25, 3.25, 3.25, 3.25, 3.25, 3.25, // 40-49%
// 3.25, 3.25, 3.25, 3.25, 3.25, 3.26, 3.26, 3.26, 3.26, 3.26, // 50-59%
// 3.26, 3.26, 3.26, 3.26, 3.26, 3.26, 3.27, 3.27, 3.27, 3.27, // 60-69%
// 3.28, 3.28, 3.28, 3.29, 3.29, 3.29, 3.30, 3.30, 3.31, 3.31, // 70-79%
// 3.32, 3.32, 3.33, 3.34, 3.35, 3.36, 3.38, 3.40, 3.42, 3.45, // 80-89%
// 3.48, 3.50, 3.52, 3.54, 3.56, 3.58, 3.60, 3.62, 3.63, 3.64, // 90-99%
// 3.65 // 100%
// };
// /**
// * 四节串联磷酸铁锂电池组 SOC-OCV 对应表 (SOC步长1%)
// * 电压范围11.2V (0%) ~ 14.6V (100%)
// * 注意:
// * 1. 假设电池完全均衡,实际需考虑单体差异
// * 2. 电压单位伏特V
// */
// const float ocv_table_4s[101] = {
// // 0-9% (单节2.80V~3.16V → 四节11.20V~12.64V)
// 11.20, 11.40, 11.60, 11.80, 12.00, 12.20, 12.40, 12.48, 12.56, 12.64, // 0-9%
// // 10-19% (单节3.18V~3.21V → 四节12.72V~12.84V)
// 12.72, 12.76, 12.80, 12.80, 12.80, 12.80, 12.84, 12.84, 12.84, 12.84, // 10-19%
// // 20-29% (单节3.22V~3.23V → 四节12.88V~12.92V)
// 12.88, 12.88, 12.88, 12.88, 12.88, 12.88, 12.92, 12.92, 12.92, 12.92, // 20-29%
// // 30-39% (单节3.23V~3.24V → 四节12.92V~12.96V)
// 12.92, 12.92, 12.92, 12.92, 12.92, 12.92, 12.92, 12.96, 12.96, 12.96, // 30-39%
// // 40-49% (单节3.24V~3.25V → 四节12.96V~13.00V)
// 12.96, 12.96, 13.00, 13.00, 13.00, 13.00, 13.00, 13.00, 13.00, 13.00, // 40-49%
// // 50-59% (单节3.25V~3.26V → 四节13.00V~13.04V)
// 13.00, 13.00, 13.00, 13.00, 13.00, 13.04, 13.04, 13.04, 13.04, 13.04, // 50-59%
// // 60-69% (单节3.26V~3.27V → 四节13.04V~13.08V)
// 13.04, 13.04, 13.04, 13.04, 13.04, 13.04, 13.08, 13.08, 13.08, 13.08, // 60-69%
// // 70-79% (单节3.28V~3.31V → 四节13.12V~13.24V)
// 13.12, 13.12, 13.12, 13.16, 13.16, 13.16, 13.20, 13.20, 13.24, 13.24, // 70-79%
// // 80-89% (单节3.32V~3.45V → 四节13.28V~13.80V)
// 13.28, 13.28, 13.32, 13.36, 13.40, 13.44, 13.52, 13.60, 13.68, 13.80, // 80-89%
// // 90-100% (单节3.48V~3.65V → 四节13.92V~14.60V)
// 13.92, 14.00, 14.08, 14.16, 14.24, 14.32, 14.40, 14.48, 14.52, 14.56, // 90-99%
// 14.60 // 100%
// };
/**
* SOC-OCV (SOC步长1%)
* 11.2V (0%) ~ 14.6V (100%)
*
* 1.
* 2. V
*/
const float ocv_table_4s[21] = {
// 0-9% (单节2.80V~3.16V → 四节11.20V~12.64V)
12.00, 12.64, // 0-9%
// 10-19% (单节3.18V~3.21V → 四节12.72V~12.84V)
12.80, 12.84, // 10-19%
// 20-29% (单节3.22V~3.23V → 四节12.88V~12.92V)
12.88, 12.92, // 20-29%
// 30-39% (单节3.23V~3.24V → 四节12.92V~12.96V)
12.93, 12.96, // 30-39%
// 40-49% (单节3.24V~3.25V → 四节12.96V~13.00V)
12.98, 13.00, // 40-49%
// 50-59% (单节3.25V~3.26V → 四节13.00V~13.04V)
13.02, 13.04, // 50-59%
// 60-69% (单节3.26V~3.27V → 四节13.04V~13.08V)
13.05, 13.08, // 60-69%
// 70-79% (单节3.28V~3.31V → 四节13.12V~13.24V)
13.16, 13.24, // 70-79%
// 80-89% (单节3.32V~3.45V → 四节13.28V~13.80V)
13.40, 13.80, // 80-89%
// 90-100% (单节3.48V~3.65V → 四节13.92V~14.60V)
13.92, 14.24, // 90-99%
14.60 // 100%
};
/**
* @brief SOC在数组中的位置
* @param
* @retval soc*100
*/
int find_soc(float voltage)
{
// static volatile int soc = 0;
// for(soc = 0; soc <= 100; soc++) {
for(int soc = 0; soc <= 100; soc++) {
if(ocv_table_4s[soc] >= voltage) {
return soc * 5;
}
}
return 100;
}

View File

@ -15,6 +15,7 @@
#include "bl_usart.h" #include "bl_usart.h"
#include "SOE.h" #include "SOE.h"
#include <stdio.h> #include <stdio.h>
@ -46,13 +47,13 @@ static STR_TimeSliceOffset m_startControl;
static void Task_startControl(void); static void Task_startControl(void);
/* 软启动 */ /* 软启动 */
#define softStart_reloadVal 10 /* 任务执行间隔 */ #define softStart_reloadVal 1 /* 任务执行间隔 */
#define softStart_offset 0 /* 任务执行偏移量 */ #define softStart_offset 0 /* 任务执行偏移量 */
static STR_TimeSliceOffset m_softStart; static STR_TimeSliceOffset m_softStart;
static void Task_softStart(void); static void Task_softStart(void);
/* 回路阻抗检测 */ /* 回路阻抗检测 */
#define impedanceCalculation_reloadVal 100 /* 任务执行间隔 */ #define impedanceCalculation_reloadVal 20 /* 任务执行间隔 */
#define impedanceCalculation_offset 0 /* 任务执行偏移量 */ #define impedanceCalculation_offset 0 /* 任务执行偏移量 */
static STR_TimeSliceOffset m_impedanceCalculation; static STR_TimeSliceOffset m_impedanceCalculation;
static void Task_impedanceCalculation(void); static void Task_impedanceCalculation(void);
@ -95,12 +96,6 @@ void Task_collectOpenCircuitVoltage(void);
static STR_TimeSliceOffset m_shortCircuitProtection; static STR_TimeSliceOffset m_shortCircuitProtection;
static void Task_shortCircuitProtection(void); static void Task_shortCircuitProtection(void);
/* 反向充电短路保护 */
#define EXCHGSCProtection_reloadVal 1000 /* 任务执行间隔 */
#define EXCHGSCProtection_offset 0 /* 任务执行偏移量 */
static STR_TimeSliceOffset m_EXCHGSCProtection;
static void Task_EXCHGSCProtection(void);
/* 过载保护 */ /* 过载保护 */
#define excessiveLoad_reloadVal 1000 /* 任务执行间隔 */ #define excessiveLoad_reloadVal 1000 /* 任务执行间隔 */
#define excessiveLoad_offset 0 /* 任务执行偏移量 */ #define excessiveLoad_offset 0 /* 任务执行偏移量 */
@ -139,7 +134,7 @@ STR_TimeSliceOffset m_uart;
void Task_uart(void); void Task_uart(void);
/* 将记录下来的时间存入flash中 */ /* 将记录下来的时间存入flash中 */
#define SOE_reloadVal 1000 /* 任务执行间隔 */ #define SOE_reloadVal 3000 /* 任务执行间隔 */
#define SOE_offset 100 /* 任务执行偏移量 */ #define SOE_offset 100 /* 任务执行偏移量 */
STR_TimeSliceOffset m_SOE; STR_TimeSliceOffset m_SOE;
void Task_SOE(void); void Task_SOE(void);
@ -216,9 +211,9 @@ void Task_wdi(void)
debug_printf("MPPT_Mode:%d \n", getMPPT_Mode()); debug_printf("MPPT_Mode:%d \n", getMPPT_Mode());
debug_printf("loopImpedance:%f \n", getLoopImpedance()); debug_printf("loopImpedance:%f \n", getLoopImpedance());
debug_printf("DutyRatio:%f \n", getDutyRatio()); debug_printf("DutyRatio:%f \n", getDutyRatio());
// debug_printf("OUT_VOLT_IN:%f \n", get_OUT_VOLT_IN()); debug_printf("OUT_VOLT_IN:%f \n", get_OUT_VOLT_IN());
debug_printf("HAL_GetTick:%d \n", HAL_GetTick()); debug_printf("HAL_GetTick:%d \n", HAL_GetTick());
debug_printf("getExChargeCurr:%f \n", getExChargeCurr());
// char buf[100]; // char buf[100];
// sprintf(buf, "chargCurrent:%f \n", getChargCurrent()); // sprintf(buf, "chargCurrent:%f \n", getChargCurrent());
@ -269,20 +264,17 @@ void Task_wdi(void)
/* 每天复位一次复位前将电量信息写入flash中 */ /* 每天复位一次复位前将电量信息写入flash中 */
static uint32_t temp = 60 * 60 * 24; static uint32_t temp = 60 * 60 * 24;
// static uint32_t temp = 60 * 30;
if (!(--temp)) { if (!(--temp)) {
temp = 0; temp = 0;
// float tempF; float tempF;
// tempF = getTotalElectricityConsumption(); tempF = getTotalElectricityConsumption();
// savetotalElectricityConsumption(&tempF); savetotalElectricityConsumption(&tempF);
// tempF = getTotalChargCapacity(); tempF = getTotalChargCapacity();
// savetotalChargCapacity(&tempF); savetotalChargCapacity(&tempF);
// timeInfo time; timeInfo time;
// time = getLastTime(); time = getLastTime();
// saveTime(&time); saveTime(&time);
// NVIC_SystemReset(); NVIC_SystemReset();
resetCheckImpedanceState();
temp = 60 * 60 * 24;
} }
} }
@ -297,7 +289,6 @@ void Task_refreshJudgeData(void)
/* 获取数据 */ /* 获取数据 */
setInputVoltage(); setInputVoltage();
setHighSideMosTemperature(); setHighSideMosTemperature();
setExChargeCurr();
// static float tempOutV; // static float tempOutV;
// tempOutV = get_OUT_VOLT_IN(); // tempOutV = get_OUT_VOLT_IN();
@ -311,7 +302,7 @@ void Task_refreshJudgeData(void)
/* 有电池太阳能输出功率大电池电压低于14V同时回路阻抗未测试或需要重新测试 */ /* 有电池太阳能输出功率大电池电压低于14V同时回路阻抗未测试或需要重新测试 */
if ((getCheckImpedanceState() == FALSE || getLoopImpedance() == 0.0f) if ((getCheckImpedanceState() == FALSE || getLoopImpedance() == 0.0f)
&& (getBatteryState() == TRUE) && (getChargCurrent() > g_cfgParameter.minCheckLoopImpedanceChargCurr) && (getBatteryState() == TRUE) && (getChargCurrent() > g_cfgParameter.maxChargCurr)
&& (getOutputVoltage() > 9) && (getSolarInCircuitVoltage() > 14) && (getOutputVoltage() > 9) && (getSolarInCircuitVoltage() > 14)
&& (getBatteryVoltage() < 14)) { && (getBatteryVoltage() < 14)) {
TimeSliceOffset_Register(&m_impedanceCalculation, Task_impedanceCalculation TimeSliceOffset_Register(&m_impedanceCalculation, Task_impedanceCalculation
@ -339,30 +330,6 @@ void Task_refreshJudgeData(void)
stopChargWork(); stopChargWork();
insertEventsOrderRecord(stopTemperature); insertEventsOrderRecord(stopTemperature);
} }
/* 反向充电电流检测 */
if (getExChargeCurr() > g_cfgParameter.reverseChargProtectionCurr) {
setPowerOutput(FALSE);
insertEventsOrderRecord(InputProtection);
}
/* 充电输入电压过高 */
if (getSolarInCircuitVoltage() >= g_cfgParameter.maxOpenSolarOutputCircuitV) {
// log_info("getSolarInCircuitVoltage : %f", getSolarInCircuitVoltage());
// log_info("g_cfgParameter.maxOpenSolarOutputCircuitV : %f", g_cfgParameter.maxOpenSolarOutputCircuitV);
TimeSliceOffset_Unregister(&m_startControl);
m_startControl.runFlag = 0;
stopChargWork();
insertEventsOrderRecord(overInputVolt);
}
static uint8_t num = 0;
if (20 == num++) {
num = 0;
setSOC();
}
} }
/** /**
@ -376,19 +343,13 @@ void Task_refreshJudgeData(void)
*/ */
void Task_startControl(void) void Task_startControl(void)
{ {
static uint8_t numStart = 0;
if (g_cfgParameter.checkCanStartTime > numStart++) {
return;
}
numStart = 0;
/* 是否达到启动条件 */ /* 是否达到启动条件 */
if (getSolarInCircuitVoltage() > g_cfgParameter.startSolarOpenCircuitV if (getSolarInCircuitVoltage() > g_cfgParameter.startSolarOpenCircuitV
&& getSolarInCircuitVoltage() < g_cfgParameter.maxOpenSolarOutputCircuitV) { && getSolarInCircuitVoltage() < g_cfgParameter.maxOpenSolarOutputCircuitV) {
TimeSliceOffset_Unregister(&m_startControl); TimeSliceOffset_Unregister(&m_startControl);
m_startControl.runFlag = 0; m_startControl.runFlag = 0;
/* 判断有无电池 */ /* 判断有无电池 */
if (getOutputVoltage() > 11.0f) { if (getOutputVoltage() > 11.0f) {
setBatteryState(TRUE); setBatteryState(TRUE);
@ -398,16 +359,12 @@ void Task_startControl(void)
/* 启动软起动任务 */ /* 启动软起动任务 */
TimeSliceOffset_Register(&m_softStart, Task_softStart, softStart_reloadVal, softStart_offset); TimeSliceOffset_Register(&m_softStart, Task_softStart, softStart_reloadVal, softStart_offset);
// if (getBatteryState() == TRUE) {
// setMPPT_Mode(MPPT);
// } else {
// setMPPT_Mode(floatCharg);
// }
// setChargControlFlag(TRUE);
// EN_PWMOUT_Eable();
} }
if (getSolarInCircuitVoltage() >= g_cfgParameter.maxOpenSolarOutputCircuitV) {
insertEventsOrderRecord(overInputVolt);
}
} }
/** /**
* @brief * @brief
@ -428,59 +385,22 @@ void beginStartControlTask(void)
*/ */
void Task_softStart(void) void Task_softStart(void)
{ {
// static uint16_t num = 0;
// static float dutyRatio = 0;
// num++;
// if (num < 5) {
// set_pwmDutyRatio(0.1f);
// EN_PWMOUT_Eable();
// }
// else if (num > 70 || dutyRatio > 0.7f) {
// TimeSliceOffset_Unregister(&m_softStart);
// m_softStart.runFlag = 0;
// dutyRatio = 0;
// num = 0;
// setDutyRatio(0.75f);
// if (getBatteryState() == TRUE) {
// setMPPT_Mode(MPPT);
// } else {
// setMPPT_Mode(floatCharg);
// }
// setChargControlFlag(TRUE);
// }
// else {
// setDutyRatio(getDutyRatio() + 0.01f);
// }
static uint16_t num = 0; static uint16_t num = 0;
// static float dutyRatio = 0; static float dutyRatio = 0;
num++; num++;
if (num < 5) { if (num < 5) {
set_pwmDutyRatio(0.1f);
EN_PWMOUT_Eable(); EN_PWMOUT_Eable();
//最小占空比斩波
setDutyRatio(0.0001f);
} }
else if (num > 80) { else if (num > 70 || dutyRatio > 0.75f) {
TimeSliceOffset_Unregister(&m_softStart); TimeSliceOffset_Unregister(&m_softStart);
m_softStart.runFlag = 0; m_softStart.runFlag = 0;
dutyRatio = 0;
num = 0; num = 0;
setDutyRatio(0.75f);
// debug_printf("getSolarInCircuitVoltage : %f", getSolarInCircuitVoltage());
//电压过低时不启动
if (getSolarInCircuitVoltage() < 18.5f) {
TimeSliceOffset_Register(&m_startControl, Task_startControl, startControl_reloadVal, startControl_offset);
setDutyRatioToZero();
return;
}
if (getBatteryState() == TRUE) { if (getBatteryState() == TRUE) {
setMPPT_Mode(MPPT); setMPPT_Mode(MPPT);
@ -490,9 +410,9 @@ void Task_softStart(void)
setChargControlFlag(TRUE); setChargControlFlag(TRUE);
} }
// else { else {
// setDutyRatio(0.01f); setDutyRatio(getDutyRatio() + 0.01f);
// } }
} }
/** /**
* @brief * @brief
@ -552,7 +472,7 @@ void Task_impedanceCalculation(void)
// } // }
/* 判断回路阻抗是否合理 */ /* 判断回路阻抗是否合理 */
if (setLoopImpedance(tempLoopImpedance) == TRUE) { if (setLoopImpedance(tempLoopImpedance) == TRUE) {
saveLoopImpedance(&tempLoopImpedance); saveLoopImpedance();
setCheckImpedanceState(); setCheckImpedanceState();
} }
@ -568,93 +488,52 @@ void Task_impedanceCalculation(void)
*/ */
void Task_collectOpenCircuitVoltage(void) void Task_collectOpenCircuitVoltage(void)
{ {
// /* 用于无充电控制时获取开路电压 */ /* 用于无充电控制时获取开路电压 */
// static uint32_t collectOpenCircuitVoltageNoNUM = 0; static uint32_t collectOpenCircuitVoltageNoNUM = 0;
// /* 用于有充电控制时获取开路电压 */ /* 用于有充电控制时获取开路电压 */
// static uint8_t collectOpenCircuitVoltageYesNUM = 0; static uint8_t collectOpenCircuitVoltageYesNUM = 0;
/* 用于有充电控制时当标志位 */ /* 用于有充电控制时当标志位 */
static BOOL collectOpenCircuitVoltageYesFlag = 0; static BOOL collectOpenCircuitVoltageYesFlag = 0;
static uint32_t collectOpenCircuitVoltageNUM = 0;
collectOpenCircuitVoltageNUM++; /* 未进行充电时3S采集一次开路电压 */
if (FALSE == getChargControlFlag()) {
if (2 <= collectOpenCircuitVoltageNoNUM++) {
setSolarOpenCircuitVoltage();
collectOpenCircuitVoltageNoNUM = 0;
}
collectOpenCircuitVoltageYesNUM = 0;
if (collectOpenCircuitVoltageYesFlag == TRUE) {
setSolarOpenCircuitVoltage();
beginChargWork();
collectOpenCircuitVoltageYesFlag = FALSE;
}
}
collectOpenCircuitVoltageYesNUM++;
/* 到达开路电压检测时间 */ /* 到达开路电压检测时间 */
if (collectOpenCircuitVoltageNUM == g_cfgParameter.collectOpenCircuitVoltageTime) { if (collectOpenCircuitVoltageYesNUM == g_cfgParameter.collectOpenCircuitVoltageTime) {
// if (collectOpenCircuitVoltageNUM == 180) {
/* 有电池才进行开路电压检测 */ /* 有电池才进行开路电压检测 */
if (!getBatteryState()) { if (getBatteryState()) {
collectOpenCircuitVoltageNUM = 0;
return;
}
collectOpenCircuitVoltageYesFlag = TRUE; collectOpenCircuitVoltageYesFlag = TRUE;
stopChargWork(); stopChargWork();
/* 设置延时为1000-500ms */ /* 设置延时为1000-500ms */
m_collectOpenCircuitVoltage.count = 500; m_collectOpenCircuitVoltage.count = 500;
} }
collectOpenCircuitVoltageYesNUM = 0;
}
/* 检测开路电压 */ /* 检测开路电压 */
if (collectOpenCircuitVoltageNUM == g_cfgParameter.collectOpenCircuitVoltageTime + 1) { if (collectOpenCircuitVoltageYesNUM == g_cfgParameter.collectOpenCircuitVoltageTime + 1) {
// if (collectOpenCircuitVoltageNUM == 181) {
/* 有电池才进行开路电压检测 */ /* 有电池才进行开路电压检测 */
if (!getBatteryState()) { if (getBatteryState()) {
collectOpenCircuitVoltageNUM = 0;
return;
}
setSolarOpenCircuitVoltage(); setSolarOpenCircuitVoltage();
beginChargWork(); beginChargWork();
collectOpenCircuitVoltageYesFlag = FALSE; collectOpenCircuitVoltageYesFlag = FALSE;
// beginSoftStartTask();
collectOpenCircuitVoltageNUM = 0;
// setChargControlFlag(TRUE);
}
/* 未进行充电时3S采集一次开路电压 */
if (FALSE == getChargControlFlag() && !collectOpenCircuitVoltageYesFlag) {
if (2 <= collectOpenCircuitVoltageNUM) {
setSolarOpenCircuitVoltage();
collectOpenCircuitVoltageNUM = 0;
return;
} }
} }
// /* 未进行充电时3S采集一次开路电压 */
// if (FALSE == getChargControlFlag()) {
// if (2 <= collectOpenCircuitVoltageNoNUM++) {
// setSolarOpenCircuitVoltage();
// collectOpenCircuitVoltageNoNUM = 0;
// }
// collectOpenCircuitVoltageYesNUM = 0;
// if (collectOpenCircuitVoltageYesFlag == TRUE) {
// setSolarOpenCircuitVoltage();
// beginChargWork();
// collectOpenCircuitVoltageYesFlag = FALSE;
// }
// }
// collectOpenCircuitVoltageYesNUM++;
// /* 到达开路电压检测时间 */
// if (collectOpenCircuitVoltageYesNUM == g_cfgParameter.collectOpenCircuitVoltageTime) {
// /* 有电池才进行开路电压检测 */
// if (getBatteryState()) {
// collectOpenCircuitVoltageYesFlag = TRUE;
// stopChargWork();
// /* 设置延时为1000-500ms */
// m_collectOpenCircuitVoltage.count = 500;
// }
// }
// /* 检测开路电压 */
// if (collectOpenCircuitVoltageYesNUM == g_cfgParameter.collectOpenCircuitVoltageTime + 1) {
// /* 有电池才进行开路电压检测 */
// if (getBatteryState()) {
// setSolarOpenCircuitVoltage();
// beginChargWork();
// collectOpenCircuitVoltageYesFlag = FALSE;
// }
// collectOpenCircuitVoltageYesNUM = 0;
// }
} }
// /** // /**
@ -748,14 +627,6 @@ void Task_shortCircuitProtection(void)
static uint8_t num = 0; static uint8_t num = 0;
num++; num++;
/* 设定输出短路保护时间 */
if (num == 2) {
// setPowerOutput(FALSE);
setPowerOutput(TRUE);
}
/* 设定输出短路保护时间 */ /* 设定输出短路保护时间 */
if (num == g_cfgParameter.shortCircuitJudgmentDelay) { if (num == g_cfgParameter.shortCircuitJudgmentDelay) {
num = 0; num = 0;
@ -763,14 +634,14 @@ void Task_shortCircuitProtection(void)
TimeSliceOffset_Unregister(&m_shortCircuitProtection); TimeSliceOffset_Unregister(&m_shortCircuitProtection);
m_shortCircuitProtection.runFlag = 0; m_shortCircuitProtection.runFlag = 0;
// /* 仍然过流,彻底关闭输出 */ /* 仍然过流,彻底关闭输出 */
// if (readOverCurrState() == FALSE) { if (readOverCurrState() == FALSE) {
// setPowerOutput(FALSE); setPowerOutput(FALSE);
// } }
// /* 不过流,则状态位复位 */ /* 不过流,则状态位复位 */
// else { else {
// setShortCircuitFlag(FALSE); setShortCircuitFlag(FALSE);
// } }
} }
} }
@ -796,53 +667,6 @@ void stopShortCircuitProtection(void)
m_shortCircuitProtection.runFlag = 0; m_shortCircuitProtection.runFlag = 0;
} }
/**
* @brief
* @param
* @retval
*/
void Task_EXCHGSCProtection(void)
{
static uint8_t num = 0;
num++;
/* 设定输出短路保护时间 */
if (num == 2) {
// setPowerOutput(FALSE);
setPowerOutput(TRUE);
}
/* 设定输出短路保护时间 */
if (num == g_cfgParameter.shortCircuitJudgmentDelay) {
num = 0;
zeroShortCircuit();
TimeSliceOffset_Unregister(&m_EXCHGSCProtection);
m_EXCHGSCProtection.runFlag = 0;
}
}
/**
* @brief
* @param
* @retval
*/
void startEXCHGSCProtection(void)
{
TimeSliceOffset_Register(&m_EXCHGSCProtection, Task_EXCHGSCProtection
, EXCHGSCProtection_reloadVal, EXCHGSCProtection_offset);
}
/**
* @brief
* @param
* @retval
*/
void stopEXCHGSCProtection(void)
{
TimeSliceOffset_Unregister(&m_EXCHGSCProtection);
m_EXCHGSCProtection.runFlag = 0;
}
/** /**
* @brief * @brief
* @param * @param
@ -891,8 +715,6 @@ void Task_excessiveLoad(void)
/* 关闭输出后开始计时 */ /* 关闭输出后开始计时 */
if (readPOW_OUT_PCON_State() == FALSE) { if (readPOW_OUT_PCON_State() == FALSE) {
numLong++; numLong++;
} else {
numLong = 0;
} }
/* 达到时间就重新尝试输出 */ /* 达到时间就重新尝试输出 */

View File

@ -33,8 +33,5 @@ BOOL readOutputState(void);
extern void WORK_VOLT_Interrupt(void); extern void WORK_VOLT_Interrupt(void);
extern void DSG_PROT_Interrupt(void); extern void DSG_PROT_Interrupt(void);
extern void EXCHG_PROT_Interrupt(void);
#endif #endif

View File

@ -31,7 +31,7 @@ float get_DSG_CURR(void);
float get_PV1_VOLT_IN(void); float get_PV1_VOLT_IN(void);
float get_PV_VOLT_IN1(void); float get_PV_VOLT_IN1(void);
float get_MOSFET_Temper(void); float get_MOSFET_Temper(void);
float get_EXCHG_CURR(void); float get_OUT_VOLT_IN(void);
void adcCaptureFir(); void adcCaptureFir();

View File

@ -9,8 +9,6 @@
void Flash_Init(void); void Flash_Init(void);
void read_Flash(uint8_t* pBuffer,uint32_t ReadAddr,uint16_t NumByteToRead); void read_Flash(uint8_t* pBuffer,uint32_t ReadAddr,uint16_t NumByteToRead);
void write_Flash(uint8_t* pBuffer,uint32_t WriteAddr,uint16_t NumByteToWrite); void write_Flash(uint8_t* pBuffer,uint32_t WriteAddr,uint16_t NumByteToWrite);
void erase_Sector_Flash(uint32_t secpos);
#endif #endif

View File

@ -15,8 +15,7 @@ void FM_GPIO_Init(void)
*/ */
void POW_FF_PCON_Open(void) void POW_FF_PCON_Open(void)
{ {
// HAL_GPIO_WritePin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin, GPIO_PIN_SET); HAL_GPIO_WritePin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin, GPIO_PIN_SET);
HAL_GPIO_WritePin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin, GPIO_PIN_RESET);
} }
/** /**
@ -26,8 +25,7 @@ void POW_FF_PCON_Open(void)
*/ */
void POW_FF_PCON_Close(void) void POW_FF_PCON_Close(void)
{ {
// HAL_GPIO_WritePin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin, GPIO_PIN_RESET);
HAL_GPIO_WritePin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin, GPIO_PIN_SET);
} }
/** /**
@ -181,27 +179,24 @@ BOOL readOverCurrState(void)
BOOL readOnlyPowerOutputState(void) BOOL readOnlyPowerOutputState(void)
{ {
// static volatile GPIO_PinState gpioTemp1, gpioTemp2, gpioTemp3; // static volatile GPIO_PinState gpioTemp1, gpioTemp2, gpioTemp3;
// GPIO_PinState gpioTemp1, gpioTemp2, gpioTemp3; GPIO_PinState gpioTemp1, gpioTemp2, gpioTemp3;
// GPIO_PinState gpioTemp1, gpioTemp2;
// gpioTemp1 = HAL_GPIO_ReadPin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin); gpioTemp1 = HAL_GPIO_ReadPin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin);
// gpioTemp2 = HAL_GPIO_ReadPin(POW_OUT_CON_GPIO_Port, POW_OUT_CON_Pin); gpioTemp2 = HAL_GPIO_ReadPin(POW_OUT_CON_GPIO_Port, POW_OUT_CON_Pin);
// gpioTemp3 = HAL_GPIO_ReadPin(DSG_PROT_GPIO_Port, DSG_PROT_Pin); gpioTemp3 = HAL_GPIO_ReadPin(DSG_PROT_GPIO_Port, DSG_PROT_Pin);
// if (gpioTemp1 == GPIO_PIN_SET if (gpioTemp1 == GPIO_PIN_SET
// && gpioTemp2 == GPIO_PIN_SET && gpioTemp2 == GPIO_PIN_SET
// // && gpioTemp3 == GPIO_PIN_SET) { && gpioTemp3 == GPIO_PIN_SET) {
// ) {
// return TRUE;
// }
if (!HAL_GPIO_ReadPin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin)
&& HAL_GPIO_ReadPin(POW_OUT_CON_GPIO_Port, POW_OUT_CON_Pin)
&& !HAL_GPIO_ReadPin(DSG_PROT_GPIO_Port, DSG_PROT_Pin)
&& !HAL_GPIO_ReadPin(EXCHG_CURR_GPIO_Port, EXCHG_CURR_Pin)) {
return TRUE; return TRUE;
} }
// if (HAL_GPIO_ReadPin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin)
// && HAL_GPIO_ReadPin(POW_OUT_CON_GPIO_Port, POW_OUT_CON_Pin)
// && HAL_GPIO_ReadPin(DSG_PROT_GPIO_Port, DSG_PROT_Pin)) {
// return TRUE;
// }
return FALSE; return FALSE;
} }
@ -231,13 +226,9 @@ void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin)
WORK_VOLT_Interrupt(); WORK_VOLT_Interrupt();
} }
else if (GPIO_Pin == DSG_PROT_Pin) { // else if (GPIO_Pin == DSG_PROT_Pin) {
DSG_PROT_Interrupt(); // DSG_PROT_Interrupt();
} // }
else if (GPIO_Pin == EXCHG_PROT_Pin) {
EXCHG_PROT_Interrupt();
}
} }

View File

@ -22,9 +22,9 @@ void FM_RTC_Init(void)
void setRTC_Time(timeInfo *time) void setRTC_Time(timeInfo *time)
{ {
/* 日期结构体 */ /* 日期结构体 */
RTC_DateTypeDef setData; static RTC_DateTypeDef setData;
/* 时间结构体 */ /* 时间结构体 */
RTC_TimeTypeDef setTime; static RTC_TimeTypeDef setTime;
setData.Year = time->year; setData.Year = time->year;
setData.Month = time->month; setData.Month = time->month;
@ -46,9 +46,9 @@ void setRTC_Time(timeInfo *time)
void getRTC_Time(timeInfo *time) void getRTC_Time(timeInfo *time)
{ {
/* 日期结构体 */ /* 日期结构体 */
RTC_DateTypeDef getData; static RTC_DateTypeDef getData;
/* 时间结构体 */ /* 时间结构体 */
RTC_TimeTypeDef getTime; static RTC_TimeTypeDef getTime;
HAL_RTC_GetDate(&hrtc, &getData, RTC_FORMAT_BIN); HAL_RTC_GetDate(&hrtc, &getData, RTC_FORMAT_BIN);
HAL_RTC_GetTime(&hrtc, &getTime, RTC_FORMAT_BIN); HAL_RTC_GetTime(&hrtc, &getTime, RTC_FORMAT_BIN);

View File

@ -111,11 +111,11 @@ adcCapture CHG_CURR_capture = {0};
/* 电流电压采集转换的 */ /* 电流电压采集转换的 */
static float P_CHG_CURR = 0; static float P_CHG_CURR = 0;
static float P_EXCHG_CURR = 0; static float P_PV_VOLT_OUT = 0;
static float P_DSG_CURR = 0; static float P_DSG_CURR = 0;
static float P_PV1_VOLT_IN = 0; static float P_PV1_VOLT_IN = 0;
static float P_PV_VOLT_IN1 = 0; static float P_PV_VOLT_IN1 = 0;
static float P_PV_VOLT_OUT = 0; static float P_OUT_VOLT_IN = 0;
/* 2.5为adc的电压4095是2^adc的位数 - 1 */ /* 2.5为adc的电压4095是2^adc的位数 - 1 */
// const float32_t Proportion = 2.5 / 4095; // const float32_t Proportion = 2.5 / 4095;
@ -134,11 +134,11 @@ const float32_t Proportion = 3.0 / 4095.0;
// 0.178709805, 0.3671073616, 0.3671073616, 0.178709805 // 0.178709805, 0.3671073616, 0.3671073616, 0.178709805
// }; // };
// /* matlab生成的3阶滤波器系数,乘比例使和接近为1 */ /* matlab生成的3阶滤波器系数,乘比例使和接近为1 */
// const int firLen = 4; const int firLen = 4;
// const float32_t firLP[4] = { const float32_t firLP[4] = {
// 0.163708486, 0.336291513, 0.336291513, 0.163708486 0.163708486, 0.336291513, 0.336291513, 0.163708486
// }; };
// void captureFirInit(void); // void captureFirInit(void);
@ -196,8 +196,8 @@ void proportionalInt(int mode)
P_PV1_VOLT_IN = ((47.0 + 4.7) / 4.7) * Proportion; P_PV1_VOLT_IN = ((47.0 + 4.7) / 4.7) * Proportion;
/* 系统电源电压比例 */ /* 系统电源电压比例 */
P_PV_VOLT_IN1 = ((47.0 + 4.7) / 4.7) * Proportion; P_PV_VOLT_IN1 = ((47.0 + 4.7) / 4.7) * Proportion;
/* 外部输入电流比例 */ /* 输出外部电压比例 */
P_EXCHG_CURR = P_DSG_CURR; P_OUT_VOLT_IN = ((47.0 + 4.7) / 4.7) * Proportion;
} }
/* 电源盒外还有网关功能 */ /* 电源盒外还有网关功能 */
@ -212,8 +212,8 @@ void proportionalInt(int mode)
P_PV1_VOLT_IN = ((47.0 + 4.7) / 4.7) * Proportion; P_PV1_VOLT_IN = ((47.0 + 4.7) / 4.7) * Proportion;
/* 系统电源电压比例 */ /* 系统电源电压比例 */
P_PV_VOLT_IN1 = ((47 + 4.7) / 4.7) * Proportion; P_PV_VOLT_IN1 = ((47 + 4.7) / 4.7) * Proportion;
/* 外部输入电流比例 */ /* 输出外部电压比例 */
P_EXCHG_CURR = P_DSG_CURR; P_OUT_VOLT_IN = ((47.0 + 4.7) / 4.7) * Proportion;
} }
@ -435,32 +435,31 @@ float get_MOSFET_Temper(void)
* @param * @param
* @retval V * @retval V
*/ */
float get_EXCHG_CURR(void) float get_OUT_VOLT_IN(void)
{ {
float I; float V;
uint16_t I_ADC; uint16_t V_ADC;
// static uint16_t V_ADCTemp = (uint16_t)(0.52f / 3.0f * 4095); static uint16_t V_ADCTemp = (uint16_t)(0.52f / 3.0f * 4095);
// static uint16_t V_ADCTemp = (uint16_t)(0.17f / 3.0f * 4095); // static uint16_t V_ADCTemp = (uint16_t)(0.17f / 3.0f * 4095);
I_ADC = ADC2_Capture(EXCHG_CURR_CHANNEL); V_ADC = ADC2_Capture(OUT_VOLT_IN_CHANNEL);
I = (float)(I_ADC) * P_EXCHG_CURR;
// if (HAL_GPIO_ReadPin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin)) { if (HAL_GPIO_ReadPin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin)) {
// V = (float)(V_ADC) * P_OUT_VOLT_IN; V = (float)(V_ADC) * P_OUT_VOLT_IN;
// } else { } else {
// if (V_ADC > V_ADCTemp) { if (V_ADC > V_ADCTemp) {
// V = (float)(V_ADC - V_ADCTemp) * P_OUT_VOLT_IN; V = (float)(V_ADC - V_ADCTemp) * P_OUT_VOLT_IN;
// } }
// V = (float)(V_ADC) * P_OUT_VOLT_IN; V = (float)(V_ADC) * P_OUT_VOLT_IN;
// } }
#ifdef enable_Printf_VI #ifdef enable_Printf_VI
debug("\n OUT_VOLT_IN ADC : %d \n", V_ADC); debug("\n OUT_VOLT_IN ADC : %d \n", V_ADC);
debug(" OUT_VOLT_IN V : %f \n", V); debug(" OUT_VOLT_IN V : %f \n", V);
#endif #endif
return I; return V;
} }
@ -510,26 +509,17 @@ void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef *hdma)
// HAL_GPIO_TogglePin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin); // HAL_GPIO_TogglePin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin);
// HAL_GPIO_WritePin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin,GPIO_PIN_RESET); // HAL_GPIO_WritePin(POW_FF_CON_GPIO_Port, POW_FF_CON_Pin,GPIO_PIN_RESET);
// WORK_VOLT_capture.outData = (float32_t)(adcBuff[0] + adcBuff[4] + adcBuff[8] + adcBuff[12] + adcBuff[16]
// + adcBuff[20] + adcBuff[24] + adcBuff[28] + adcBuff[32] + adcBuff[36]) / indata16_size;
// DSG_CURR_capture.outData = (float32_t)(adcBuff[1] + adcBuff[5] + adcBuff[9] + adcBuff[13] + adcBuff[17]
// + adcBuff[21] + adcBuff[25] + adcBuff[29] + adcBuff[33] + adcBuff[37]) / indata16_size;
// CHG_CURR_capture.outData = (float32_t)(adcBuff[2] + adcBuff[6] + adcBuff[10] + adcBuff[14] + adcBuff[18]
// + adcBuff[22] + adcBuff[26] + adcBuff[30] + adcBuff[34] + adcBuff[38]) / indata16_size;
// PV_VOLT_IN_capture.outData = (float32_t)(adcBuff[3] + adcBuff[7] + adcBuff[11] + adcBuff[15] + adcBuff[19]
// + adcBuff[23] + adcBuff[27] + adcBuff[31] + adcBuff[35] + adcBuff[39]) / indata16_size;
WORK_VOLT_capture.outData = (adcBuff[0] + adcBuff[4] + adcBuff[8] + adcBuff[12] + adcBuff[16]
WORK_VOLT_capture.outData = (float32_t)(adcBuff[0] + adcBuff[4] + adcBuff[8] + adcBuff[12] + adcBuff[16]
+ adcBuff[20] + adcBuff[24] + adcBuff[28] + adcBuff[32] + adcBuff[36]) / indata16_size; + adcBuff[20] + adcBuff[24] + adcBuff[28] + adcBuff[32] + adcBuff[36]) / indata16_size;
DSG_CURR_capture.outData = (adcBuff[1] + adcBuff[5] + adcBuff[9] + adcBuff[13] + adcBuff[17] DSG_CURR_capture.outData = (float32_t)(adcBuff[1] + adcBuff[5] + adcBuff[9] + adcBuff[13] + adcBuff[17]
+ adcBuff[21] + adcBuff[25] + adcBuff[29] + adcBuff[33] + adcBuff[37]) / indata16_size; + adcBuff[21] + adcBuff[25] + adcBuff[29] + adcBuff[33] + adcBuff[37]) / indata16_size;
CHG_CURR_capture.outData = (adcBuff[2] + adcBuff[6] + adcBuff[10] + adcBuff[14] + adcBuff[18] CHG_CURR_capture.outData = (float32_t)(adcBuff[2] + adcBuff[6] + adcBuff[10] + adcBuff[14] + adcBuff[18]
+ adcBuff[22] + adcBuff[26] + adcBuff[30] + adcBuff[34] + adcBuff[38]) / indata16_size; + adcBuff[22] + adcBuff[26] + adcBuff[30] + adcBuff[34] + adcBuff[38]) / indata16_size;
PV_VOLT_IN_capture.outData = (adcBuff[3] + adcBuff[7] + adcBuff[11] + adcBuff[15] + adcBuff[19] PV_VOLT_IN_capture.outData = (float32_t)(adcBuff[3] + adcBuff[7] + adcBuff[11] + adcBuff[15] + adcBuff[19]
+ adcBuff[23] + adcBuff[27] + adcBuff[31] + adcBuff[35] + adcBuff[39]) / indata16_size; + adcBuff[23] + adcBuff[27] + adcBuff[31] + adcBuff[35] + adcBuff[39]) / indata16_size;
// WORK_VOLT_capture.outData = ;
setSoftShortCircuit(DSG_CURR_capture.outData); setSoftShortCircuit(DSG_CURR_capture.outData);
chargControl(); chargControl();

View File

@ -95,13 +95,3 @@ void write_Flash(uint8_t* pBuffer,uint32_t WriteAddr,uint16_t NumByteToWrite)
// Flash_Write_MorePage(pBuffer, WriteAddr, NumByteToWrite); // Flash_Write_MorePage(pBuffer, WriteAddr, NumByteToWrite);
// W25Q128_Write(pBuffer, WriteAddr, NumByteToWrite); // W25Q128_Write(pBuffer, WriteAddr, NumByteToWrite);
} }
/**
* @brief flash中secpos扇区的数据
*
*/
void erase_Sector_Flash(uint32_t secpos)
{
W25QXX_Erase_Sector(secpos);
}

View File

@ -7,9 +7,9 @@ device_handle g_gw485_uart2_handle;
device_handle g_bat485_uart3_handle; device_handle g_bat485_uart3_handle;
device_handle g_debug_uart4_handle; device_handle g_debug_uart4_handle;
static uint8_t Debug_in_buff[10]; static uint8_t Debug_in_buff[200];
static uint8_t Gw485_in_buff[300]; static uint8_t Gw485_in_buff[200];
static uint8_t Bat485_in_buff[300]; static uint8_t Bat485_in_buff[200];
uint8_t rx_gw485_buf[1]; uint8_t rx_gw485_buf[1];
uint8_t rx_bat485_buf[1]; uint8_t rx_bat485_buf[1];

View File

@ -10,7 +10,7 @@
#include "stm32g431xx.h" #include "stm32g431xx.h"
#define SYS_VOLT_IN_CHANNEL ADC_CHANNEL_1 #define SYS_VOLT_IN_CHANNEL ADC_CHANNEL_1
#define EXCHG_CURR_CHANNEL ADC_CHANNEL_6 #define OUT_VOLT_IN_CHANNEL ADC_CHANNEL_9
#define MOSFET_Temper_CHANNEL ADC_CHANNEL_15 #define MOSFET_Temper_CHANNEL ADC_CHANNEL_15
void HD_adc_Init(void); void HD_adc_Init(void);

View File

@ -2,60 +2,7 @@
void HD_GPIO_Init(void) void HD_GPIO_Init(void)
{ {
// // MX_GPIO_Init(); // MX_GPIO_Init();
// GPIO_InitTypeDef GPIO_InitStruct = {0};
// /* GPIO Ports Clock Enable */
// __HAL_RCC_GPIOC_CLK_ENABLE();
// __HAL_RCC_GPIOF_CLK_ENABLE();
// __HAL_RCC_GPIOA_CLK_ENABLE();
// __HAL_RCC_GPIOB_CLK_ENABLE();
// /*Configure GPIO pin Output Level */
// // HAL_GPIO_WritePin(FLASH_CS_GPIO_Port, FLASH_CS_Pin, GPIO_PIN_RESET);
// /*Configure GPIO pin Output Level */
// HAL_GPIO_WritePin(GPIOB, WDI_INPUT_Pin|RUN_LED_Pin|POW_FF_CON_Pin|POW_OUT_CON_Pin, GPIO_PIN_RESET);
// /*Configure GPIO pin Output Level */
// HAL_GPIO_WritePin(GPIOA, EN_PWMOUT_Pin|FFMOS_CON_Pin, GPIO_PIN_SET);
// /*Configure GPIO pin : DSG_PROT_Pin */
// GPIO_InitStruct.Pin = DSG_PROT_Pin;
// GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING;
// GPIO_InitStruct.Pull = GPIO_PULLUP;
// HAL_GPIO_Init(DSG_PROT_GPIO_Port, &GPIO_InitStruct);
// /*Configure GPIO pins : FLASH_CS_Pin EN_PWMOUT_Pin FFMOS_CON_Pin */
// // GPIO_InitStruct.Pin = FLASH_CS_Pin|EN_PWMOUT_Pin|FFMOS_CON_Pin;
// // GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
// // GPIO_InitStruct.Pull = GPIO_NOPULL;
// // GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
// // HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
// GPIO_InitStruct.Pin = EN_PWMOUT_Pin|FFMOS_CON_Pin;
// GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
// GPIO_InitStruct.Pull = GPIO_NOPULL;
// GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
// HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
// /*Configure GPIO pins : WDI_INPUT_Pin RUN_LED_Pin POW_FF_CON_Pin POW_OUT_CON_Pin */
// GPIO_InitStruct.Pin = WDI_INPUT_Pin|RUN_LED_Pin|POW_FF_CON_Pin|POW_OUT_CON_Pin;
// GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
// GPIO_InitStruct.Pull = GPIO_NOPULL;
// GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
// HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
// /*Configure GPIO pin : WORK_VOLT_INT_Pin */
// GPIO_InitStruct.Pin = WORK_VOLT_INT_Pin;
// GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
// GPIO_InitStruct.Pull = GPIO_PULLDOWN;
// HAL_GPIO_Init(WORK_VOLT_INT_GPIO_Port, &GPIO_InitStruct);
// /* EXTI interrupt init*/
// HAL_NVIC_SetPriority(EXTI15_10_IRQn, 5, 0);
// HAL_NVIC_EnableIRQ(EXTI15_10_IRQn);
GPIO_InitTypeDef GPIO_InitStruct = {0}; GPIO_InitTypeDef GPIO_InitStruct = {0};
@ -66,7 +13,7 @@ void HD_GPIO_Init(void)
__HAL_RCC_GPIOB_CLK_ENABLE(); __HAL_RCC_GPIOB_CLK_ENABLE();
/*Configure GPIO pin Output Level */ /*Configure GPIO pin Output Level */
// HAL_GPIO_WritePin(FLASH_CS_GPIO_Port, FLASH_CS_Pin, GPIO_PIN_RESET); // HAL_GPIO_WritePin(FLASH_CS_GPIO_Port, FLASH_CS_Pin, GPIO_PIN_RESET);
/*Configure GPIO pin Output Level */ /*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOB, WDI_INPUT_Pin|RUN_LED_Pin|POW_FF_CON_Pin|POW_OUT_CON_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(GPIOB, WDI_INPUT_Pin|RUN_LED_Pin|POW_FF_CON_Pin|POW_OUT_CON_Pin, GPIO_PIN_RESET);
@ -76,16 +23,21 @@ void HD_GPIO_Init(void)
/*Configure GPIO pin : DSG_PROT_Pin */ /*Configure GPIO pin : DSG_PROT_Pin */
GPIO_InitStruct.Pin = DSG_PROT_Pin; GPIO_InitStruct.Pin = DSG_PROT_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING; GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING;
GPIO_InitStruct.Pull = GPIO_PULLDOWN; GPIO_InitStruct.Pull = GPIO_PULLUP;
HAL_GPIO_Init(DSG_PROT_GPIO_Port, &GPIO_InitStruct); HAL_GPIO_Init(DSG_PROT_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pin : FLASH_CS_Pin */ /*Configure GPIO pins : FLASH_CS_Pin EN_PWMOUT_Pin FFMOS_CON_Pin */
// GPIO_InitStruct.Pin = FLASH_CS_Pin; // GPIO_InitStruct.Pin = FLASH_CS_Pin|EN_PWMOUT_Pin|FFMOS_CON_Pin;
// GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; // GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
// GPIO_InitStruct.Pull = GPIO_NOPULL; // GPIO_InitStruct.Pull = GPIO_NOPULL;
// GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; // GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
// HAL_GPIO_Init(FLASH_CS_GPIO_Port, &GPIO_InitStruct); // HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
GPIO_InitStruct.Pin = EN_PWMOUT_Pin|FFMOS_CON_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/*Configure GPIO pins : WDI_INPUT_Pin RUN_LED_Pin POW_FF_CON_Pin POW_OUT_CON_Pin */ /*Configure GPIO pins : WDI_INPUT_Pin RUN_LED_Pin POW_FF_CON_Pin POW_OUT_CON_Pin */
GPIO_InitStruct.Pin = WDI_INPUT_Pin|RUN_LED_Pin|POW_FF_CON_Pin|POW_OUT_CON_Pin; GPIO_InitStruct.Pin = WDI_INPUT_Pin|RUN_LED_Pin|POW_FF_CON_Pin|POW_OUT_CON_Pin;
@ -94,29 +46,13 @@ void HD_GPIO_Init(void)
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/*Configure GPIO pins : EN_PWMOUT_Pin FFMOS_CON_Pin */
GPIO_InitStruct.Pin = EN_PWMOUT_Pin|FFMOS_CON_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/*Configure GPIO pin : WORK_VOLT_INT_Pin */ /*Configure GPIO pin : WORK_VOLT_INT_Pin */
GPIO_InitStruct.Pin = WORK_VOLT_INT_Pin; GPIO_InitStruct.Pin = WORK_VOLT_INT_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING; GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
GPIO_InitStruct.Pull = GPIO_PULLDOWN; GPIO_InitStruct.Pull = GPIO_PULLDOWN;
HAL_GPIO_Init(WORK_VOLT_INT_GPIO_Port, &GPIO_InitStruct); HAL_GPIO_Init(WORK_VOLT_INT_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pin : EXCHG_PROT_Pin */
GPIO_InitStruct.Pin = EXCHG_PROT_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
HAL_GPIO_Init(EXCHG_PROT_GPIO_Port, &GPIO_InitStruct);
/* EXTI interrupt init*/ /* EXTI interrupt init*/
HAL_NVIC_SetPriority(EXTI9_5_IRQn, 0, 0); HAL_NVIC_SetPriority(EXTI15_10_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(EXTI9_5_IRQn);
HAL_NVIC_SetPriority(EXTI15_10_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(EXTI15_10_IRQn); HAL_NVIC_EnableIRQ(EXTI15_10_IRQn);
} }

View File

@ -18,29 +18,6 @@ void HD_RTC_Init(void)
{ {
Error_Handler(); Error_Handler();
} }
// RTC_TimeTypeDef sTime = {0};
// RTC_DateTypeDef sDate = {0};
// sTime.Hours = 0;
// sTime.Minutes = 0;
// sTime.Seconds = 0;
// sTime.SubSeconds = 0;
// sTime.DayLightSaving = RTC_DAYLIGHTSAVING_NONE;
// sTime.StoreOperation = RTC_STOREOPERATION_RESET;
// if (HAL_RTC_SetTime(&hrtc, &sTime, RTC_FORMAT_BIN) != HAL_OK)
// {
// Error_Handler();
// }
// sDate.WeekDay = RTC_WEEKDAY_MONDAY;
// sDate.Month = RTC_MONTH_JANUARY;
// sDate.Date = 1;
// sDate.Year = 0;
// if (HAL_RTC_SetDate(&hrtc, &sDate, RTC_FORMAT_BIN) != HAL_OK)
// {
// Error_Handler();
// }
} }

View File

@ -60,12 +60,12 @@ void Error_Handler(void);
#define DSG_PROT_Pin GPIO_PIN_13 #define DSG_PROT_Pin GPIO_PIN_13
#define DSG_PROT_GPIO_Port GPIOC #define DSG_PROT_GPIO_Port GPIOC
#define DSG_PROT_EXTI_IRQn EXTI15_10_IRQn #define DSG_PROT_EXTI_IRQn EXTI15_10_IRQn
#define EXCHG_CURR_Pin GPIO_PIN_0
#define EXCHG_CURR_GPIO_Port GPIOC
#define WORK_VOLT_Pin GPIO_PIN_1 #define WORK_VOLT_Pin GPIO_PIN_1
#define WORK_VOLT_GPIO_Port GPIOC #define WORK_VOLT_GPIO_Port GPIOC
#define DSG_CURR_Pin GPIO_PIN_2 #define DSG_CURR_Pin GPIO_PIN_2
#define DSG_CURR_GPIO_Port GPIOC #define DSG_CURR_GPIO_Port GPIOC
#define OUT_VOLT_IN_Pin GPIO_PIN_3
#define OUT_VOLT_IN_GPIO_Port GPIOC
#define SYS_VOLT_IN_Pin GPIO_PIN_0 #define SYS_VOLT_IN_Pin GPIO_PIN_0
#define SYS_VOLT_IN_GPIO_Port GPIOA #define SYS_VOLT_IN_GPIO_Port GPIOA
#define GW485_RDE_Pin GPIO_PIN_1 #define GW485_RDE_Pin GPIO_PIN_1
@ -109,9 +109,6 @@ void Error_Handler(void);
#define DEBUG_TX_GPIO_Port GPIOC #define DEBUG_TX_GPIO_Port GPIOC
#define DEBUG_RX_Pin GPIO_PIN_11 #define DEBUG_RX_Pin GPIO_PIN_11
#define DEBUG_RX_GPIO_Port GPIOC #define DEBUG_RX_GPIO_Port GPIOC
#define EXCHG_PROT_Pin GPIO_PIN_5
#define EXCHG_PROT_GPIO_Port GPIOB
#define EXCHG_PROT_EXTI_IRQn EXTI9_5_IRQn
#define RUN_LED_Pin GPIO_PIN_6 #define RUN_LED_Pin GPIO_PIN_6
#define RUN_LED_GPIO_Port GPIOB #define RUN_LED_GPIO_Port GPIOB
#define POW_FF_CON_Pin GPIO_PIN_7 #define POW_FF_CON_Pin GPIO_PIN_7

View File

@ -56,7 +56,6 @@ void DebugMon_Handler(void);
void PendSV_Handler(void); void PendSV_Handler(void);
void SysTick_Handler(void); void SysTick_Handler(void);
void DMA1_Channel1_IRQHandler(void); void DMA1_Channel1_IRQHandler(void);
void EXTI9_5_IRQHandler(void);
void TIM1_BRK_TIM15_IRQHandler(void); void TIM1_BRK_TIM15_IRQHandler(void);
void TIM1_UP_TIM16_IRQHandler(void); void TIM1_UP_TIM16_IRQHandler(void);
void USART2_IRQHandler(void); void USART2_IRQHandler(void);

View File

@ -267,14 +267,14 @@ void HAL_ADC_MspInit(ADC_HandleTypeDef* adcHandle)
__HAL_RCC_GPIOA_CLK_ENABLE(); __HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE(); __HAL_RCC_GPIOB_CLK_ENABLE();
/**ADC2 GPIO Configuration /**ADC2 GPIO Configuration
PC0 ------> ADC2_IN6 PC3 ------> ADC2_IN9
PA0 ------> ADC2_IN1 PA0 ------> ADC2_IN1
PB15 ------> ADC2_IN15 PB15 ------> ADC2_IN15
*/ */
GPIO_InitStruct.Pin = EXCHG_CURR_Pin; GPIO_InitStruct.Pin = OUT_VOLT_IN_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(EXCHG_CURR_GPIO_Port, &GPIO_InitStruct); HAL_GPIO_Init(OUT_VOLT_IN_GPIO_Port, &GPIO_InitStruct);
GPIO_InitStruct.Pin = SYS_VOLT_IN_Pin; GPIO_InitStruct.Pin = SYS_VOLT_IN_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
@ -334,11 +334,11 @@ void HAL_ADC_MspDeInit(ADC_HandleTypeDef* adcHandle)
} }
/**ADC2 GPIO Configuration /**ADC2 GPIO Configuration
PC0 ------> ADC2_IN6 PC3 ------> ADC2_IN9
PA0 ------> ADC2_IN1 PA0 ------> ADC2_IN1
PB15 ------> ADC2_IN15 PB15 ------> ADC2_IN15
*/ */
HAL_GPIO_DeInit(EXCHG_CURR_GPIO_Port, EXCHG_CURR_Pin); HAL_GPIO_DeInit(OUT_VOLT_IN_GPIO_Port, OUT_VOLT_IN_Pin);
HAL_GPIO_DeInit(SYS_VOLT_IN_GPIO_Port, SYS_VOLT_IN_Pin); HAL_GPIO_DeInit(SYS_VOLT_IN_GPIO_Port, SYS_VOLT_IN_Pin);

View File

@ -61,8 +61,8 @@ void MX_GPIO_Init(void)
/*Configure GPIO pin : DSG_PROT_Pin */ /*Configure GPIO pin : DSG_PROT_Pin */
GPIO_InitStruct.Pin = DSG_PROT_Pin; GPIO_InitStruct.Pin = DSG_PROT_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING; GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING;
GPIO_InitStruct.Pull = GPIO_PULLDOWN; GPIO_InitStruct.Pull = GPIO_PULLUP;
HAL_GPIO_Init(DSG_PROT_GPIO_Port, &GPIO_InitStruct); HAL_GPIO_Init(DSG_PROT_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pin : FLASH_CS_Pin */ /*Configure GPIO pin : FLASH_CS_Pin */
@ -92,16 +92,7 @@ void MX_GPIO_Init(void)
GPIO_InitStruct.Pull = GPIO_PULLDOWN; GPIO_InitStruct.Pull = GPIO_PULLDOWN;
HAL_GPIO_Init(WORK_VOLT_INT_GPIO_Port, &GPIO_InitStruct); HAL_GPIO_Init(WORK_VOLT_INT_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pin : EXCHG_PROT_Pin */
GPIO_InitStruct.Pin = EXCHG_PROT_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
HAL_GPIO_Init(EXCHG_PROT_GPIO_Port, &GPIO_InitStruct);
/* EXTI interrupt init*/ /* EXTI interrupt init*/
HAL_NVIC_SetPriority(EXTI9_5_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(EXTI9_5_IRQn);
HAL_NVIC_SetPriority(EXTI15_10_IRQn, 0, 0); HAL_NVIC_SetPriority(EXTI15_10_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(EXTI15_10_IRQn); HAL_NVIC_EnableIRQ(EXTI15_10_IRQn);

View File

@ -111,8 +111,6 @@ int main(void)
// MX_SPI1_Init(); // MX_SPI1_Init();
/* USER CODE BEGIN 2 */ /* USER CODE BEGIN 2 */
// while (1) {
// };
start(); start();
@ -152,13 +150,14 @@ void SystemClock_Config(void)
/** Initializes the RCC Oscillators according to the specified parameters /** Initializes the RCC Oscillators according to the specified parameters
* in the RCC_OscInitTypeDef structure. * in the RCC_OscInitTypeDef structure.
*/ */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE|RCC_OSCILLATORTYPE_LSE; RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI|RCC_OSCILLATORTYPE_LSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.LSEState = RCC_LSE_ON; RCC_OscInitStruct.LSEState = RCC_LSE_ON;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
RCC_OscInitStruct.PLL.PLLM = RCC_PLLM_DIV1; RCC_OscInitStruct.PLL.PLLM = RCC_PLLM_DIV1;
RCC_OscInitStruct.PLL.PLLN = 18; RCC_OscInitStruct.PLL.PLLN = 9;
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2; RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2;
RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2; RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2;

View File

@ -89,7 +89,7 @@ void NMI_Handler(void)
void HardFault_Handler(void) void HardFault_Handler(void)
{ {
/* USER CODE BEGIN HardFault_IRQn 0 */ /* USER CODE BEGIN HardFault_IRQn 0 */
NVIC_SystemReset();
/* USER CODE END HardFault_IRQn 0 */ /* USER CODE END HardFault_IRQn 0 */
while (1) while (1)
{ {
@ -217,20 +217,6 @@ void DMA1_Channel1_IRQHandler(void)
/* USER CODE END DMA1_Channel1_IRQn 1 */ /* USER CODE END DMA1_Channel1_IRQn 1 */
} }
/**
* @brief This function handles EXTI line[9:5] interrupts.
*/
void EXTI9_5_IRQHandler(void)
{
/* USER CODE BEGIN EXTI9_5_IRQn 0 */
/* USER CODE END EXTI9_5_IRQn 0 */
HAL_GPIO_EXTI_IRQHandler(EXCHG_PROT_Pin);
/* USER CODE BEGIN EXTI9_5_IRQn 1 */
/* USER CODE END EXTI9_5_IRQn 1 */
}
/** /**
* @brief This function handles TIM1 break interrupt and TIM15 global interrupt. * @brief This function handles TIM1 break interrupt and TIM15 global interrupt.
*/ */

View File

@ -47,7 +47,7 @@ void MX_TIM3_Init(void)
htim3.Instance = TIM3; htim3.Instance = TIM3;
htim3.Init.Prescaler = 0; htim3.Init.Prescaler = 0;
htim3.Init.CounterMode = TIM_COUNTERMODE_UP; htim3.Init.CounterMode = TIM_COUNTERMODE_UP;
htim3.Init.Period = 719; htim3.Init.Period = 720;
htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_PWM_Init(&htim3) != HAL_OK) if (HAL_TIM_PWM_Init(&htim3) != HAL_OK)

View File

@ -189,7 +189,7 @@
<option> <option>
<name>TrustZoneModes</name> <name>TrustZoneModes</name>
<version>0</version> <version>0</version>
<state>0</state> <state>1</state>
</option> </option>
<option> <option>
<name>OGAarch64Abi</name> <name>OGAarch64Abi</name>
@ -1096,12 +1096,12 @@
<settings> <settings>
<name>BUILDACTION</name> <name>BUILDACTION</name>
<archiveVersion>2</archiveVersion> <archiveVersion>2</archiveVersion>
<data /> <data></data>
</settings> </settings>
<settings> <settings>
<name>Coder</name> <name>Coder</name>
<archiveVersion>0</archiveVersion> <archiveVersion>0</archiveVersion>
<data /> <data></data>
</settings> </settings>
</configuration> </configuration>
<group> <group>
@ -1141,9 +1141,6 @@
<file> <file>
<name>$PROJ_DIR$\..\APP\businessLogic\Src\parameter.c</name> <name>$PROJ_DIR$\..\APP\businessLogic\Src\parameter.c</name>
</file> </file>
<file>
<name>$PROJ_DIR$\..\APP\businessLogic\Src\soc.c</name>
</file>
<file> <file>
<name>$PROJ_DIR$\..\APP\businessLogic\Src\SOE.c</name> <name>$PROJ_DIR$\..\APP\businessLogic\Src\SOE.c</name>
</file> </file>
@ -1210,16 +1207,16 @@
<group> <group>
<name>Core</name> <name>Core</name>
<file> <file>
<name>$PROJ_DIR$\..\Core\Src\adc.c</name> <name>$PROJ_DIR$\..\Core\Src\main.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\Core\Src\dma.c</name>
</file> </file>
<file> <file>
<name>$PROJ_DIR$\..\Core\Src\gpio.c</name> <name>$PROJ_DIR$\..\Core\Src\gpio.c</name>
</file> </file>
<file> <file>
<name>$PROJ_DIR$\..\Core\Src\main.c</name> <name>$PROJ_DIR$\..\Core\Src\adc.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\Core\Src\dma.c</name>
</file> </file>
<file> <file>
<name>$PROJ_DIR$\..\Core\Src\rtc.c</name> <name>$PROJ_DIR$\..\Core\Src\rtc.c</name>
@ -1228,16 +1225,16 @@
<name>$PROJ_DIR$\..\Core\Src\spi.c</name> <name>$PROJ_DIR$\..\Core\Src\spi.c</name>
</file> </file>
<file> <file>
<name>$PROJ_DIR$\..\Core\Src\stm32g4xx_hal_msp.c</name> <name>$PROJ_DIR$\..\Core\Src\tim.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\Core\Src\usart.c</name>
</file> </file>
<file> <file>
<name>$PROJ_DIR$\..\Core\Src\stm32g4xx_it.c</name> <name>$PROJ_DIR$\..\Core\Src\stm32g4xx_it.c</name>
</file> </file>
<file> <file>
<name>$PROJ_DIR$\..\Core\Src\tim.c</name> <name>$PROJ_DIR$\..\Core\Src\stm32g4xx_hal_msp.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\Core\Src\usart.c</name>
</file> </file>
</group> </group>
</group> </group>
@ -1252,9 +1249,6 @@
</group> </group>
<group> <group>
<name>STM32G4xx_HAL_Driver</name> <name>STM32G4xx_HAL_Driver</name>
<file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal.c</name>
</file>
<file> <file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_adc.c</name> <name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_adc.c</name>
</file> </file>
@ -1262,16 +1256,16 @@
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_adc_ex.c</name> <name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_adc_ex.c</name>
</file> </file>
<file> <file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_cortex.c</name> <name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_ll_adc.c</name>
</file> </file>
<file> <file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma.c</name> <name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal.c</name>
</file> </file>
<file> <file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma_ex.c</name> <name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc.c</name>
</file> </file>
<file> <file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_exti.c</name> <name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc_ex.c</name>
</file> </file>
<file> <file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash.c</name> <name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_flash.c</name>
@ -1285,6 +1279,15 @@
<file> <file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_gpio.c</name> <name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_gpio.c</name>
</file> </file>
<file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_exti.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_dma_ex.c</name>
</file>
<file> <file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr.c</name> <name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr.c</name>
</file> </file>
@ -1292,10 +1295,7 @@
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr_ex.c</name> <name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_pwr_ex.c</name>
</file> </file>
<file> <file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc.c</name> <name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_cortex.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rcc_ex.c</name>
</file> </file>
<file> <file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rtc.c</name> <name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_rtc.c</name>
@ -1321,21 +1321,6 @@
<file> <file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_uart_ex.c</name> <name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_hal_uart_ex.c</name>
</file> </file>
<file>
<name>$PROJ_DIR$\..\Drivers\STM32G4xx_HAL_Driver\Src\stm32g4xx_ll_adc.c</name>
</file>
</group>
</group>
<group>
<name>Middlewares</name>
<group>
<name>Library</name>
<group>
<name>DSP Library/DSP Library</name>
<file>
<name>$PROJ_DIR$\..\Middlewares\ST\ARM\DSP\Lib\iar_cortexM4lf_math.a</name>
</file>
</group>
</group> </group>
</group> </group>
<group> <group>
@ -1347,4 +1332,17 @@
<name>$PROJ_DIR$\..\tools\TimeSliceOffset\timeSliceOffset.c</name> <name>$PROJ_DIR$\..\tools\TimeSliceOffset\timeSliceOffset.c</name>
</file> </file>
</group> </group>
<group>
<name>Middlewares</name>
<group>
<name>Library</name>
<group>
<name>DSP Library/DSP Library</name>
<file>
<name>$PROJ_DIR$/../Middlewares/ST/ARM/DSP/Lib/iar_cortexM4lf_math.a</name>
</file>
</group>
</group>
</group>
</project> </project>

View File

@ -1463,9 +1463,6 @@
<file> <file>
<name>$PROJ_DIR$\..\APP\businessLogic\Src\parameter.c</name> <name>$PROJ_DIR$\..\APP\businessLogic\Src\parameter.c</name>
</file> </file>
<file>
<name>$PROJ_DIR$\..\APP\businessLogic\Src\soc.c</name>
</file>
<file> <file>
<name>$PROJ_DIR$\..\APP\businessLogic\Src\SOE.c</name> <name>$PROJ_DIR$\..\APP\businessLogic\Src\SOE.c</name>
</file> </file>

View File

@ -109,26 +109,25 @@ Mcu.Pin28=PA14
Mcu.Pin29=PC10 Mcu.Pin29=PC10
Mcu.Pin3=PF0-OSC_IN Mcu.Pin3=PF0-OSC_IN
Mcu.Pin30=PC11 Mcu.Pin30=PC11
Mcu.Pin31=PB5 Mcu.Pin31=PB6
Mcu.Pin32=PB6 Mcu.Pin32=PB7
Mcu.Pin33=PB7 Mcu.Pin33=PB9
Mcu.Pin34=PB9 Mcu.Pin34=VP_RTC_VS_RTC_Activate
Mcu.Pin35=VP_RTC_VS_RTC_Activate Mcu.Pin35=VP_RTC_VS_RTC_Calendar
Mcu.Pin36=VP_RTC_VS_RTC_Calendar Mcu.Pin36=VP_SYS_VS_Systick
Mcu.Pin37=VP_SYS_VS_Systick Mcu.Pin37=VP_SYS_VS_DBSignals
Mcu.Pin38=VP_SYS_VS_DBSignals Mcu.Pin38=VP_TIM6_VS_ClockSourceINT
Mcu.Pin39=VP_TIM6_VS_ClockSourceINT Mcu.Pin39=VP_TIM7_VS_ClockSourceINT
Mcu.Pin4=PF1-OSC_OUT Mcu.Pin4=PF1-OSC_OUT
Mcu.Pin40=VP_TIM7_VS_ClockSourceINT Mcu.Pin40=VP_TIM15_VS_ClockSourceINT
Mcu.Pin41=VP_TIM15_VS_ClockSourceINT Mcu.Pin41=VP_TIM16_VS_ClockSourceINT
Mcu.Pin42=VP_TIM16_VS_ClockSourceINT Mcu.Pin42=VP_STMicroelectronics.X-CUBE-ALGOBUILD_VS_DSPOoLibraryJjLibrary_1.4.0_1.4.0
Mcu.Pin43=VP_STMicroelectronics.X-CUBE-ALGOBUILD_VS_DSPOoLibraryJjLibrary_1.4.0_1.4.0 Mcu.Pin5=PC1
Mcu.Pin5=PC0 Mcu.Pin6=PC2
Mcu.Pin6=PC1 Mcu.Pin7=PC3
Mcu.Pin7=PC2
Mcu.Pin8=PA0 Mcu.Pin8=PA0
Mcu.Pin9=PA1 Mcu.Pin9=PA1
Mcu.PinsNb=44 Mcu.PinsNb=43
Mcu.ThirdParty0=STMicroelectronics.X-CUBE-ALGOBUILD.1.4.0 Mcu.ThirdParty0=STMicroelectronics.X-CUBE-ALGOBUILD.1.4.0
Mcu.ThirdPartyNb=1 Mcu.ThirdPartyNb=1
Mcu.UserConstants= Mcu.UserConstants=
@ -139,7 +138,6 @@ NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.DMA1_Channel1_IRQn=true\:4\:0\:true\:false\:true\:false\:true\:true NVIC.DMA1_Channel1_IRQn=true\:4\:0\:true\:false\:true\:false\:true\:true
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.EXTI15_10_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true NVIC.EXTI15_10_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
NVIC.EXTI9_5_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
NVIC.ForceEnableDMAVector=true NVIC.ForceEnableDMAVector=true
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
@ -248,12 +246,6 @@ PB15.GPIOParameters=GPIO_Label
PB15.GPIO_Label=MOSFET_Temper PB15.GPIO_Label=MOSFET_Temper
PB15.Mode=IN15-Single-Ended PB15.Mode=IN15-Single-Ended
PB15.Signal=ADC2_IN15 PB15.Signal=ADC2_IN15
PB5.GPIOParameters=GPIO_PuPd,GPIO_Label,GPIO_ModeDefaultEXTI
PB5.GPIO_Label=EXCHG_PROT
PB5.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_RISING
PB5.GPIO_PuPd=GPIO_PULLDOWN
PB5.Locked=true
PB5.Signal=GPXTI5
PB6.GPIOParameters=GPIO_Label PB6.GPIOParameters=GPIO_Label
PB6.GPIO_Label=RUN_LED PB6.GPIO_Label=RUN_LED
PB6.Locked=true PB6.Locked=true
@ -266,11 +258,6 @@ PB9.GPIOParameters=GPIO_Label
PB9.GPIO_Label=POW_OUT_CON PB9.GPIO_Label=POW_OUT_CON
PB9.Locked=true PB9.Locked=true
PB9.Signal=GPIO_Output PB9.Signal=GPIO_Output
PC0.GPIOParameters=GPIO_Label
PC0.GPIO_Label=EXCHG_CURR
PC0.Locked=true
PC0.Mode=IN6-Single-Ended
PC0.Signal=ADC2_IN6
PC1.GPIOParameters=GPIO_Label PC1.GPIOParameters=GPIO_Label
PC1.GPIO_Label=WORK_VOLT PC1.GPIO_Label=WORK_VOLT
PC1.Locked=true PC1.Locked=true
@ -286,8 +273,8 @@ PC11.Mode=Asynchronous
PC11.Signal=UART4_RX PC11.Signal=UART4_RX
PC13.GPIOParameters=GPIO_PuPd,GPIO_Label,GPIO_ModeDefaultEXTI PC13.GPIOParameters=GPIO_PuPd,GPIO_Label,GPIO_ModeDefaultEXTI
PC13.GPIO_Label=DSG_PROT PC13.GPIO_Label=DSG_PROT
PC13.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_RISING PC13.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_FALLING
PC13.GPIO_PuPd=GPIO_PULLDOWN PC13.GPIO_PuPd=GPIO_PULLUP
PC13.Locked=true PC13.Locked=true
PC13.Signal=GPXTI13 PC13.Signal=GPXTI13
PC14-OSC32_IN.Mode=LSE-External-Oscillator PC14-OSC32_IN.Mode=LSE-External-Oscillator
@ -298,6 +285,11 @@ PC2.GPIOParameters=GPIO_Label
PC2.GPIO_Label=DSG_CURR PC2.GPIO_Label=DSG_CURR
PC2.Mode=IN8-Single-Ended PC2.Mode=IN8-Single-Ended
PC2.Signal=ADC1_IN8 PC2.Signal=ADC1_IN8
PC3.GPIOParameters=GPIO_Label
PC3.GPIO_Label=OUT_VOLT_IN
PC3.Locked=true
PC3.Mode=IN9-Single-Ended
PC3.Signal=ADC2_IN9
PC9.GPIOParameters=GPIO_Speed,GPIO_Label PC9.GPIOParameters=GPIO_Speed,GPIO_Label
PC9.GPIO_Label=CHG_CONH PC9.GPIO_Label=CHG_CONH
PC9.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH PC9.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
@ -338,7 +330,7 @@ ProjectManager.ToolChainLocation=
ProjectManager.UAScriptAfterPath= ProjectManager.UAScriptAfterPath=
ProjectManager.UAScriptBeforePath= ProjectManager.UAScriptBeforePath=
ProjectManager.UnderRoot=false ProjectManager.UnderRoot=false
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-MX_ADC1_Init-ADC1-false-HAL-true,5-MX_ADC2_Init-ADC2-false-HAL-true,6-MX_TIM3_Init-TIM3-false-HAL-true,7-MX_TIM6_Init-TIM6-false-HAL-true,8-MX_UART4_Init-UART4-false-HAL-true,9-MX_USART2_UART_Init-USART2-false-HAL-true,10-MX_USART3_UART_Init-USART3-false-HAL-true,11-MX_TIM7_Init-TIM7-false-HAL-true,12-MX_TIM16_Init-TIM16-false-HAL-true,13-MX_TIM15_Init-TIM15-false-HAL-true,14-MX_RTC_Init-RTC-false-HAL-true,15-MX_SPI1_Init-SPI1-false-HAL-true ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-MX_ADC1_Init-ADC1-false-HAL-true,5-MX_ADC2_Init-ADC2-false-HAL-true,6-MX_TIM3_Init-TIM3-false-HAL-true,7-MX_TIM6_Init-TIM6-false-HAL-true,8-MX_UART4_Init-UART4-false-HAL-true,9-MX_USART2_UART_Init-USART2-false-HAL-true,10-MX_USART3_UART_Init-USART3-false-HAL-true,11-MX_TIM7_Init-TIM7-false-HAL-true,12-MX_TIM16_Init-TIM16-false-HAL-true,13-MX_TIM15_Init-TIM15-false-HAL-true,14-MX_RTC_Init-RTC-false-HAL-true
RCC.ADC12Freq_Value=72000000 RCC.ADC12Freq_Value=72000000
RCC.AHBFreq_Value=72000000 RCC.AHBFreq_Value=72000000
RCC.APB1Freq_Value=72000000 RCC.APB1Freq_Value=72000000
@ -359,17 +351,16 @@ RCC.I2C1Freq_Value=72000000
RCC.I2C2Freq_Value=72000000 RCC.I2C2Freq_Value=72000000
RCC.I2C3Freq_Value=72000000 RCC.I2C3Freq_Value=72000000
RCC.I2SFreq_Value=72000000 RCC.I2SFreq_Value=72000000
RCC.IPParameters=ADC12Freq_Value,AHBFreq_Value,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CRSFreq_Value,CortexFreq_Value,EXTERNAL_CLOCK_VALUE,FCLKCortexFreq_Value,FDCANFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI48_VALUE,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2C3Freq_Value,I2SFreq_Value,LPTIM1Freq_Value,LPUART1Freq_Value,LSCOPinFreq_Value,LSI_VALUE,MCO1PinFreq_Value,PLLN,PLLPoutputFreq_Value,PLLQoutputFreq_Value,PLLRCLKFreq_Value,PLLSourceVirtual,PWRFreq_Value,RNGFreq_Value,RTCClockSelection,RTCFreq_Value,SAI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,UART4Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value RCC.IPParameters=ADC12Freq_Value,AHBFreq_Value,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CRSFreq_Value,CortexFreq_Value,EXTERNAL_CLOCK_VALUE,FCLKCortexFreq_Value,FDCANFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI48_VALUE,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2C3Freq_Value,I2SFreq_Value,LPTIM1Freq_Value,LPUART1Freq_Value,LSCOPinFreq_Value,LSI_VALUE,MCO1PinFreq_Value,PLLN,PLLPoutputFreq_Value,PLLQoutputFreq_Value,PLLRCLKFreq_Value,PWRFreq_Value,RNGFreq_Value,RTCClockSelection,RTCFreq_Value,SAI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,UART4Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value
RCC.LPTIM1Freq_Value=72000000 RCC.LPTIM1Freq_Value=72000000
RCC.LPUART1Freq_Value=72000000 RCC.LPUART1Freq_Value=72000000
RCC.LSCOPinFreq_Value=32000 RCC.LSCOPinFreq_Value=32000
RCC.LSI_VALUE=32000 RCC.LSI_VALUE=32000
RCC.MCO1PinFreq_Value=16000000 RCC.MCO1PinFreq_Value=16000000
RCC.PLLN=18 RCC.PLLN=9
RCC.PLLPoutputFreq_Value=72000000 RCC.PLLPoutputFreq_Value=72000000
RCC.PLLQoutputFreq_Value=72000000 RCC.PLLQoutputFreq_Value=72000000
RCC.PLLRCLKFreq_Value=72000000 RCC.PLLRCLKFreq_Value=72000000
RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE
RCC.PWRFreq_Value=72000000 RCC.PWRFreq_Value=72000000
RCC.RNGFreq_Value=72000000 RCC.RNGFreq_Value=72000000
RCC.RTCClockSelection=RCC_RTCCLKSOURCE_LSE RCC.RTCClockSelection=RCC_RTCCLKSOURCE_LSE
@ -382,7 +373,7 @@ RCC.USART1Freq_Value=72000000
RCC.USART2Freq_Value=72000000 RCC.USART2Freq_Value=72000000
RCC.USART3Freq_Value=72000000 RCC.USART3Freq_Value=72000000
RCC.USBFreq_Value=72000000 RCC.USBFreq_Value=72000000
RCC.VCOInputFreq_Value=8000000 RCC.VCOInputFreq_Value=16000000
RCC.VCOOutputFreq_Value=144000000 RCC.VCOOutputFreq_Value=144000000
RTC.Format=RTC_FORMAT_BIN RTC.Format=RTC_FORMAT_BIN
RTC.IPParameters=Format,WeekDay RTC.IPParameters=Format,WeekDay
@ -391,8 +382,6 @@ SH.GPXTI12.0=GPIO_EXTI12
SH.GPXTI12.ConfNb=1 SH.GPXTI12.ConfNb=1
SH.GPXTI13.0=GPIO_EXTI13 SH.GPXTI13.0=GPIO_EXTI13
SH.GPXTI13.ConfNb=1 SH.GPXTI13.ConfNb=1
SH.GPXTI5.0=GPIO_EXTI5
SH.GPXTI5.ConfNb=1
SH.S_TIM3_CH4.0=TIM3_CH4,PWM Generation4 CH4 SH.S_TIM3_CH4.0=TIM3_CH4,PWM Generation4 CH4
SH.S_TIM3_CH4.ConfNb=1 SH.S_TIM3_CH4.ConfNb=1
SPI1.CalculateBaudRate=36.0 MBits/s SPI1.CalculateBaudRate=36.0 MBits/s
@ -413,7 +402,7 @@ TIM16.PeriodNoDither=999
TIM16.Prescaler=71 TIM16.Prescaler=71
TIM3.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4 TIM3.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
TIM3.IPParameters=PeriodNoDither,Channel-PWM Generation4 CH4 TIM3.IPParameters=PeriodNoDither,Channel-PWM Generation4 CH4
TIM3.PeriodNoDither=719 TIM3.PeriodNoDither=720
TIM6.IPParameters=Prescaler,PeriodNoDither,TIM_MasterOutputTrigger TIM6.IPParameters=Prescaler,PeriodNoDither,TIM_MasterOutputTrigger
TIM6.PeriodNoDither=9 TIM6.PeriodNoDither=9
TIM6.Prescaler=71 TIM6.Prescaler=71

View File

@ -54,6 +54,7 @@ typedef enum {
runLedOtherMode = 2, //其他模式 runLedOtherMode = 2, //其他模式
}runLedMode; }runLedMode;
/* 顺序事件记录 */ /* 顺序事件记录 */
typedef enum { typedef enum {
firstStageProtection = 1, //第一段保护,短路保护 firstStageProtection = 1, //第一段保护,短路保护
@ -64,11 +65,6 @@ typedef enum {
stopTemperature, //停止温度保护 stopTemperature, //停止温度保护
overchargCurr, //充电电流过大保护 overchargCurr, //充电电流过大保护
overInputVolt, //太阳能输入电压过大保护 overInputVolt, //太阳能输入电压过大保护
hardwareShortCircuitProtection, //硬件短路保护
hardwareInputProtection, //硬件防反输入保护
InputProtection, //软件防反输入保护
startEvent, //启动
abnormalControl, //异常控制
}eventsOrderRecordMode; }eventsOrderRecordMode;