Compare commits

...

9 Commits

Author SHA1 Message Date
Kilian Bracher de184afd03
add -Wextra compiler flag
(but turn off warnings for unused parameters)
2023-12-04 18:43:17 +01:00
Jasper Blanckenburg cef05f52bc Multiply SoC delta by 100 to get percentage 2023-08-01 14:39:01 +02:00
Jasper Blanckenburg 61155995f8 Disregard AMS slave status error flag 2023-07-12 19:34:30 +02:00
Jasper Blanckenburg 410597c0f3 Correctly unmarshal slave error kinds 2023-07-03 14:20:24 +02:00
Jasper Blanckenburg 12422071a5 Read IMD M pin 2023-07-03 14:20:13 +02:00
Jasper Blanckenburg 554eecfc94 Configure IOC for Master v2 2023-07-02 13:27:50 +02:00
Jasper Blanckenburg 208d84e2a5 Integrate current
The current counter on the shunt can't be activated for some reason.
2023-06-25 16:41:29 +02:00
Jasper Blanckenburg 5dba504e10 Basic SoC estimation 2023-06-25 15:29:08 +02:00
Jasper Blanckenburg 2eb7109416 Revert "Implementation of SoC Prediction"
This reverts commit c4543e7e01.
2023-06-25 15:28:53 +02:00
20 changed files with 1748 additions and 189 deletions

File diff suppressed because one or more lines are too long

36
Core/Inc/imd_monitoring.h Normal file
View File

@ -0,0 +1,36 @@
#ifndef INC_IMD_MONITORING_H
#define INC_IMD_MONITORING_H
#include <stdint.h>
#include "stm32f3xx_hal.h"
typedef enum {
IMD_STATE_UNKNOWN,
IMD_STATE_SHORTCIRCUIT_SUPPLY,
IMD_STATE_SHORTCIRCUIT_GND,
IMD_STATE_NORMAL,
IMD_STATE_UNDERVOLTAGE,
IMD_STATE_SST,
IMD_STATE_DEV_ERROR,
IMD_STATE_GND_FAULT,
} IMDState;
typedef struct {
int ok;
IMDState state;
uint32_t r_iso;
uint32_t freq;
uint32_t duty_cycle;
uint32_t last_high;
} IMDData;
extern IMDData imd_data;
void imd_init(TIM_HandleTypeDef *htim);
void imd_update(void);
#endif // INC_IMD_MONITORING_H

View File

@ -61,6 +61,10 @@ void Error_Handler(void);
#define HV_MISMATCH_ERR_GPIO_Port GPIOA
#define RELAY_MISMATCH_ERR_Pin GPIO_PIN_1
#define RELAY_MISMATCH_ERR_GPIO_Port GPIOA
#define IMD_M_Pin GPIO_PIN_2
#define IMD_M_GPIO_Port GPIOA
#define IMD_OK_Pin GPIO_PIN_3
#define IMD_OK_GPIO_Port GPIOA
#define RELAY_CONNECTION_ERR_Pin GPIO_PIN_4
#define RELAY_CONNECTION_ERR_GPIO_Port GPIOA
#define HV_ACTIVE_Pin GPIO_PIN_5

View File

@ -10,16 +10,17 @@
#define SHUNT_THRESH_OVERTEMP 1000 // 1/10 °C
typedef struct {
int32_t current;
int32_t voltage_bat;
int32_t voltage_veh;
int32_t voltage3;
int32_t current; // mA
int32_t voltage_bat; // mV
int32_t voltage_veh; // mV
int32_t voltage3; // mV
int32_t busbartemp;
int32_t power;
int32_t energy;
int32_t current_counter;
float current_counter; // mAs
uint32_t last_message;
uint32_t last_current_message;
} ShuntData;
extern ShuntData shunt_data;
@ -28,6 +29,4 @@ void shunt_check();
void shunt_handle_can_msg(uint16_t id, const uint8_t *data);
int32_t shunt_getcurrent();
#endif // INC_SHUNT_MONITORING_H

View File

@ -49,6 +49,5 @@ void slaves_check();
void slaves_handle_panic(const uint8_t *data);
void slaves_handle_status(const uint8_t *data);
void slaves_handle_log(const uint8_t *data);
uint16_t slaves_get_minimum_voltage();
#endif // INC_SLAVE_MONITORING_H

View File

@ -3,16 +3,16 @@
#include <stdint.h>
extern uint8_t current_soc;
#define N_MODELPARAMETERS 11
#define BATTERYCAPACITYAs (21000.0*3600) //TODO Check if value is correct Cap in Ah * 3600 (Convert to As)
extern float current_soc;
void soc_init();
void soc_update(int32_t shunt_current);
void soe_update();
void soap_update();
void soc_update();
typedef struct {
uint16_t ocv;
float soc;
} ocv_soc_pair_t;
extern ocv_soc_pair_t OCV_SOC_PAIRS[];
float soc_for_ocv(uint16_t ocv);
#endif // INC_SOC_ESTIMATION_H

View File

@ -57,7 +57,7 @@
/*#define HAL_RNG_MODULE_ENABLED */
/*#define HAL_RTC_MODULE_ENABLED */
/*#define HAL_SPI_MODULE_ENABLED */
/*#define HAL_TIM_MODULE_ENABLED */
#define HAL_TIM_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
/*#define HAL_USART_MODULE_ENABLED */
/*#define HAL_IRDA_MODULE_ENABLED */

View File

@ -56,6 +56,7 @@ void DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
void USB_LP_CAN_RX0_IRQHandler(void);
void TIM1_BRK_TIM15_IRQHandler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */

View File

@ -1,5 +1,6 @@
#include "can.h"
#include "imd_monitoring.h"
#include "main.h"
#include "shunt_monitoring.h"
#include "slave_monitoring.h"
@ -8,6 +9,7 @@
#include "can-halal.h"
#include <math.h>
#include <stdint.h>
void can_init(CAN_HandleTypeDef *handle) {
@ -20,11 +22,17 @@ void can_init(CAN_HandleTypeDef *handle) {
}
HAL_StatusTypeDef can_send_status() {
uint8_t data[6];
uint8_t data[8];
data[0] = ts_state.current_state | (sdc_closed << 7);
data[1] = current_soc;
data[1] = roundf(current_soc);
ftcan_marshal_unsigned(&data[2], min_voltage, 2);
ftcan_marshal_signed(&data[4], max_temp, 2);
data[6] = imd_data.state | (imd_data.ok << 7);
if (imd_data.r_iso < 0xFFF) {
data[7] = imd_data.r_iso >> 4;
} else {
data[7] = 0xFF;
}
return ftcan_transmit(CAN_ID_AMS_STATUS, data, sizeof(data));
}

86
Core/Src/imd_monitoring.c Normal file
View File

@ -0,0 +1,86 @@
#include "imd_monitoring.h"
#include "main.h"
#define FREQ_TIMER 1000 // Hz
#define FREQ_TOLERANCE 1 // Hz
#define FREQ_NORMAL 10 // Hz
#define FREQ_UNDERVOLTAGE 20 // Hz
#define FREQ_SST 30 // Hz
#define FREQ_DEV_ERROR 40 // Hz
#define FREQ_GND_FAULT 50 // Hz
#define RISO_MIN_DUTY_CYCLE 8 // %
#define RISO_MAX 50000 // kOhm
#define PWM_TIMEOUT 200 // ms
IMDData imd_data;
static TIM_HandleTypeDef *htim;
void imd_init(TIM_HandleTypeDef *handle) {
htim = handle;
HAL_TIM_IC_Start_IT(htim, TIM_CHANNEL_1);
HAL_TIM_IC_Start(htim, TIM_CHANNEL_2);
imd_data.state = IMD_STATE_UNKNOWN;
}
void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *handle) {
if (handle != htim || htim->Channel != HAL_TIM_ACTIVE_CHANNEL_1) {
return;
}
uint32_t period = HAL_TIM_ReadCapturedValue(htim, TIM_CHANNEL_1);
if (period == 0) {
// First edge, ignore
return;
}
imd_data.last_high = HAL_GetTick();
imd_data.freq = FREQ_TIMER / period;
uint32_t high_time = HAL_TIM_ReadCapturedValue(htim, TIM_CHANNEL_2);
imd_data.duty_cycle = (100 * high_time) / period;
// Check PWM frequency for state determination
if (imd_data.freq > FREQ_NORMAL - FREQ_TOLERANCE &&
imd_data.freq < FREQ_NORMAL + FREQ_TOLERANCE) {
imd_data.state = IMD_STATE_NORMAL;
} else if (imd_data.freq > FREQ_UNDERVOLTAGE - FREQ_TOLERANCE &&
imd_data.freq < FREQ_UNDERVOLTAGE + FREQ_TOLERANCE) {
imd_data.state = IMD_STATE_UNDERVOLTAGE;
} else if (imd_data.freq > FREQ_SST - FREQ_TOLERANCE &&
imd_data.freq < FREQ_SST + FREQ_TOLERANCE) {
imd_data.state = IMD_STATE_SST;
} else if (imd_data.freq > FREQ_DEV_ERROR - FREQ_TOLERANCE &&
imd_data.freq < FREQ_DEV_ERROR + FREQ_TOLERANCE) {
imd_data.state = IMD_STATE_DEV_ERROR;
} else if (imd_data.freq > FREQ_GND_FAULT - FREQ_TOLERANCE &&
imd_data.freq < FREQ_GND_FAULT + FREQ_TOLERANCE) {
imd_data.state = IMD_STATE_GND_FAULT;
} else {
imd_data.state = IMD_STATE_UNKNOWN;
}
// Calculate R_iso
if (imd_data.state == IMD_STATE_NORMAL ||
imd_data.state == IMD_STATE_UNDERVOLTAGE) {
if (imd_data.duty_cycle < RISO_MIN_DUTY_CYCLE) {
imd_data.r_iso = RISO_MAX;
} else {
imd_data.r_iso = (90 * 1200) / (imd_data.duty_cycle - 5) - 1200;
}
}
}
void imd_update() {
imd_data.ok = HAL_GPIO_ReadPin(IMD_OK_GPIO_Port, IMD_OK_Pin);
if (HAL_GetTick() - imd_data.last_high > PWM_TIMEOUT) {
if (HAL_GPIO_ReadPin(IMD_M_GPIO_Port, IMD_M_Pin) == GPIO_PIN_SET) {
imd_data.state = IMD_STATE_SHORTCIRCUIT_SUPPLY;
} else {
imd_data.state = IMD_STATE_SHORTCIRCUIT_GND;
}
}
}

View File

@ -22,14 +22,15 @@
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "can.h"
#include "soc_estimation.h"
#include "stm32f3xx_hal.h"
#include "stm32f3xx_hal_gpio.h"
#include "imd_monitoring.h"
#include "shunt_monitoring.h"
#include "slave_monitoring.h"
#include "soc_estimation.h"
#include "ts_state_machine.h"
#include "stm32f3xx_hal.h"
#include "stm32f3xx_hal_gpio.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
@ -50,9 +51,12 @@
/* Private variables ---------------------------------------------------------*/
ADC_HandleTypeDef hadc2;
CAN_HandleTypeDef hcan;
I2C_HandleTypeDef hi2c1;
TIM_HandleTypeDef htim15;
UART_HandleTypeDef huart1;
/* USER CODE BEGIN PV */
@ -65,6 +69,8 @@ static void MX_GPIO_Init(void);
static void MX_ADC2_Init(void);
static void MX_CAN_Init(void);
static void MX_USART1_UART_Init(void);
static void MX_I2C1_Init(void);
static void MX_TIM15_Init(void);
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
@ -92,7 +98,7 @@ static void loop_delay() {
*/
int main(void) {
/* USER CODE BEGIN 1 */
uint8_t soc_init_complete = 0;
/* USER CODE END 1 */
/* MCU Configuration--------------------------------------------------------*/
@ -117,11 +123,15 @@ int main(void) {
MX_ADC2_Init();
MX_CAN_Init();
MX_USART1_UART_Init();
MX_I2C1_Init();
MX_TIM15_Init();
/* USER CODE BEGIN 2 */
can_init(&hcan);
slaves_init();
shunt_init();
ts_sm_init();
soc_init();
imd_init(&htim15);
HAL_GPIO_WritePin(AMS_NERROR_GPIO_Port, AMS_NERROR_Pin, GPIO_PIN_SET);
/* USER CODE END 2 */
@ -138,17 +148,11 @@ int main(void) {
slaves_check();
shunt_check();
ts_sm_update();
if(soc_init_complete){
soc_update(shunt_getcurrent());
}
else
{
soc_init();
soc_init_complete = 1;
}
soc_update();
imd_update();
can_send_status();
loop_delay();
loop_delay();
}
/* USER CODE END 3 */
}
@ -190,9 +194,10 @@ void SystemClock_Config(void) {
Error_Handler();
}
PeriphClkInit.PeriphClockSelection =
RCC_PERIPHCLK_USART1 | RCC_PERIPHCLK_ADC12;
RCC_PERIPHCLK_USART1 | RCC_PERIPHCLK_I2C1 | RCC_PERIPHCLK_ADC12;
PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2;
PeriphClkInit.Adc12ClockSelection = RCC_ADC12PLLCLK_DIV1;
PeriphClkInit.I2c1ClockSelection = RCC_I2C1CLKSOURCE_HSI;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) {
Error_Handler();
}
@ -285,6 +290,108 @@ static void MX_CAN_Init(void) {
/* USER CODE END CAN_Init 2 */
}
/**
* @brief I2C1 Initialization Function
* @param None
* @retval None
*/
static void MX_I2C1_Init(void) {
/* USER CODE BEGIN I2C1_Init 0 */
/* USER CODE END I2C1_Init 0 */
/* USER CODE BEGIN I2C1_Init 1 */
/* USER CODE END I2C1_Init 1 */
hi2c1.Instance = I2C1;
hi2c1.Init.Timing = 0x2000090E;
hi2c1.Init.OwnAddress1 = 0;
hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
hi2c1.Init.OwnAddress2 = 0;
hi2c1.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
if (HAL_I2C_Init(&hi2c1) != HAL_OK) {
Error_Handler();
}
/** Configure Analogue filter
*/
if (HAL_I2CEx_ConfigAnalogFilter(&hi2c1, I2C_ANALOGFILTER_ENABLE) != HAL_OK) {
Error_Handler();
}
/** Configure Digital filter
*/
if (HAL_I2CEx_ConfigDigitalFilter(&hi2c1, 0) != HAL_OK) {
Error_Handler();
}
/* USER CODE BEGIN I2C1_Init 2 */
/* USER CODE END I2C1_Init 2 */
}
/**
* @brief TIM15 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM15_Init(void) {
/* USER CODE BEGIN TIM15_Init 0 */
/* USER CODE END TIM15_Init 0 */
TIM_SlaveConfigTypeDef sSlaveConfig = {0};
TIM_IC_InitTypeDef sConfigIC = {0};
TIM_MasterConfigTypeDef sMasterConfig = {0};
/* USER CODE BEGIN TIM15_Init 1 */
/* USER CODE END TIM15_Init 1 */
htim15.Instance = TIM15;
htim15.Init.Prescaler = 16000 - 1;
htim15.Init.CounterMode = TIM_COUNTERMODE_UP;
htim15.Init.Period = 65535;
htim15.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim15.Init.RepetitionCounter = 0;
htim15.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_IC_Init(&htim15) != HAL_OK) {
Error_Handler();
}
sSlaveConfig.SlaveMode = TIM_SLAVEMODE_RESET;
sSlaveConfig.InputTrigger = TIM_TS_TI1FP1;
sSlaveConfig.TriggerPolarity = TIM_INPUTCHANNELPOLARITY_RISING;
sSlaveConfig.TriggerPrescaler = TIM_ICPSC_DIV1;
sSlaveConfig.TriggerFilter = 0;
if (HAL_TIM_SlaveConfigSynchro(&htim15, &sSlaveConfig) != HAL_OK) {
Error_Handler();
}
sConfigIC.ICPolarity = TIM_INPUTCHANNELPOLARITY_RISING;
sConfigIC.ICSelection = TIM_ICSELECTION_DIRECTTI;
sConfigIC.ICPrescaler = TIM_ICPSC_DIV1;
sConfigIC.ICFilter = 0;
if (HAL_TIM_IC_ConfigChannel(&htim15, &sConfigIC, TIM_CHANNEL_1) != HAL_OK) {
Error_Handler();
}
sConfigIC.ICPolarity = TIM_INPUTCHANNELPOLARITY_FALLING;
sConfigIC.ICSelection = TIM_ICSELECTION_INDIRECTTI;
if (HAL_TIM_IC_ConfigChannel(&htim15, &sConfigIC, TIM_CHANNEL_2) != HAL_OK) {
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim15, &sMasterConfig) !=
HAL_OK) {
Error_Handler();
}
/* USER CODE BEGIN TIM15_Init 2 */
/* USER CODE END TIM15_Init 2 */
}
/**
* @brief USART1 Initialization Function
* @param None
@ -345,11 +452,11 @@ static void MX_GPIO_Init(void) {
HAL_GPIO_WritePin(PRECHARGE_CTRL_GPIO_Port, PRECHARGE_CTRL_Pin,
GPIO_PIN_RESET);
/*Configure GPIO pins : HV_MISMATCH_ERR_Pin RELAY_MISMATCH_ERR_Pin
/*Configure GPIO pins : HV_MISMATCH_ERR_Pin RELAY_MISMATCH_ERR_Pin IMD_OK_Pin
RELAY_CONNECTION_ERR_Pin HV_ACTIVE_Pin NEG_AIR_CLOSED_Pin
POS_AIR_CLOSED_Pin */
GPIO_InitStruct.Pin = HV_MISMATCH_ERR_Pin | RELAY_MISMATCH_ERR_Pin |
RELAY_CONNECTION_ERR_Pin | HV_ACTIVE_Pin |
IMD_OK_Pin | RELAY_CONNECTION_ERR_Pin | HV_ACTIVE_Pin |
NEG_AIR_CLOSED_Pin | POS_AIR_CLOSED_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_NOPULL;

View File

@ -20,6 +20,7 @@ void shunt_init() {
shunt_data.energy = 0;
shunt_data.current_counter = 0;
shunt_data.last_message = 0;
shunt_data.last_current_message = 0;
}
void shunt_check() {
@ -46,6 +47,12 @@ void shunt_handle_can_msg(uint16_t id, const uint8_t *data) {
switch (id) {
case CAN_ID_SHUNT_CURRENT:
shunt_data.current = result;
if (shunt_data.last_current_message > 0) {
uint32_t now = HAL_GetTick();
float dt = (now - shunt_data.last_current_message) * 0.001f;
shunt_data.current_counter += shunt_data.current * dt;
}
shunt_data.last_current_message = HAL_GetTick();
break;
case CAN_ID_SHUNT_VOLTAGE1:
shunt_data.voltage_bat = result;
@ -63,15 +70,13 @@ void shunt_handle_can_msg(uint16_t id, const uint8_t *data) {
shunt_data.power = result;
break;
case CAN_ID_SHUNT_CURRENT_COUNTER:
shunt_data.current_counter = result;
// TODO: Use this when we get the shunt to emit current counter data (the
// shunt apparently emits As, not mAs)
// shunt_data.current_counter = result * 1000;
break;
case CAN_ID_SHUNT_ENERGY_COUNTER:
shunt_data.energy = result;
break;
}
}
int32_t shunt_getcurrent()
{
return shunt_data.current;
}

View File

@ -91,9 +91,10 @@ void slaves_check() {
}
void slaves_handle_panic(const uint8_t *data) {
uint8_t slave_id = ftcan_unmarshal_unsigned(&data, 1);
const uint8_t **ptr = &data;
uint8_t slave_id = ftcan_unmarshal_unsigned(ptr, 1);
uint8_t idx = get_slave_index(slave_id);
uint8_t error_kind = ftcan_unmarshal_unsigned(&data, 1);
uint8_t error_kind = ftcan_unmarshal_unsigned(ptr, 1);
switch (error_kind) {
case SLAVE_PANIC_OT:
slaves[idx].error.kind = SLAVE_ERR_OT;
@ -118,11 +119,7 @@ void slaves_handle_status(const uint8_t *data) {
uint8_t slave_id = data[0] & 0x7F;
uint8_t idx = get_slave_index(slave_id);
int error = data[0] & 0x80;
if (error) {
if (slaves[idx].error.kind == SLAVE_ERR_NONE) {
slaves[idx].error.kind = SLAVE_ERR_UNKNOWN;
}
} else {
if (!error) {
slaves[idx].error.kind = SLAVE_ERR_NONE;
}
slaves[idx].soc = data[1];
@ -136,14 +133,3 @@ void slaves_handle_status(const uint8_t *data) {
void slaves_handle_log(const uint8_t *data) {
// TODO
}
uint16_t slaves_get_minimum_voltage()
{
uint16_t minvoltage = 50000;
for(uint8_t idx = 0; idx < N_SLAVES;idx++){
if(slaves->min_voltage < minvoltage){
min_voltage = slaves->min_voltage;
}
}
return minvoltage;
}

View File

@ -1,103 +1,89 @@
#include "soc_estimation.h"
#include <stdint.h>
#include "shunt_monitoring.h"
#include "slave_monitoring.h"
#include "stm32f3xx_hal.h"
#include <stddef.h>
#include <stdint.h>
//------------------------------------Battery RC and OCV-SoC Parameters-----------------------------------------
//@Note Parameters were obtained by EIS Measurements at the start of the season
//If the errror with this values is to large, consider retesting some cells
const float SOC[N_MODELPARAMETERS]={0,0.1,0.2,0.3,0.4,0.5,0.6,0.7,0.8,0.9,1};
const float R0[N_MODELPARAMETERS]={0.0089,0.0087,0.0090,0.0087,0.0087,0.0087,0.0088,0.0088,0.0087,0.0088,0.0089};
const float R1[N_MODELPARAMETERS]={0.0164,0.0063,0.0050,0.0055,0.0051,0.0052,0.0057,0.0048,0.0059,0.0055,0.0061};
const float C1[N_MODELPARAMETERS]={2.5694,0.2649,0.2876,0.2594,0.2415,0.2360,0.2946,0.2558,0.2818,0.2605,0.2763};
const float OCV_Data[N_MODELPARAMETERS]={2.762504,3.326231,3.460875,3.57681,3.655326,3.738444,3.835977,3.925841,4.032575,4.078275,4.191449};
#define SOC_ESTIMATION_NO_CURRENT_THRESH 200 // mA
#define SOC_ESTIMATION_NO_CURRENT_TIME 100000 // ms
#define SOC_ESTIMATION_BATTERY_CAPACITY 70300800 // mAs
ocv_soc_pair_t OCV_SOC_PAIRS[] = {
{25000, 0.00f}, {29900, 3.97f}, {32300, 9.36f}, {33200, 12.60f},
{33500, 13.68f}, {34100, 20.15f}, {35300, 32.01f}, {38400, 66.53f},
{40100, 83.79f}, {40200, 90.26f}, {40400, 94.58f}, {41000, 98.89f},
{42000, 100.00f}};
//---------------------------------------------------------------------------------------------------------------
float current_soc;
int current_was_flowing;
uint32_t last_current_time;
float soc_before_current;
float mAs_before_current;
float soc_approxparameterbysoc(float,float*, uint8_t);
float soc_approxsocbyocv(float);
uint8_t current_soc;
float current_floatsoc;
float batterycapacity;
/**
* @brief This Function initializes the SoC Prediction
* @note Because SoC is initalized using the OCV-Curve of the Cell, it is necessary to obtain a valid value
* for the lowest cell voltage before calling this function
*/
void soc_init() {
float minvoltage = ((float)slaves_get_minimum_voltage())/1000;
current_floatsoc = soc_approxsocbyocv(minvoltage);
batterycapacity = BATTERYCAPACITYAs*current_floatsoc;
current_soc = (uint8_t)(current_floatsoc*100);
current_soc = 0;
last_current_time = 0;
current_was_flowing = 1;
}
/**
* @brief Update Function for the State of Charge. Call this Function every time the shunt sends a new current
* @note The SoC Prediction works using a Coulomb Counter to track the SoC. Alternativly and maybe more elegant
* would be to track the SoC using the integrated current counter of the shunt.
* @param shunt_current
*/
void soc_update(int32_t shunt_current) {
// TODO
static uint32_t lasttick = 0;
if(lasttick != 0)
{
uint32_t dt = HAL_GetTick() - lasttick;
batterycapacity += batterycapacity + ((float) dt*shunt_current)/1000;
current_floatsoc = batterycapacity/BATTERYCAPACITYAs;
current_soc = (uint8_t) (current_floatsoc*100);
}
lasttick=HAL_GetTick();
}
void soe_update()
{
//TODO
}
void soap_update()
{
//TODO
}
float soc_approxparameterbysoc(float soc,float* lut, uint8_t lutlen)
{
//TODO
return 0;
}
float soc_approxsocbyocv(float ocv)
{
if(ocv < OCV_Data[0])
return 0;
if(ocv > OCV_Data[N_MODELPARAMETERS])
return 1;
//Iterate through OCV Lookup
uint8_t ocvindex = 0;
for(uint8_t i = 0; i < (N_MODELPARAMETERS-1);i++)
{
if((OCV_Data[i] <= ocv) && (OCV_Data[i+1] > ocv))
{
ocvindex = i;
void soc_update() {
uint32_t now = HAL_GetTick();
if (shunt_data.current >= SOC_ESTIMATION_NO_CURRENT_THRESH) {
last_current_time = now;
if (!current_was_flowing) {
soc_before_current = current_soc;
mAs_before_current = shunt_data.current_counter;
}
current_was_flowing = 1;
} else {
current_was_flowing = 0;
}
float m = (ocv-OCV_Data[ocvindex])/(OCV_Data[ocvindex+1]-OCV_Data[ocvindex]);
float soc = (SOC[ocvindex+1] - SOC[ocvindex])*m + SOC[ocvindex];
return soc;
if (now - last_current_time >= SOC_ESTIMATION_NO_CURRENT_TIME ||
last_current_time == 0) {
// Assume we're measuring OCV if there's been no current for a while (or
// we've just turned on the battery).
current_soc = soc_for_ocv(min_voltage);
} else {
// Otherwise, use the current counter to update SoC
float as_delta = shunt_data.current_counter - mAs_before_current;
float soc_delta = as_delta / SOC_ESTIMATION_BATTERY_CAPACITY * 100;
current_soc = soc_before_current + soc_delta;
}
}
}
float soc_for_ocv(uint16_t ocv) {
size_t i = 0;
size_t array_length = sizeof(OCV_SOC_PAIRS) / sizeof(*OCV_SOC_PAIRS);
// Find the index of the first element with OCV greater than the target OCV
while (i < array_length && OCV_SOC_PAIRS[i].ocv <= ocv) {
i++;
}
// If the target OCV is lower than the smallest OCV in the array, return the
// first SOC value
if (i == 0) {
return OCV_SOC_PAIRS[0].soc;
}
// If the target OCV is higher than the largest OCV in the array, return the
// last SOC value
if (i == array_length) {
return OCV_SOC_PAIRS[array_length - 1].soc;
}
// Perform linear interpolation
uint16_t ocv1 = OCV_SOC_PAIRS[i - 1].ocv;
uint16_t ocv2 = OCV_SOC_PAIRS[i].ocv;
float soc1 = OCV_SOC_PAIRS[i - 1].soc;
float soc2 = OCV_SOC_PAIRS[i].soc;
float slope = (soc2 - soc1) / (ocv2 - ocv1);
float interpolated_soc = soc1 + slope * (ocv - ocv1);
return interpolated_soc;
}

View File

@ -207,6 +207,149 @@ void HAL_CAN_MspDeInit(CAN_HandleTypeDef* hcan)
}
/**
* @brief I2C MSP Initialization
* This function configures the hardware resources used in this example
* @param hi2c: I2C handle pointer
* @retval None
*/
void HAL_I2C_MspInit(I2C_HandleTypeDef* hi2c)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hi2c->Instance==I2C1)
{
/* USER CODE BEGIN I2C1_MspInit 0 */
/* USER CODE END I2C1_MspInit 0 */
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/**I2C1 GPIO Configuration
PA15 ------> I2C1_SCL
PB9 ------> I2C1_SDA
*/
GPIO_InitStruct.Pin = GPIO_PIN_15;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF4_I2C1;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_9;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF4_I2C1;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* Peripheral clock enable */
__HAL_RCC_I2C1_CLK_ENABLE();
/* USER CODE BEGIN I2C1_MspInit 1 */
/* USER CODE END I2C1_MspInit 1 */
}
}
/**
* @brief I2C MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hi2c: I2C handle pointer
* @retval None
*/
void HAL_I2C_MspDeInit(I2C_HandleTypeDef* hi2c)
{
if(hi2c->Instance==I2C1)
{
/* USER CODE BEGIN I2C1_MspDeInit 0 */
/* USER CODE END I2C1_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_I2C1_CLK_DISABLE();
/**I2C1 GPIO Configuration
PA15 ------> I2C1_SCL
PB9 ------> I2C1_SDA
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_15);
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_9);
/* USER CODE BEGIN I2C1_MspDeInit 1 */
/* USER CODE END I2C1_MspDeInit 1 */
}
}
/**
* @brief TIM_IC MSP Initialization
* This function configures the hardware resources used in this example
* @param htim_ic: TIM_IC handle pointer
* @retval None
*/
void HAL_TIM_IC_MspInit(TIM_HandleTypeDef* htim_ic)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(htim_ic->Instance==TIM15)
{
/* USER CODE BEGIN TIM15_MspInit 0 */
/* USER CODE END TIM15_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_TIM15_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**TIM15 GPIO Configuration
PA2 ------> TIM15_CH1
*/
GPIO_InitStruct.Pin = IMD_M_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF9_TIM15;
HAL_GPIO_Init(IMD_M_GPIO_Port, &GPIO_InitStruct);
/* TIM15 interrupt Init */
HAL_NVIC_SetPriority(TIM1_BRK_TIM15_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(TIM1_BRK_TIM15_IRQn);
/* USER CODE BEGIN TIM15_MspInit 1 */
/* USER CODE END TIM15_MspInit 1 */
}
}
/**
* @brief TIM_IC MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param htim_ic: TIM_IC handle pointer
* @retval None
*/
void HAL_TIM_IC_MspDeInit(TIM_HandleTypeDef* htim_ic)
{
if(htim_ic->Instance==TIM15)
{
/* USER CODE BEGIN TIM15_MspDeInit 0 */
/* USER CODE END TIM15_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM15_CLK_DISABLE();
/**TIM15 GPIO Configuration
PA2 ------> TIM15_CH1
*/
HAL_GPIO_DeInit(IMD_M_GPIO_Port, IMD_M_Pin);
/* TIM15 interrupt DeInit */
HAL_NVIC_DisableIRQ(TIM1_BRK_TIM15_IRQn);
/* USER CODE BEGIN TIM15_MspDeInit 1 */
/* USER CODE END TIM15_MspDeInit 1 */
}
}
/**
* @brief UART MSP Initialization
* This function configures the hardware resources used in this example

View File

@ -56,6 +56,7 @@
/* External variables --------------------------------------------------------*/
extern CAN_HandleTypeDef hcan;
extern TIM_HandleTypeDef htim15;
/* USER CODE BEGIN EV */
/* USER CODE END EV */
@ -217,6 +218,20 @@ void USB_LP_CAN_RX0_IRQHandler(void)
/* USER CODE END USB_LP_CAN_RX0_IRQn 1 */
}
/**
* @brief This function handles TIM1 break and TIM15 interrupts.
*/
void TIM1_BRK_TIM15_IRQHandler(void)
{
/* USER CODE BEGIN TIM1_BRK_TIM15_IRQn 0 */
/* USER CODE END TIM1_BRK_TIM15_IRQn 0 */
HAL_TIM_IRQHandler(&htim15);
/* USER CODE BEGIN TIM1_BRK_TIM15_IRQn 1 */
/* USER CODE END TIM1_BRK_TIM15_IRQn 1 */
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

View File

@ -40,7 +40,7 @@ cxxDefinitionsFile:
asDefinitionsFile:
# Compiler flags
cFlags: []
cFlags: [-Wall, -Wextra, -Wno-unused-parameter]
cxxFlags: []
assemblyFlags: []
linkerFlags:

View File

@ -38,10 +38,12 @@ BUILD_DIR = build
C_SOURCES = \
Core/Lib/can-halal/can-halal.c \
Core/Src/can.c \
Core/Src/imd_monitoring.c \
Core/Src/main.c \
Core/Src/shunt_monitoring.c \
Core/Src/slave_monitoring.c \
Core/Src/soc_estimation.c \
Core/Src/status_led.c \
Core/Src/stm32f3xx_hal_msp.c \
Core/Src/stm32f3xx_it.c \
Core/Src/system_stm32f3xx.c \
@ -85,7 +87,7 @@ PREFIX = arm-none-eabi-
POSTFIX = "
# The gcc compiler bin path can be either defined in make command via GCC_PATH variable (> make GCC_PATH=xxx)
# either it can be added to the PATH environment variable.
GCC_PATH="/home/jasper/.config/Code/User/globalStorage/bmd.stm32-for-vscode/@xpack-dev-tools/arm-none-eabi-gcc/11.3.1-1.1.2/.content/bin
GCC_PATH="/home/kbracher/.vscode-server/data/User/globalStorage/bmd.stm32-for-vscode/@xpack-dev-tools/arm-none-eabi-gcc/12.3.1-1.2.1/.content/bin
ifdef GCC_PATH
CXX = $(GCC_PATH)/$(PREFIX)g++$(POSTFIX)
CC = $(GCC_PATH)/$(PREFIX)gcc$(POSTFIX)
@ -161,7 +163,7 @@ CXXFLAGS += -g -gdwarf -ggdb
endif
# Add additional flags
CFLAGS +=
CFLAGS += -Wall -Wextra -Wno-unused-parameter
ASFLAGS +=
CXXFLAGS +=
@ -241,13 +243,13 @@ $(BUILD_DIR):
# flash
#######################################
flash: $(BUILD_DIR)/$(TARGET).elf
"/home/jasper/.config/Code/User/globalStorage/bmd.stm32-for-vscode/@xpack-dev-tools/openocd/0.11.0-5.1/.content/bin/openocd" -f ./openocd.cfg -c "program $(BUILD_DIR)/$(TARGET).elf verify reset exit"
"/home/kbracher/.vscode-server/data/User/globalStorage/bmd.stm32-for-vscode/@xpack-dev-tools/openocd/0.12.0-2.1/.content/bin/openocd" -f ./openocd.cfg -c "program $(BUILD_DIR)/$(TARGET).elf verify reset exit"
#######################################
# erase
#######################################
erase: $(BUILD_DIR)/$(TARGET).elf
"/home/jasper/.config/Code/User/globalStorage/bmd.stm32-for-vscode/@xpack-dev-tools/openocd/0.11.0-5.1/.content/bin/openocd" -f ./openocd.cfg -c "init; reset halt; stm32f3x mass_erase 0; exit"
"/home/kbracher/.vscode-server/data/User/globalStorage/bmd.stm32-for-vscode/@xpack-dev-tools/openocd/0.12.0-2.1/.content/bin/openocd" -f ./openocd.cfg -c "init; reset halt; stm32f3x mass_erase 0; exit"
#######################################
# clean up

View File

@ -26,45 +26,51 @@ Mcu.CPN=STM32F302CBT6
Mcu.Family=STM32F3
Mcu.IP0=ADC2
Mcu.IP1=CAN
Mcu.IP2=NVIC
Mcu.IP3=RCC
Mcu.IP4=SYS
Mcu.IP5=USART1
Mcu.IPNb=6
Mcu.IP2=I2C1
Mcu.IP3=NVIC
Mcu.IP4=RCC
Mcu.IP5=SYS
Mcu.IP6=TIM15
Mcu.IP7=USART1
Mcu.IPNb=8
Mcu.Name=STM32F302C(B-C)Tx
Mcu.Package=LQFP48
Mcu.Pin0=PF0-OSC_IN
Mcu.Pin1=PF1-OSC_OUT
Mcu.Pin10=PB2
Mcu.Pin11=PB10
Mcu.Pin12=PB11
Mcu.Pin13=PB12
Mcu.Pin14=PB13
Mcu.Pin15=PB14
Mcu.Pin16=PB15
Mcu.Pin17=PA8
Mcu.Pin18=PA9
Mcu.Pin19=PA10
Mcu.Pin10=PB0
Mcu.Pin11=PB1
Mcu.Pin12=PB2
Mcu.Pin13=PB10
Mcu.Pin14=PB11
Mcu.Pin15=PB12
Mcu.Pin16=PB13
Mcu.Pin17=PB14
Mcu.Pin18=PB15
Mcu.Pin19=PA8
Mcu.Pin2=PA0
Mcu.Pin20=PA11
Mcu.Pin21=PA12
Mcu.Pin22=PA13
Mcu.Pin23=PA14
Mcu.Pin24=PB3
Mcu.Pin25=PB4
Mcu.Pin26=PB5
Mcu.Pin27=PB6
Mcu.Pin28=PB7
Mcu.Pin29=PB8
Mcu.Pin20=PA9
Mcu.Pin21=PA10
Mcu.Pin22=PA11
Mcu.Pin23=PA12
Mcu.Pin24=PA13
Mcu.Pin25=PA14
Mcu.Pin26=PA15
Mcu.Pin27=PB3
Mcu.Pin28=PB4
Mcu.Pin29=PB5
Mcu.Pin3=PA1
Mcu.Pin30=VP_SYS_VS_Systick
Mcu.Pin4=PA4
Mcu.Pin5=PA5
Mcu.Pin6=PA6
Mcu.Pin7=PA7
Mcu.Pin8=PB0
Mcu.Pin9=PB1
Mcu.PinsNb=31
Mcu.Pin30=PB6
Mcu.Pin31=PB7
Mcu.Pin32=PB8
Mcu.Pin33=PB9
Mcu.Pin34=VP_SYS_VS_Systick
Mcu.Pin4=PA2
Mcu.Pin5=PA3
Mcu.Pin6=PA4
Mcu.Pin7=PA5
Mcu.Pin8=PA6
Mcu.Pin9=PA7
Mcu.PinsNb=35
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F302CBTx
@ -80,6 +86,7 @@ NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.SysTick_IRQn=true\:15\:0\:false\:false\:true\:false\:true\:false
NVIC.TIM1_BRK_TIM15_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
NVIC.USB_LP_CAN_RX0_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
PA0.GPIOParameters=GPIO_Label
@ -105,6 +112,16 @@ PA13.Signal=SYS_JTMS-SWDIO
PA14.Locked=true
PA14.Mode=Trace_Asynchronous_SW
PA14.Signal=SYS_JTCK-SWCLK
PA15.Mode=I2C
PA15.Signal=I2C1_SCL
PA2.GPIOParameters=GPIO_Label
PA2.GPIO_Label=IMD_M
PA2.Locked=true
PA2.Signal=S_TIM15_CH1
PA3.GPIOParameters=GPIO_Label
PA3.GPIO_Label=IMD_OK
PA3.Locked=true
PA3.Signal=GPIO_Input
PA4.GPIOParameters=GPIO_Label
PA4.GPIO_Label=RELAY_CONNECTION_ERR
PA4.Locked=true
@ -188,6 +205,8 @@ PB8.GPIOParameters=GPIO_Label
PB8.GPIO_Label=AMS_NERROR
PB8.Locked=true
PB8.Signal=GPIO_Output
PB9.Mode=I2C
PB9.Signal=I2C1_SDA
PF0-OSC_IN.Mode=HSE-External-Oscillator
PF0-OSC_IN.Signal=RCC_OSC_IN
PF1-OSC_OUT.Mode=HSE-External-Oscillator
@ -221,7 +240,7 @@ ProjectManager.StackSize=0x400
ProjectManager.TargetToolchain=Makefile
ProjectManager.ToolChainLocation=
ProjectManager.UnderRoot=false
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_ADC2_Init-ADC2-false-HAL-true,4-MX_CAN_Init-CAN-false-HAL-true,5-MX_USART1_UART_Init-USART1-false-HAL-true
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_ADC2_Init-ADC2-false-HAL-true,4-MX_CAN_Init-CAN-false-HAL-true,5-MX_USART1_UART_Init-USART1-false-HAL-true,6-MX_I2C1_Init-I2C1-false-HAL-true,7-MX_TIM15_Init-TIM15-false-HAL-true
RCC.ADC12outputFreq_Value=16000000
RCC.AHBFreq_Value=16000000
RCC.APB1Freq_Value=16000000
@ -256,6 +275,10 @@ RCC.USART2Freq_Value=16000000
RCC.USART3Freq_Value=16000000
RCC.USBFreq_Value=16000000
RCC.VCOOutput2Freq_Value=4000000
SH.S_TIM15_CH1.0=TIM15_CH1,PWM_Input_1
SH.S_TIM15_CH1.ConfNb=1
TIM15.IPParameters=Prescaler
TIM15.Prescaler=16000-1
USART1.IPParameters=VirtualMode-Asynchronous
USART1.VirtualMode-Asynchronous=VM_ASYNC
VP_SYS_VS_Systick.Mode=SysTick

1159
compile_commands.json Normal file

File diff suppressed because it is too large Load Diff