create new branch for 23 charger testing

This commit is contained in:
2025-02-20 21:57:06 +01:00
parent 177f47426a
commit c1c85c276e
1403 changed files with 4985 additions and 1123693 deletions

View File

@ -0,0 +1,43 @@
/*
* b_cccv_algo.h
*
* Created on: 16.06.2023
* Author: max
*/
#include <stdint.h>
#include "stm32h7xx_hal.h"
#ifndef INC_B_CCCV_ALGO_H_
#define INC_B_CCCV_ALGO_H_
#define I_GAIN 4
#define P_GAIN 10
#define CHARGE_CURRENT_LIMIT 10.0
#define SIMULINKTEST
#undef SIMULINKTEST
typedef enum{
NO_CHARGING,
CHARGING_IN_PROGRESS,
CHARGING_COMPLETED
} CCCV_CONTROL_STATE;
#ifdef SIMULINKTEST
CCCV_CONTROL_STATE cccvloop(float maxcellvoltage, float voltagesetpoint, float maxcurrent, float*ccurrent);
#else
CCCV_CONTROL_STATE cccvloop(float maxcellvoltage, float voltagesetpoint, float maxcurrent);
void setchargecurrent(float chargecurrent);
void setchargevoltage(uint8_t numberofcells,float maximumcellvoltage);
float getMaximumCellVoltage();
void chargingloop(float maximumcellvoltage);
void startcharging(float endvoltage);
void initChargerAlgo(uint8_t numberofcells, float maximumcellvoltage);
void setchargevoltage(uint8_t numberofcells,float maximumcellvoltage);
void stopcharging();
#endif
float matlabvalidationwrapper(float maxcellvoltage, float voltagesetpoint, float maxcurrent);
#endif /* INC_B_CCCV_ALGO_H_ */

View File

@ -0,0 +1,62 @@
#ifndef CAN_HALAL_H
#define CAN_HALAL_H
// Define family macros if none are defined and we recognize a chip macro
#if !defined(STM32F3) && !defined(STM32H7)
#if defined(STM32F302x6) || defined(STM32F302x8) || defined(STM32F302xB) || \
defined(STM32F302xC)
#define STM32F3
#endif
#if defined(STM32H7A3xx)
#define STM32H7
#endif
#endif
#if defined(STM32F3)
#include "stm32f3xx_hal.h"
#define FTCAN_IS_BXCAN
#define FTCAN_NUM_FILTERS 13
#elif defined(STM32H7)
#include "stm32h7xx_hal.h"
#define FTCAN_IS_FDCAN
#define FTCAN_NUM_FILTERS 13
#else
#error "Couldn't detect STM family"
#endif
#if defined(FTCAN_IS_BXCAN)
HAL_StatusTypeDef ftcan_init(CAN_HandleTypeDef *handle);
#elif defined(FTCAN_IS_FDCAN)
HAL_StatusTypeDef ftcan_init(FDCAN_HandleTypeDef *handle);
#else
#error "Unknown CAN peripheral"
#endif
HAL_StatusTypeDef ftcan_transmit(uint16_t id, const uint8_t *data,
size_t datalen);
HAL_StatusTypeDef ftcan_add_filter(uint16_t id, uint16_t mask);
/**
* Define this function to be notified of incoming CAN messages
*/
void ftcan_msg_received_cb(uint16_t id, size_t datalen, const uint8_t *data);
/**
* Read num_bytes bytes from a message (unmarshalled network byte order). The
* msg pointer is advanced by the corresponding number of bytes.
*
* Both methods return a 64-bit integer, but you can safely cast it to a smaller
* integer type.
*/
uint64_t ftcan_unmarshal_unsigned(const uint8_t **data, size_t num_bytes);
int64_t ftcan_unmarshal_signed(const uint8_t **data, size_t num_bytes);
/**
* Write num_bytes to a message (marshalled in network byte order). The pointer
* is advanced by the corresponding number of bytes and returned.
*/
uint8_t *ftcan_marshal_unsigned(uint8_t *data, uint64_t val, size_t num_bytes);
uint8_t *ftcan_marshal_signed(uint8_t *data, int64_t val, size_t num_bytes);
#endif // CAN_HALAL_H

22
Software/Core/Inc/can.h Normal file
View File

@ -0,0 +1,22 @@
/*
* can.h
*
* Created on: 21.06.2023
* Author: max
*/
#ifndef INC_CAN_H_
#define INC_CAN_H_
#include "stm32h7xx_hal.h"
#define CAN_ID_AMS_STATUS 0x00A
#define CAN_ID_AMS_IN 0x00B
#define CAN_ID_SLAVE_STATUS_BASE 0x080
#define CAN_ID_CHARGER_ACTIVE 0x200
void initCan(FDCAN_HandleTypeDef *hcan);
#endif /* INC_CAN_H_ */

View File

@ -0,0 +1,17 @@
/*
* charge_ctrl_test_shell.h
*
* Created on: May 21, 2023
* Author: max
*/
#ifndef INC_CHARGE_CTRL_TEST_SHELL_H_
#define INC_CHARGE_CTRL_TEST_SHELL_H_
#include "stm32h7xx_hal.h"
void charge_shell_init(UART_HandleTypeDef *huart);
void charge_shell_loop();
#endif /* INC_CHARGE_CTRL_TEST_SHELL_H_ */

View File

@ -0,0 +1,39 @@
/*
* charger_control.h
*
* Created on: May 21, 2023
* Author: MaxMax
*/
#ifndef INC_CHARGER_CONTROL_H_
#define INC_CHARGER_CONTROL_H_
#include "stm32h7xx_hal.h"
#define CURRENT_DAC_ADR 0x58
#define VOLTAGE_DAC_ADR 0x5E
#define CHARGER_ADC_ADR 0x90
typedef struct{
uint8_t acfail;
uint8_t dcfail;
uint8_t cc_status;
uint8_t ot_status;
uint8_t lim_status;
uint16_t voltage;
uint16_t current;
}ChargerStatusHandleTypeDef;
void charger_control_init(I2C_HandleTypeDef* hi2c);
ChargerStatusHandleTypeDef charger_control_get_state();
void charger_control_set_current(uint32_t current);
void charger_control_set_voltage(uint32_t voltage);
void charger_control_enable_charger_relay();
void charger_control_disable_charger_relay();
void charger_control_enable_remote();
void charger_control_disable_remote();
void charger_control_setup_DACs();
#endif /* INC_CHARGER_CONTROL_H_ */

View File

@ -7,12 +7,13 @@
******************************************************************************
* @attention
*
* Copyright (c) 2024 STMicroelectronics.
* All rights reserved.
* <h2><center>&copy; Copyright (c) 2022 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
@ -57,6 +58,32 @@ void Error_Handler(void);
/* USER CODE END EFP */
/* Private defines -----------------------------------------------------------*/
#define STATUS_LED_1_Pin GPIO_PIN_6
#define STATUS_LED_1_GPIO_Port GPIOF
#define STATUS_LED_2_Pin GPIO_PIN_7
#define STATUS_LED_2_GPIO_Port GPIOF
#define Display_Reset_Pin GPIO_PIN_8
#define Display_Reset_GPIO_Port GPIOC
#define Display_Standby_Pin GPIO_PIN_10
#define Display_Standby_GPIO_Port GPIOC
#define Display_Left_Right_Pin GPIO_PIN_11
#define Display_Left_Right_GPIO_Port GPIOC
#define Display_Up_Down_Pin GPIO_PIN_12
#define Display_Up_Down_GPIO_Port GPIOC
#define Charger_CC_Status_Pin GPIO_PIN_9
#define Charger_CC_Status_GPIO_Port GPIOG
#define Charger_OT_Pin GPIO_PIN_11
#define Charger_OT_GPIO_Port GPIOG
#define Charger_LIM_Pin GPIO_PIN_12
#define Charger_LIM_GPIO_Port GPIOG
#define Charger_DC_FAIL_Pin GPIO_PIN_13
#define Charger_DC_FAIL_GPIO_Port GPIOG
#define Charger_Relay_Pin GPIO_PIN_14
#define Charger_Relay_GPIO_Port GPIOG
#define Charger_AC_Fail_Pin GPIO_PIN_4
#define Charger_AC_Fail_GPIO_Port GPIOB
#define Charger_Remote_Shutdown_Pin GPIO_PIN_5
#define Charger_Remote_Shutdown_GPIO_Port GPIOB
/* USER CODE BEGIN Private defines */

View File

@ -0,0 +1,46 @@
/*
* slave_handler.h
*
* Created on: Jun 21, 2023
* Author: max
*/
#ifndef INC_SLAVE_HANDLER_H_
#define INC_SLAVE_HANDLER_H_
#include "stm32h7xx_hal.h"
#define N_SLAVES 6
typedef enum {
SLAVE_ERR_NONE,
SLAVE_ERR_TIMEOUT,
SLAVE_ERR_OT,
SLAVE_ERR_UT,
SLAVE_ERR_OV,
SLAVE_ERR_UV,
SLAVE_ERR_UNKNOWN,
} SlaveErrorKind;
typedef struct {
SlaveErrorKind kind;
uint32_t data; // Cell/temperature ID etc
} SlaveError;
typedef struct {
uint8_t id;
SlaveError error;
uint8_t soc;
uint16_t min_voltage;
uint16_t max_voltage;
int16_t max_temp;
uint32_t last_message;
} SlaveHandle;
extern SlaveHandle slaves[N_SLAVES];
float slaves_get_maximum_voltage();
void slaves_handle_status(const uint8_t *data);
void slave_handler_init();
#endif /* INC_SLAVE_HANDLER_H_ */

View File

@ -45,13 +45,12 @@
/* #define HAL_DAC_MODULE_ENABLED */
/* #define HAL_DCMI_MODULE_ENABLED */
/* #define HAL_DMA2D_MODULE_ENABLED */
#define HAL_ETH_MODULE_ENABLED
/* #define HAL_ETH_LEGACY_MODULE_ENABLED */
/* #define HAL_ETH_MODULE_ENABLED */
/* #define HAL_NAND_MODULE_ENABLED */
/* #define HAL_NOR_MODULE_ENABLED */
/* #define HAL_OTFDEC_MODULE_ENABLED */
/* #define HAL_SRAM_MODULE_ENABLED */
/* #define HAL_SDRAM_MODULE_ENABLED */
#define HAL_SDRAM_MODULE_ENABLED
/* #define HAL_HASH_MODULE_ENABLED */
/* #define HAL_HRTIM_MODULE_ENABLED */
/* #define HAL_HSEM_MODULE_ENABLED */
@ -59,29 +58,29 @@
/* #define HAL_JPEG_MODULE_ENABLED */
/* #define HAL_OPAMP_MODULE_ENABLED */
/* #define HAL_OSPI_MODULE_ENABLED */
/* #define HAL_XSPI_MODULE_ENABLED */
/* #define HAL_OSPI_MODULE_ENABLED */
/* #define HAL_I2S_MODULE_ENABLED */
/* #define HAL_SMBUS_MODULE_ENABLED */
/* #define HAL_IWDG_MODULE_ENABLED */
/* #define HAL_LPTIM_MODULE_ENABLED */
#define HAL_LTDC_MODULE_ENABLED
/* #define HAL_XSPI_MODULE_ENABLED */
/* #define HAL_QSPI_MODULE_ENABLED */
/* #define HAL_RAMECC_MODULE_ENABLED */
/* #define HAL_RNG_MODULE_ENABLED */
/* #define HAL_RTC_MODULE_ENABLED */
/* #define HAL_SAI_MODULE_ENABLED */
/* #define HAL_SD_MODULE_ENABLED */
#define HAL_SD_MODULE_ENABLED
/* #define HAL_MMC_MODULE_ENABLED */
/* #define HAL_SPDIFRX_MODULE_ENABLED */
/* #define HAL_SPI_MODULE_ENABLED */
/* #define HAL_SWPMI_MODULE_ENABLED */
/* #define HAL_TIM_MODULE_ENABLED */
/* #define HAL_UART_MODULE_ENABLED */
#define HAL_UART_MODULE_ENABLED
/* #define HAL_USART_MODULE_ENABLED */
/* #define HAL_IRDA_MODULE_ENABLED */
/* #define HAL_SMARTCARD_MODULE_ENABLED */
/* #define HAL_WWDG_MODULE_ENABLED */
/* #define HAL_PCD_MODULE_ENABLED */
#define HAL_PCD_MODULE_ENABLED
/* #define HAL_HCD_MODULE_ENABLED */
/* #define HAL_DFSDM_MODULE_ENABLED */
/* #define HAL_DSI_MODULE_ENABLED */
@ -107,7 +106,7 @@
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE (25000000UL) /*!< Value of the External oscillator in Hz : FPGA case fixed to 60MHZ */
#define HSE_VALUE (16000000UL) /*!< Value of the External oscillator in Hz : FPGA case fixed to 60MHZ */
#endif /* HSE_VALUE */
#if !defined (HSE_STARTUP_TIMEOUT)
@ -166,7 +165,7 @@
* @brief This is the HAL system configuration section
*/
#define VDD_VALUE (3300UL) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY (15UL) /*!< tick interrupt priority */
#define TICK_INT_PRIORITY (0UL) /*!< tick interrupt priority */
#define USE_RTOS 0
#define USE_SD_TRANSCEIVER 0U /*!< use uSD Transceiver */
#define USE_SPI_CRC 0U /*!< use CRC in SPI */
@ -221,8 +220,8 @@
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
/* ########################### Ethernet Configuration ######################### */
#define ETH_TX_DESC_CNT 4U /* number of Ethernet Tx DMA descriptors */
#define ETH_RX_DESC_CNT 4U /* number of Ethernet Rx DMA descriptors */
#define ETH_TX_DESC_CNT 4 /* number of Ethernet Tx DMA descriptors */
#define ETH_RX_DESC_CNT 4 /* number of Ethernet Rx DMA descriptors */
#define ETH_MAC_ADDR0 (0x02UL)
#define ETH_MAC_ADDR1 (0x00UL)
@ -287,10 +286,6 @@
#include "stm32h7xx_hal_eth.h"
#endif /* HAL_ETH_MODULE_ENABLED */
#ifdef HAL_ETH_LEGACY_MODULE_ENABLED
#include "stm32h7xx_hal_eth_legacy.h"
#endif /* HAL_ETH_LEGACY_MODULE_ENABLED */
#ifdef HAL_EXTI_MODULE_ENABLED
#include "stm32h7xx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */

View File

@ -6,12 +6,13 @@
******************************************************************************
* @attention
*
* Copyright (c) 2024 STMicroelectronics.
* All rights reserved.
* <h2><center>&copy; Copyright (c) 2022 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
@ -55,6 +56,12 @@ void SVC_Handler(void);
void DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
void FDCAN1_IT0_IRQHandler(void);
void FDCAN1_IT1_IRQHandler(void);
void FMC_IRQHandler(void);
void FDCAN_CAL_IRQHandler(void);
void LTDC_IRQHandler(void);
void LTDC_ER_IRQHandler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */