Merge branch 'mvbms-test'

This commit is contained in:
2024-07-02 17:54:30 +03:00
27 changed files with 1243 additions and 333 deletions

View File

@ -1,37 +0,0 @@
/*
* AMS_CAN.h
*
* Created on: Mar 19, 2022
* Author: jasper
*/
#ifndef INC_AMS_CAN_H_
#define INC_AMS_CAN_H_
#include "main.h"
#include "stm32f3xx_hal.h"
#include "stm32f3xx_hal_can.h"
#include "stm32f3xx_hal_def.h"
#include <stdint.h>
typedef struct {
uint8_t pwrgndfans;
} rx_status_frame;
uint8_t txbuffer;
uint8_t rxbuffer;
void ams_can_init(CAN_HandleTypeDef* hcan);
void ams_can_handle_ams_msg(CAN_RxHeaderTypeDef* header, uint8_t* data);
void ams_can_send_status();
/**
* @brief Send an AMS Error via CAN.
*
* Data is taken from error_data
*/
void ams_can_send_error();
HAL_StatusTypeDef ams_can_wait_for_free_mailboxes(CAN_HandleTypeDef* handle,
int num_mailboxes,
uint32_t timeout);
void ams_can_send_log();
#endif /* INC_AMS_CAN_H_ */

View File

@ -11,7 +11,12 @@
#include "ADBMS_Abstraction.h"
#include "ADBMS_CMD_MAKROS.h"
#include "ADBMS_LL_Driver.h"
#include "AMS_CAN.h"
#include "can.h"
#include "TMP1075.h"
#include "can-halal.h"
#include "errors.h"
#include "stm32f3xx_hal.h"
#include <stdint.h>
typedef enum {
AMSDEACTIVE,

33
Core/Inc/PWM_control.h Normal file
View File

@ -0,0 +1,33 @@
#ifndef INC_PWM_CONTROL_H
#define INC_PWM_CONTROL_H
#include "stm32f3xx_hal.h"
#include "ADBMS_LL_Driver.h"
#include "state_machine.h"
#include <stdint.h>
#include "main.h"
/* The PWM period (1/FPWM) is defined by the following parameters:
ARR value, the Prescaler value, and the internal clock itself which drives the timer module FCLK.
F_PWM = (F_CLK)/((ARR + 1) * (PSC + 1))
F_CLK = 16 MHz
POWERGROUND ESC Signal: pulse every 20 ms, 1 ms = 0%, 2 ms = 100%
FREQ = 50 Hz -> 16 MHz/50 Hz = 320000 = ((39999 + 1) * (7 + 1))
DUTY CYCLE = 1/20 -> 0%, DUTY CYCLE = 2/20 -> 100%
CCR * DUTY_CYCLE
CCR: 1/20 -> 500, 2/20 -> 1000
*/
#define POWERGROUND_FREQ 50
#define POWERGROUND_MAX_DUTY_CYCLE 0.1
#define POWERGROUND_MIN_DUTY_CYCLE 0.05
//#define BATTERY_COOLING_FREQ 20000
void PWM_control_init(TIM_HandleTypeDef* powerground, TIM_HandleTypeDef* battery_cooling);
void PWM_powerground_control(uint8_t percent);
void PWM_battery_cooling_control(uint8_t percent);
#endif /* INC_CHANNEL_CONTROL_H */

View File

@ -1,15 +1,17 @@
#ifndef INC_TMP1075_H_
#define INC_TMP1075_H_
#include "AMS_CAN.h"
#include "can.h"
#include "common_defs.h"
#include "stm32f3xx_hal.h"
#include "stm32f3xx_hal_def.h"
#include "stm32f3xx_hal_i2c.h"
#include "TMP1075.h"
#include "can-halal.h"
#include "errors.h"
#include <stdint.h>
extern uint32_t tmp1075_failed_sensors;
extern int16_t tmp1075_temps[N_TEMP_SENSORS];
HAL_StatusTypeDef tmp1075_init(I2C_HandleTypeDef* hi2c);
HAL_StatusTypeDef tmp1075_measure();
HAL_StatusTypeDef tmp1075_sensor_init(int n);

23
Core/Inc/can.h Normal file
View File

@ -0,0 +1,23 @@
#ifndef INC_CAN_H
#define INC_CAN_H
#include "stm32f3xx_hal.h"
#include "ADBMS_Abstraction.h"
#include "main.h"
#include "can-halal.h"
#include "AMS_HighLevel.h"
#include "state_machine.h"
#include <stdint.h>
#define CAN_ID_IN 0x501
#define CAN_ID_OUT 0x502
#define CAN_STATUS_FREQ 1000
void can_init(CAN_HandleTypeDef* hcan);
void can_handle_send_status();
void can_handle_recieve_command(const uint8_t *data);
void ftcan_msg_received_cb(uint16_t id, size_t datalen, const uint8_t *data);
#endif /* "INC_CAN_H" */

View File

@ -8,7 +8,7 @@
#ifndef INC_COMMON_DEFS_H_
#define INC_COMMON_DEFS_H_
#define N_CELLS 14
#define N_TEMP_SENSORS 14
#define N_CELLS 12
#define N_TEMP_SENSORS 12
#endif /* INC_COMMON_DEFS_H_ */

View File

@ -1,17 +0,0 @@
#ifndef INC_EEPROM_H_
#define INC_EEPROM_H_
#include "stm32f3xx_hal.h"
#include <stdint.h>
__attribute__((packed)) typedef struct {
uint8_t id;
} EEPROMConfig;
extern EEPROMConfig eeprom_config;
void eeprom_init(I2C_HandleTypeDef* hi2c);
void eeprom_config_save();
#endif // INC_EEPROM_H_

View File

@ -73,10 +73,8 @@ void Error_Handler(void);
#define STATUS_LED_G_GPIO_Port GPIOB
#define PRECHARGE_EN_Pin GPIO_PIN_11
#define PRECHARGE_EN_GPIO_Port GPIOB
#define AUX_IN_Pin GPIO_PIN_13
#define AUX_IN_GPIO_Port GPIOB
#define AUX_OUT_Pin GPIO_PIN_14
#define AUX_OUT_GPIO_Port GPIOB
#define PWM_Battery_Cooling_Pin GPIO_PIN_15
#define PWM_Battery_Cooling_GPIO_Port GPIOB
#define RELAY_BATT_SIDE_ON_Pin GPIO_PIN_8
#define RELAY_BATT_SIDE_ON_GPIO_Port GPIOA
#define RELAY_ESC_SIDE_ON_Pin GPIO_PIN_9

96
Core/Inc/state_machine.h Normal file
View File

@ -0,0 +1,96 @@
#ifndef INC_STATE_MACHINE_H
#define INC_STATE_MACHINE_H
#include <stdint.h>
#include <stdbool.h>
#include "ADBMS_LL_Driver.h"
#include "AMS_HighLevel.h"
#include "errors.h"
#include "PWM_control.h"
#include "TMP1075.h"
#include <math.h>
// Minimum vehicle side voltage to exit precharge
#define MIN_VEHICLE_SIDE_VOLTAGE 150000 // mV
// Time to wait after reaching 95% of battery voltage before exiting precharge
// Set this to 1000 in scruti to demonstrate the voltage on the multimeter
#define PRECHARGE_95_DURATION 0 // ms
// Time to wait for discharge
#define DISCHARGE_DURATION 5000 // ms
// Time to wait after there is no more error condition before exiting TS_ERROR
#define NO_ERROR_TIME 1000 // ms
// Time to wait for charger voltage before going to TS_ERROR
#define MAX_CHARGING_CHECK_DURATION 2000 // ms
// Time to wait between closing relays
#define RELAY_CLOSE_WAIT 10 // ms
#warning
typedef enum { // states -> 3 bit. valid transitions: (all could transition to error)
STATE_INACTIVE, // INACTIVE -> PRECHARGE, CHARGING, ERROR
STATE_PRECHARGE, // PRECHARGE -> INACTIVE, READY, DISCHARGE, ERROR
STATE_READY, // READY -> ACTIVE, DISCHARGE, ERROR
STATE_ACTIVE, // ACTIVE -> READY, DISCHARGE, ERROR
STATE_DISCHARGE, // DISCHARGE -> INACTIVE, PRECHARGE, ERROR
STATE_CHARGING_PRECHARGE,
STATE_CHARGING, // CHARGING -> INACTIVE, DISCHARGE, ERROR
STATE_ERROR, // ERROR -> INACTIVE, DISCHARGE, ERROR
} State;
typedef struct {
uint16_t bms_timeout : 1;
uint16_t bms_fault : 1;
uint16_t temperature_error : 1;
uint16_t current_error : 1;
uint16_t current_sensor_missing : 1;
uint16_t voltage_error : 1;
uint16_t voltage_missing : 1;
uint16_t state_transition_fail : 1;
} ErrorKind;
//typedef enum {} WarningKind;
typedef struct {
State current_state;
State target_state;
uint16_t error_source; // TSErrorSource (bitmask)
ErrorKind error_type; // TSErrorKind
} StateHandle;
extern StateHandle state;
static bool relay_closed = 0;
static bool precharge_closed = 0;
extern int16_t RELAY_BAT_SIDE_VOLTAGE;
extern int16_t RELAY_ESC_SIDE_VOLTAGE;
extern int16_t CURRENT_MEASUREMENT;
extern uint8_t powerground_status;
void sm_init();
void sm_update();
State sm_update_inactive();
State sm_update_precharge();
State sm_update_ready();
State sm_update_active();
State sm_update_discharge();
State sm_update_charging_precharge();
State sm_update_charging();
State sm_update_error();
typedef enum { RELAY_MAIN, RELAY_PRECHARGE } Relay;
void sm_set_relay_positions(State state);
void sm_set_relay(Relay relay, bool closed);
void sm_check_charging();
void sm_check_battery_temperature(int8_t* id, int16_t* temp);
int16_t sm_return_cell_temperature(int id);
int16_t sm_return_cell_voltage(int id);
void sm_handle_ams_in(const uint8 *data);
void sm_check_errors();
void sm_set_error(ErrorKind error_kind, bool is_errored);
void sm_test_cycle_states();
#endif /* "INC_STATE_MACHINE_H" */

View File

@ -81,7 +81,7 @@
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
#define HSE_VALUE ((uint32_t)16000000) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
/**

View File

@ -55,6 +55,8 @@ void SVC_Handler(void);
void DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
void USB_LP_CAN_RX0_IRQHandler(void);
void CAN_RX1_IRQHandler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */