Compare commits

..

1 Commits

Author SHA1 Message Date
Kilian Bracher c5c4184d6b balancing update 2024-07-08 17:50:17 +02:00
40 changed files with 11426 additions and 4969 deletions

File diff suppressed because one or more lines are too long

View File

@ -1,110 +0,0 @@
V1.0
- merged mvbms-test to main
- made the changes needed for the project to compile
V1.1
- changed PWM settings in mxcube for ESC_L/R_PWM
- add pwm_calibrate_powerground
- precharge and discharge are now timer dependent instead of voltage dependent
- remove the transitions (precharge -> discharge) to stop weird interactions
V1.2
- change auxvoltages and cellvoltages to float to achieve higher precision
- added void sm_calibrate_powerground(); void sm_precharge_discharge_manager();
- fixed the clock in mxcube
- cleaned up PWM_powerground_control()
- cleaned up the state machine
V1.3
- added eeprom.h and eeprom.c, is still WIP
- void sm_check_charging(); was removed, you need to call 0xF1XX to enter charging mode, precharge is then 3 seconds then the relay closes. call 0x0000 to exit charging
- removed some variables and some functions
V1.4
- replaced ADBMS code with the newest version from the Slaves
- added the Author to things i made
- error_source is now set in the state_machine.c
V1.5
- int16_t auxVoltages[MAXIMUM_AUX_VOLTAGES] to float
- errors out when no messages are recieved for CAN_TIMEOUT messages
- void set_error_source(int source); -> void set_error_source(SlaveErrorKind source);
V1.6
- set temperature limit to 59
- precharge and discharge durations are now 5 seconds
- RELAY_BAT/ESC_SIDE and CURRENT_MEASUREMENT to int32_t
- CAN messages are now correctly formated
- minimum cell voltage is now set to 3200 mV
- powerground calibration is now done in STATE_PRECHARGE (well yes but actually no)
V1.7
- added eeprom functions
- fixed(tm) voltage and CURRENT_MEASUREMENT
- changed the CAN message a bit
- added soc_estimation.c soc_estimation.h
- added MIN/MAX_CELL_VOLTAGE for AMS_HighLevel
- cleaned up state_machine code
- changed the format of the CAN message.
V1.8
- removed macros from can.h
- added documentation to PWM_control.h
- the MVBMS only reacts to messages if they are different from the previous message
- powerground calibration now starts at STATE_PRECHARGE
- moved header files from state_machine.c to h
- added status_LED.c, changed the ioc file accordingly
V1.9
- switched ~CSB and ~WC to high speed GPIO
- cleaned up the includes in most files
- wrote some code for the eeprom
V1.10
- PWM_control now has some macros and the method PWM_powerground_softcontrol()
- added void sm_powerground_manager() to state_machine.c
V1.11
- added can_handle_dump() to dump the logging data from the EEPROM to CAN
- rewrote eeprom_read() and eeprom_write
- added void sm_program_powerground() and void sm_eeprom_write_status()
-
V1.12
- added some TODOs as warnings
- added AMS_Balancing_Loop() to AMS_HighLevel
- added current_soc to logging data
- removed void sm_balancing() (the AMS should do it automatically if we set it to charging state)
- changed the colors for the states in status_LED
V1.13
- moved macros and libraries from eeprom.c to h
- added can.h to state_machine.h
- added balancing to AMS_HighLevel.c (hopefully)
- fixed can_handle_dump()
V1.14
- added programming mode to program the ESCs
- removed void status_led_blink_sequence(uint8_t blinks, color color) and added proper blinking
- fixed the bit shift of temperature in the can message
- moved tmp1075_measure() and can_handle_send_status() to the state_machine
V1.15
- changed max temperature to 55 from 60 according to the data sheet of the cell
- changed ocv_soc_pairs to something close to the curve of other swaytronics batteries
- the can messages uses roundf to round the values
- made the pwm spool up in 300ms
- increased MIN_CELL_VOLTAGE
- the STM32 wait 1s for the BMS to finish its measurements
- added debugging mode (turns off error checking)
- added and ERROR_LATCH_TIME
- added different blink speeds for different states
V1.16
- TIME_BLINK_SLOW: 1000 -> 2000
- moved can.c timers to can.h to detec
- added logging of cells on can ID 0x503
- eeprom gets initialized in main
- startup delay is now 500ms
- removed a zero from ocv_soc_pairs
- changed precharge and discharge timers to 8000ms

2
Core/Inc/ADBMS_Abstraction.h Executable file → Normal file
View File

@ -47,7 +47,7 @@ struct ADBMS6830_Internal_Status {
typedef struct {
int16_t cellVoltages[MAXIMUM_CELL_VOLTAGES];
float auxVoltages[MAXIMUM_AUX_VOLTAGES];
int16_t auxVoltages[MAXIMUM_AUX_VOLTAGES];
struct ADBMS6830_Internal_Status status;
uint16 internalDieTemp;

0
Core/Inc/ADBMS_CMD_MAKROS.h Executable file → Normal file
View File

4
Core/Inc/ADBMS_LL_Driver.h Executable file → Normal file
View File

@ -27,8 +27,8 @@ uint8 calculateDataPEC(uint8* data, uint8 datalen);
uint16 updateDataPEC(uint16 currentPEC, uint8 din);
uint8 checkDataPEC(uint8* data, uint8 datalen);
[[gnu::access(read_only, 2, 3)]] uint8 writeCMD(uint16 command, const uint8* args, uint8 arglen);
[[gnu::access(write_only, 2, 3)]] uint8 readCMD(uint16 command, uint8* buffer, uint8 buflen);
uint8 writeCMD(uint16 command, uint8* args, uint8 arglen);
uint8 readCMD(uint16 command, uint8* buffer, uint8 buflen);
uint8 pollCMD(uint16 command);
void mcuAdbmsCSLow();

14
Core/Inc/AMS_HighLevel.h Executable file → Normal file
View File

@ -11,10 +11,12 @@
#include "ADBMS_Abstraction.h"
#include "ADBMS_CMD_MAKROS.h"
#include "ADBMS_LL_Driver.h"
#include "can.h"
#include "TMP1075.h"
#include "can-halal.h"
#include "errors.h"
#include "stm32f3xx_hal.h"
#include <stdbool.h>
#include <stdint.h>
typedef enum {
AMSDEACTIVE,
@ -29,7 +31,11 @@ typedef enum {
extern amsState currentAMSState;
extern Cell_Module module;
extern uint32_t balancedCells;
extern bool BalancingActive;
extern uint8_t BalancingActive;
extern uint8_t stateofcharge;
extern uint8_t amserrorcode;
extern uint8_t amswarningcode;
extern uint8_t numberofCells;
extern uint8_t numberofAux;
@ -44,4 +50,8 @@ uint8_t AMS_Error_Loop();
uint8_t AMS_Charging_Loop();
uint8_t AMS_Discharging_Loop();
uint8_t writeWarningLog(uint8_t warningCode);
uint8_t writeErrorLog(uint8_t errorCode);
uint8_t integrateCurrent();
#endif /* INC_AMS_HIGHLEVEL_H_ */

View File

@ -1,21 +1,15 @@
/*
* PWM_control.h
*
* Created on: 07.07.2024
* Author: Hamza
*/
#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))
(ARR + 1) * (PSC + 1) = (F_CLK)/(F_PWM)
(PSC + 1) = (F_CLK)/(F_PWM * (ARR + 1))
F_CLK = 16 MHz
@ -25,21 +19,14 @@ DUTY CYCLE = 1/20 -> 0%, DUTY CYCLE = 2/20 -> 100%
CCR * DUTY_CYCLE
CCR: 1/20 -> 500, 2/20 -> 1000
*/
// UNUSED
#define POWERGROUND_FREQ 50
#define POWERGROUND_PRESCALER 7
#define POWERGROUND_ARR 39999
#define POWERGROUND_MIN_DUTY_CYCLE 0.05
#define POWERGROUND_MAX_DUTY_CYCLE 0.1
//#define BATTERY_COOLING_FREQ 20000
extern uint8_t current_powerground_status;
extern uint8_t target_powerground_status;
void PWM_control_init(TIM_HandleTypeDef* powerground, TIM_HandleTypeDef* battery_cooling);
void PWM_control_init(TIM_HandleTypeDef* pg, TIM_HandleTypeDef* bat_cool, TIM_HandleTypeDef* esc_cool);
void PWM_powerground_softcontrol();
void PWM_powerground_control(uint8_t percent);
void PWM_battery_cooling_control(uint8_t percent);
void PWM_set_throttle();
#endif /* INC_CHANNEL_CONTROL_H */

View File

@ -1,14 +1,14 @@
#ifndef INC_TMP1075_H_
#define INC_TMP1075_H_
#include "can.h"
#include "common_defs.h"
#include "stm32f3xx_hal.h"
#include "TMP1075.h"
#include "can-halal.h"
#include "errors.h"
#include <stdint.h>
#define N_CELLS 13
#define N_TEMP_SENSORS 13
extern uint32_t tmp1075_failed_sensors;
extern int16_t tmp1075_temps[N_TEMP_SENSORS];

View File

@ -1,26 +1,20 @@
/*
* can.h
*
* Created on: 07.07.2024
* Author: Hamza
*/
#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>
extern uint32_t can_status_timer, can_log_timer, can_timeout_timer;
#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_send_log();
void can_handle_dump();
void can_handle_recieve_command(const uint8_t *data);

14
Core/Inc/common_defs.h Normal file
View File

@ -0,0 +1,14 @@
/*
* common_defs.h
*
* Created on: 23 Mar 2022
* Author: Jasper
*/
#ifndef INC_COMMON_DEFS_H_
#define INC_COMMON_DEFS_H_
#define N_CELLS 12
#define N_TEMP_SENSORS 12
#endif /* INC_COMMON_DEFS_H_ */

View File

@ -1,33 +0,0 @@
/*
* PWM_control.h
*
* Created on: 10.07.2024
* Author: Hamza
*/
#ifndef INC_EEPROM_H_
#define INC_EEPROM_H_
#include <stm32f3xx_hal.h>
#include "ADBMS_LL_Driver.h"
#include "soc_estimation.h"
#include <state_machine.h>
#include "stm32f3xx_hal_def.h"
#include "stm32f3xx_hal_i2c.h"
#include "TMP1075.h"
// see Datasheet for these values
#define EEPROM_I2C_ADDR 0xA4 // 0xA4 for the the first 2⁸ addresses and 0xA6 for the the last 2⁸ addresses
#define EERROM_MEMORY_ADDR_SIZE 2 // it is controlled by A17 in the address Byte, see datasheet
#define EEPROM_MEMORY_SIZE 131072 // in bytes
#define EEPROM_PAGE_SIZE 32 // in bytes
extern uint32_t write_address, read_address;
void eeprom_init(I2C_HandleTypeDef* hi2c);
void eeprom_write_status();
HAL_StatusTypeDef eeprom_read(uint8_t* data, uint16_t data_length);
HAL_StatusTypeDef eeprom_write(uint8_t* data, uint16_t data_length);
#endif // INC_EEPROM_H_

View File

@ -12,7 +12,7 @@
#define ERROR_TIME_THRESH 150 // ms
typedef enum : uint16_t {
typedef enum {
SEK_OVERTEMP = 0x0,
SEK_UNDERTEMP = 0x1,
SEK_OVERVOLT = 0x2,
@ -27,7 +27,7 @@ typedef enum : uint16_t {
} SlaveErrorKind;
typedef struct {
uint16_t error_sources;
int error_sources;
SlaveErrorKind data_kind;
uint8_t data[4];
uint32_t errors_since;
@ -35,7 +35,7 @@ typedef struct {
extern SlaveErrorData error_data;
void set_error_source(SlaveErrorKind source);
void clear_error_source(SlaveErrorKind source);
void set_error_source(int source);
void clear_error_source(int source);
#endif // INC_ERRORS_H

View File

@ -59,40 +59,32 @@ void Error_Handler(void);
/* USER CODE END EFP */
/* Private defines -----------------------------------------------------------*/
#define RELAY_EN_Pin GPIO_PIN_0
#define RELAY_EN_GPIO_Port GPIOA
#define _60V_EN_Pin GPIO_PIN_1
#define _60V_EN_GPIO_Port GPIOA
#define PWM_PG_FAN1_Pin GPIO_PIN_2
#define PWM_PG_FAN1_GPIO_Port GPIOA
#define PWM_PG_FAN2_Pin GPIO_PIN_3
#define PWM_PG_FAN2_GPIO_Port GPIOA
#define CSB_Pin GPIO_PIN_4
#define CSB_GPIO_Port GPIOA
#define ESC_L_PWM_Pin GPIO_PIN_0
#define ESC_L_PWM_GPIO_Port GPIOB
#define ESC_R_PWM_Pin GPIO_PIN_1
#define ESC_R_PWM_GPIO_Port GPIOB
#define BAT_COOLING_PWM_Pin GPIO_PIN_10
#define BAT_COOLING_PWM_GPIO_Port GPIOB
#define BAT_COOLING_ENABLE_Pin GPIO_PIN_11
#define BAT_COOLING_ENABLE_GPIO_Port GPIOB
#define ESC_COOLING_ENABLE_Pin GPIO_PIN_14
#define ESC_COOLING_ENABLE_GPIO_Port GPIOB
#define ESC_COOLING_PWM_Pin GPIO_PIN_15
#define ESC_COOLING_PWM_GPIO_Port GPIOB
#define EEPROM___WC__Pin GPIO_PIN_8
#define EEPROM___WC__GPIO_Port GPIOA
#define EEPROM_SCL_Pin GPIO_PIN_9
#define EEPROM_SCL_GPIO_Port GPIOA
#define EEPROM_SDA_Pin GPIO_PIN_10
#define EEPROM_SDA_GPIO_Port GPIOA
#define TMP_SCL_Pin GPIO_PIN_15
#define TMP_SCL_GPIO_Port GPIOA
#define RELAY_ENABLE_Pin GPIO_PIN_4
#define RELAY_ENABLE_GPIO_Port GPIOB
#define PRECHARGE_ENABLE_Pin GPIO_PIN_5
#define PRECHARGE_ENABLE_GPIO_Port GPIOB
#define STATUS_LED_R_Pin GPIO_PIN_6
#define STATUS_LED_R_Pin GPIO_PIN_0
#define STATUS_LED_R_GPIO_Port GPIOB
#define STATUS_LED_G_Pin GPIO_PIN_7
#define STATUS_LED_G_GPIO_Port GPIOB
#define STATUS_LED_B_Pin GPIO_PIN_8
#define STATUS_LED_B_Pin GPIO_PIN_1
#define STATUS_LED_B_GPIO_Port GPIOB
#define TMP_SDA_Pin GPIO_PIN_9
#define TMP_SDA_GPIO_Port GPIOB
#define STATUS_LED_G_Pin GPIO_PIN_2
#define STATUS_LED_G_GPIO_Port GPIOB
#define PRECHARGE_EN_Pin GPIO_PIN_11
#define PRECHARGE_EN_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
#define RELAY_ESC_SIDE_ON_GPIO_Port GPIOA
#define CURRENT_SENSOR_ON_Pin GPIO_PIN_10
#define CURRENT_SENSOR_ON_GPIO_Port GPIOA
/* USER CODE BEGIN Private defines */

View File

@ -1,21 +0,0 @@
#ifndef INC_SOC_ESTIMATION_H
#define INC_SOC_ESTIMATION_H
#include "state_machine.h"
#include "stm32f3xx_hal.h"
#include <stddef.h>
#include <stdint.h>
extern float current_soc;
void soc_init();
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

@ -1,26 +1,30 @@
/*
* state_machine.h
*
* Created on: 07.07.2024
* Author: Hamza
*/
#ifndef INC_STATE_MACHINE_H
#define INC_STATE_MACHINE_H
#include "ADBMS_LL_Driver.h"
#include <AMS_HighLevel.h>
#include <can.h>
#include <eeprom.h>
#include <errors.h>
#include <PWM_control.h>
#include <status_LED.h>
#include <TMP1075.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
@ -33,6 +37,7 @@ typedef enum { // states -> 3 bit. valid transitions: (all could t
} State;
typedef struct {
uint16_t bms_timeout : 1;
uint16_t bms_fault : 1;
uint16_t temperature_error : 1;
@ -41,8 +46,7 @@ typedef struct {
uint16_t voltage_error : 1;
uint16_t voltage_missing : 1;
uint16_t state_transition_fail : 1;
uint16_t eeprom_error : 1;
uint16_t : 7; // padding
} ErrorKind;
//typedef enum {} WarningKind;
@ -54,27 +58,17 @@ typedef struct {
ErrorKind error_type; // TSErrorKind
} StateHandle;
typedef enum { RELAY_MAIN, RELAY_PRECHARGE } Relay;
extern StateHandle state;
extern bool programming_mode;
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;
extern int32_t RELAY_BAT_SIDE_VOLTAGE;
extern int32_t RELAY_ESC_SIDE_VOLTAGE;
extern int32_t CURRENT_MEASUREMENT;
void sm_init();
void sm_update();
void sm_handle_ams_in(const uint8 *data);
void sm_precharge_discharge_manager();
void sm_powerground_manager();
void sm_calibrate_powerground();
void sm_balancing();
void sm_eeprom_write_status();
void sm_program_powerground();
void sm_check_errors();
void sm_set_error_source();
State sm_update_inactive();
State sm_update_precharge();
@ -85,14 +79,18 @@ 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);
void sm_check_battery_temperature(uint8_t* id, uint16_t* temp);
void sm_check_battery_voltage(uint8_t* id, uint16_t* voltage);
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

@ -1,31 +0,0 @@
/*
* status_LED.h
*
* Created on: 07.07.2024
* Author: Hamza
*/
#ifndef INC_STATUS_LED_H
#define INC_STATUS_LED_H
#include "stm32f3xx_hal.h"
#include <state_machine.h>
typedef enum {
OFF,
RED,
GREEN,
BLUE,
YELLOW,
PINK,
CYAN,
WHITE
} color;
void status_led_init(TIM_HandleTypeDef* r, TIM_HandleTypeDef* g, TIM_HandleTypeDef* b);
void status_led_update();
void status_led_set_color(color color);
void status_led_set(uint8_t r, uint8_t g, uint8_t b);
#endif /* "INC_STATUS_LED_H" */

View File

@ -58,7 +58,7 @@
/*#define HAL_RTC_MODULE_ENABLED */
#define HAL_SPI_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 */

9
Core/Src/ADBMS_Abstraction.c Executable file → Normal file
View File

@ -28,7 +28,7 @@ uint8 amsReset() {
amsStopBalancing();
amsConfigOverUnderVoltage(DEFAULT_OV, DEFAULT_UV);
const uint8 buffer[6] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF};
uint8 buffer[6] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF};
CHECK_RETURN(writeCMD(CLRFLAG, buffer, 6)); //clear flags,
CHECK_RETURN(writeCMD(CLOVUV, buffer, 6)); //OVUV flags
@ -131,7 +131,6 @@ uint8 amsAuxAndStatusMeasurement(Cell_Module* module) {
uint8 amsConfigBalancing(uint32 channels, uint8 dutyCycle) {
uint8 buffer_a[PWM_GROUP_A_SIZE] = {};
uint8 buffer_b[PWM_GROUP_B_SIZE] = {};
CHECK_RETURN(writeCMD(ADCV | ADCV_CONT, NULL, 0)); //start continuous cell voltage measurement with redundancy
CHECK_RETURN(readCMD(RDPWMA, buffer_a, PWM_GROUP_A_SIZE));
CHECK_RETURN(readCMD(RDPWMB, buffer_b, PWM_GROUP_B_SIZE));
@ -202,11 +201,13 @@ uint8 amsCheckUnderOverVoltage(Cell_Module* module) {
}
uint8 amsClearAux() {
return writeCMD(CLRAUX, NULL, 0);
uint8 buffer[6];
return writeCMD(CLRAUX, buffer, 0);
}
uint8 amsClearCells() {
return writeCMD(CLRCELL, NULL, 0);
uint8 buffer[6];
return writeCMD(CLRCELL, buffer, 0);
}
uint8 amsReadCellVoltages(Cell_Module* module) {

81
Core/Src/ADBMS_LL_Driver.c Executable file → Normal file
View File

@ -6,6 +6,7 @@
*/
#include "ADBMS_LL_Driver.h"
#include <stdbool.h>
#define INITIAL_COMMAND_PEC 0x0010
#define INITIAL_DATA_PEC 0x0010
@ -31,7 +32,7 @@ uint8 calculateCommandPEC(uint8_t* data, uint8_t datalen) {
if (datalen >= 3) {
for (int i = 0; i < (datalen - 2); i++) {
for (int n = 0; n < 8; n++) {
const uint8 din = data[i] << (n);
uint8 din = data[i] << (n);
currentpec = updateCommandPEC(currentpec, din);
}
}
@ -53,13 +54,13 @@ uint8 checkCommandPEC(uint8* data, uint8 datalen) {
for (int i = 0; i < (datalen - 2); i++) {
for (int n = 0; n < 8; n++) {
const uint8 din = data[i] << (n);
uint8 din = data[i] << (n);
currentpec = updateCommandPEC(currentpec, din);
}
}
const uint8 pechigh = (currentpec >> 7) & 0xFF;
const uint8 peclow = (currentpec << 1) & 0xFF;
uint8 pechigh = (currentpec >> 7) & 0xFF;
uint8 peclow = (currentpec << 1) & 0xFF;
if ((pechigh == data[datalen - 2]) && (peclow == data[datalen - 1])) {
return 0;
@ -70,13 +71,13 @@ uint8 checkCommandPEC(uint8* data, uint8 datalen) {
uint16 updateCommandPEC(uint16 currentPEC, uint8 din) {
din = (din >> 7) & 0x01;
const uint8 in0 = din ^ ((currentPEC >> 14) & 0x01);
const uint8 in3 = in0 ^ ((currentPEC >> 2) & 0x01);
const uint8 in4 = in0 ^ ((currentPEC >> 3) & 0x01);
const uint8 in7 = in0 ^ ((currentPEC >> 6) & 0x01);
const uint8 in8 = in0 ^ ((currentPEC >> 7) & 0x01);
const uint8 in10 = in0 ^ ((currentPEC >> 9) & 0x01);
const uint8 in14 = in0 ^ ((currentPEC >> 13) & 0x01);
uint8 in0 = din ^ ((currentPEC >> 14) & 0x01);
uint8 in3 = in0 ^ ((currentPEC >> 2) & 0x01);
uint8 in4 = in0 ^ ((currentPEC >> 3) & 0x01);
uint8 in7 = in0 ^ ((currentPEC >> 6) & 0x01);
uint8 in8 = in0 ^ ((currentPEC >> 7) & 0x01);
uint8 in10 = in0 ^ ((currentPEC >> 9) & 0x01);
uint8 in14 = in0 ^ ((currentPEC >> 13) & 0x01);
uint16 newPEC = 0;
@ -103,9 +104,9 @@ uint16 updateCommandPEC(uint16 currentPEC, uint8 din) {
//CRC-10
//x^10 + x^7 + x^3 + x^2 + x + 1
uint16_t pec10_calc(bool rx_cmd, int len, const uint8_t* data) {
uint16_t remainder = 16; /* PEC_SEED; 0000010000 */
const uint16_t polynom = 0x8F; /* x10 + x7 + x3 + x2 + x + 1 <- the CRC15 polynomial
uint16_t pec10_calc(bool rx_cmd, int len, uint8_t* data) {
uint16_t remainder = 16; /* PEC_SEED; 0000010000 */
uint16_t polynom = 0x8F; /* x10 + x7 + x3 + x2 + x + 1 <- the CRC15 polynomial
100 1000 1111 48F */
/* Perform modulo-2 division, a byte at a time. */
@ -149,13 +150,16 @@ crc F_CRC_CalculaCheckSum(uint8_t const AF_Datos[], uint16_t VF_nBytes);
uint8 calculateDataPEC(uint8_t* data, uint8_t datalen) {
if (datalen >= 3) {
const crc currentpec = pec10_calc(true, datalen - 2, data) & 0x3FF; // mask to 10 bits
crc currentpec = pec10_calc(true, datalen - 2, data) & 0x3FF; // mask to 10 bits
// memory layout is [[zeroes], PEC[9:8]], [PEC[7:0]]
data[datalen - 2] = (currentpec >> 8) & 0xFF;
data[datalen - 1] = currentpec & 0xFF;
volatile uint8 result = pec10_calc(true, datalen, data);
return 0;
} else {
return 1;
@ -167,7 +171,7 @@ uint8 checkDataPEC(uint8* data, uint8 len) {
return 255;
}
const crc currentpec = F_CRC_CalculaCheckSum(data, len);
crc currentpec = F_CRC_CalculaCheckSum(data, len);
return (currentpec == 0) ? 0 : 1;
}
@ -209,10 +213,10 @@ crc F_CRC_CalculaCheckSum(uint8_t const AF_Datos[], uint16_t VF_nBytes) {
uint16 updateDataPEC(uint16 currentPEC, uint8 din) {
din = (din >> 7) & 0x01;
const uint8 in0 = din ^ ((currentPEC >> 9) & 0x01);
const uint8 in2 = in0 ^ ((currentPEC >> 1) & 0x01);
const uint8 in3 = in0 ^ ((currentPEC >> 2) & 0x01);
const uint8 in7 = in0 ^ ((currentPEC >> 6) & 0x01);
uint8 in0 = din ^ ((currentPEC >> 9) & 0x01);
uint8 in2 = in0 ^ ((currentPEC >> 1) & 0x01);
uint8 in3 = in0 ^ ((currentPEC >> 2) & 0x01);
uint8 in7 = in0 ^ ((currentPEC >> 6) & 0x01);
uint16 newPEC = 0;
@ -229,7 +233,7 @@ uint16 updateDataPEC(uint16 currentPEC, uint8 din) {
return newPEC;
}
uint8 writeCMD(uint16 command, const uint8 * args, uint8 arglen) {
uint8 writeCMD(uint16 command, uint8* args, uint8 arglen) {
uint8 ret;
if (arglen > 0) {
uint8 buffer[6 + arglen]; //command + PEC (2 bytes) + data + DPEC (2 bytes)
@ -263,9 +267,23 @@ uint8 writeCMD(uint16 command, const uint8 * args, uint8 arglen) {
return ret;
}
uint8 readCMD(uint16 command, uint8 * buffer, uint8 buflen) {
uint8 txbuffer[6 + buflen];
uint8 rxbuffer[6 + buflen];
#define ITER_COUNT 50
static uint8_t count = 0;
static bool isOn = false;
uint8 readCMD(uint16 command, uint8* buffer, uint8 buflen) {
if (count == ITER_COUNT) {
HAL_GPIO_WritePin(STATUS_LED_B_GPIO_Port, STATUS_LED_B_Pin, isOn ? GPIO_PIN_SET : GPIO_PIN_RESET);
count = 0;
isOn = !isOn;
} else {
count++;
}
uint8 txbuffer[6 + buflen] = {};
uint8 rxbuffer[6 + buflen] = {};
txbuffer[0] = (command >> 8) & 0xFF;
txbuffer[1] = (command)&0xFF;
@ -318,22 +336,25 @@ void mcuAdbmsCSHigh() {
}
uint8 mcuSPITransmit(uint8* buffer, uint8 buffersize) {
uint8 rxbuf[buffersize];
const HAL_StatusTypeDef status = HAL_SPI_TransmitReceive(adbmsspi, buffer, rxbuf, buffersize,
ADBMS_SPI_TIMEOUT);
HAL_StatusTypeDef status;
uint8 rxbuf[buffersize];
status = HAL_SPI_TransmitReceive(adbmsspi, buffer, rxbuf, buffersize,
ADBMS_SPI_TIMEOUT);
__HAL_SPI_CLEAR_OVRFLAG(adbmsspi);
return status;
}
uint8 mcuSPIReceive(uint8* buffer, uint8 buffersize) {
const HAL_StatusTypeDef status = HAL_SPI_Receive(adbmsspi, buffer, buffersize, ADBMS_SPI_TIMEOUT);
HAL_StatusTypeDef status;
status = HAL_SPI_Receive(adbmsspi, buffer, buffersize, ADBMS_SPI_TIMEOUT);
return status;
}
uint8 mcuSPITransmitReceive(uint8* rxbuffer, uint8* txbuffer,
uint8 buffersize) {
const HAL_StatusTypeDef status = HAL_SPI_TransmitReceive(adbmsspi, txbuffer, rxbuffer, buffersize,
ADBMS_SPI_TIMEOUT);
HAL_StatusTypeDef status;
status = HAL_SPI_TransmitReceive(adbmsspi, txbuffer, rxbuffer, buffersize,
ADBMS_SPI_TIMEOUT);
return status;
}

185
Core/Src/AMS_HighLevel.c Executable file → Normal file
View File

@ -6,27 +6,36 @@
*/
#include "AMS_HighLevel.h"
#include "ADBMS_LL_Driver.h"
#include <stdint.h>
Cell_Module module = {};
uint32_t balancedCells = 0;
bool balancingActive = false;
uint8_t BalancingActive = 0;
uint8_t stateofcharge = 100;
int64_t currentintegrator = 0;
uint32_t lastticks = 0;
uint32_t currenttick = 0;
uint8_t eepromconfigured = 0;
uint8_t internalbalancingalgo = 1;
uint16_t startbalancingthreshold = 41000;
uint16_t stopbalancingthreshold = 30000;
uint16_t balancingvoltagedelta = 10;
uint16_t amsuv = 0;
uint16_t amsov = 0;
uint8_t numberofCells = 13;
uint8_t amserrorcode = 0;
uint8_t amswarningcode = 0;
uint8_t numberofCells = 14;
uint8_t numberofAux = 0;
uint8_t packetChecksumFails = 0;
#define MAX_PACKET_CHECKSUM_FAILS 5
uint8_t deviceSleeps = 0;
#define MAX_DEVICE_SLEEP 3 //TODO: change to correct value
#define MAX_CELL_VOLTAGE 4200 //change to 4200
#define MIN_CELL_VOLTAGE 3200 //change to 3000
#define CELL_VOLTAGE_DIFF_BALANCING 20 //max difference between lowest cell and any other cell
#define MAX_DEVICE_SLEEP 3 //TODO: change to correct value
amsState currentAMSState = AMSDEACTIVE;
amsState lastAMSState = AMSDEACTIVE;
@ -39,9 +48,18 @@ struct pollingTimes {
struct pollingTimes pollingTimes = {0, 0};
void AMS_Init(SPI_HandleTypeDef* hspi) {
initAMS(hspi, numberofCells, numberofAux);
amsov = DEFAULT_OV;
amsuv = DEFAULT_UV;
if (eepromconfigured == 1) {
/*amsov = eepromcellovervoltage>>4;
amsuv = (eepromcellundervoltage-1)>>4;
numberofCells = eepromnumofcells;
numberofAux = eepromnumofaux;
initAMS(hspi, eepromnumofcells, eepromnumofaux);*/
amsConfigOverUnderVoltage(amsov, amsuv);
} else {
initAMS(hspi, numberofCells, numberofAux);
amsov = DEFAULT_OV;
amsuv = DEFAULT_UV;
}
pollingTimes = (struct pollingTimes) {HAL_GetTick(), HAL_GetTick()};
@ -65,8 +83,10 @@ void AMS_Loop() {
case AMSDISCHARGING:
break;
case AMSWARNING:
writeWarningLog(0x01);
break;
case AMSERROR:
writeErrorLog(amserrorcode);
break;
}
lastAMSState = currentAMSState;
@ -81,7 +101,6 @@ void AMS_Loop() {
case AMSDEACTIVE:
break;
case AMSCHARGING:
AMS_Idle_Loop();
break;
case AMSIDLEBALANCING:
AMS_Idle_Loop();
@ -98,8 +117,8 @@ void AMS_Loop() {
uint8_t AMS_Idle_Loop() {
if (!amsWakeUp()) {
error_data.data_kind = SEK_INTERNAL_BMS_TIMEOUT; //we don't receive data for the wakeup command
set_error_source(ERROR_SOURCE_INTERNAL); //so we can't tell if we timed out
//error_data.data_kind = SEK_INTERNAL_BMS_TIMEOUT;
//set_error_source(ERROR_SOURCE_INTERNAL);
}
packetChecksumFails += amsAuxAndStatusMeasurement(&module);
@ -128,21 +147,24 @@ uint8_t AMS_Idle_Loop() {
packetChecksumFails += amsCellMeasurement(&module);
packetChecksumFails += amsCheckUnderOverVoltage(&module);
packetChecksumFails += integrateCurrent();
if (packetChecksumFails > MAX_PACKET_CHECKSUM_FAILS) {
error_data.data_kind = SEK_INTERNAL_BMS_CHECKSUM_FAIL;
set_error_source(ERROR_SOURCE_INTERNAL);
}
tmp1075_measure();
int any_voltage_error = 0;
for (size_t i = 0; i < numberofCells; i++) {
if (module.cellVoltages[i] < MIN_CELL_VOLTAGE) {
if (module.cellVoltages[i] < 2500) {
any_voltage_error = 1;
error_data.data_kind = SEK_UNDERVOLT;
error_data.data[0] = i;
uint8_t* ptr = &error_data.data[1];
ptr = ftcan_marshal_unsigned(ptr, module.cellVoltages[i], 2);
} else if (module.cellVoltages[i] > MAX_CELL_VOLTAGE) {
} else if (module.cellVoltages[i] > 4200) {
any_voltage_error = 1;
error_data.data_kind = SEK_OVERVOLT;
error_data.data[0] = i;
@ -168,15 +190,26 @@ uint8_t AMS_Idle_Loop() {
}
mcuDelay(10);
if ((module.overVoltage | module.underVoltage)) {
}
return 0;
}
uint8_t AMS_Warning_Loop() { return 0; }
uint8_t AMS_Warning_Loop() {
amsWakeUp();
amsConfigOverUnderVoltage(amsov, amsuv);
amsClearAux();
amsCellMeasurement(&module);
amsAuxAndStatusMeasurement(&module);
amsCheckUnderOverVoltage(&module);
if (!(module.overVoltage | module.underVoltage)) {
currentAMSState = AMSIDLE;
// amsClearWarning();
}
amsStopBalancing();
return 0;
}
uint8_t AMS_Error_Loop() { return 0; }
@ -185,28 +218,96 @@ uint8_t AMS_Charging_Loop() { return 0; }
uint8_t AMS_Discharging_Loop() { return 0; }
uint8_t AMS_Balancing_Loop() {
AMS_Idle_Loop();
uint8_t id_cell_lowest_voltage = 0;
uint8_t num_of_cells_to_balance = 0;
for (int i = 0; i < 13; i++) {
if (module.cellVoltages[i] < module.cellVoltages[id_cell_lowest_voltage])
id_cell_lowest_voltage = i;
}
uint8_t balancingdone = 1;
if ((eepromconfigured == 1) && (internalbalancingalgo == 1) &&
(module.internalDieTemp <
28000 /*Thermal Protection 93°C*/)) // If the EEPROM is configured and
// the internal Balancing Algorithm
// should be used
{
uint16_t highestcellvoltage = module.cellVoltages[0];
uint16_t lowestcellvoltage = module.cellVoltages[0];
uint8_t highestcell = 0;
uint8_t lowestcell = 0;
for (int i = 0; i < 13; i++) {
if (module.cellVoltages[i] - CELL_VOLTAGE_DIFF_BALANCING < module.cellVoltages[id_cell_lowest_voltage]){
amsConfigBalancing((1 << i), 0xF);
num_of_cells_to_balance++;
} else {
amsConfigBalancing((1 << i), 0x0);
for (uint8_t n = 0; n < numberofCells; n++) {
if (module.cellVoltages[n] > highestcellvoltage) {
highestcellvoltage = module.cellVoltages[n];
highestcell = n;
}
if (module.cellVoltages[n] < lowestcellvoltage) {
lowestcellvoltage = module.cellVoltages[n];
lowestcell = n;
}
}
if (currentAMSState ==
AMSCHARGING) // Balancing is only Active if the BMS is in Charging Mode
{
uint32_t channelstobalance = 0;
if (highestcellvoltage > startbalancingthreshold) {
for (uint8_t n = 0; n < numberofCells; n++) {
if (module.cellVoltages[n] > stopbalancingthreshold) {
uint16_t dv = module.cellVoltages[n] - lowestcellvoltage;
if (dv > (balancingvoltagedelta * 1000)) {
balancingdone = 0;
channelstobalance |= 1 << n;
}
}
}
}
amsConfigBalancing(channelstobalance, 0x0F);
amsStartBalancing(100);
}
else if (currentAMSState == AMSIDLEBALANCING) {
uint32_t channelstobalance = 0;
if (lowestcellvoltage <
stopbalancingthreshold) // If under Voltage of one Cell is reached
{
amsStopBalancing();
balancingdone = 1;
} else // otherwise continue with regular Balancing Algorithm
{
for (uint8_t n = 0; n < numberofCells; n++) {
uint16_t dv = module.cellVoltages[n] - lowestcellvoltage;
if (dv > balancingvoltagedelta) {
balancingdone = 0;
channelstobalance |= 1 << n;
}
}
amsConfigBalancing(channelstobalance, 0x0F);
amsStartBalancing(100);
}
}
} else {
amsStopBalancing();
balancingdone = 1;
}
return balancingdone;
}
uint8_t writeWarningLog(uint8_t warningCode) {
// eepromWriteWarningLog(warningCode);
return 0;
}
uint8_t writeErrorLog(uint8_t errorCode) {
// eepromWriteErrorLog(errorCode);
return 0;
}
uint8_t integrateCurrent() {
lastticks = currenttick;
currenttick = HAL_GetTick();
if (currenttick < lastticks) {
currentintegrator += (module.auxVoltages[0] - module.auxVoltages[2]) *
(currenttick - lastticks);
}
if (num_of_cells_to_balance == 0){
balancingActive = 0;
return 0;
}
balancingActive = 1;
amsStartBalancing(0);
return 0;
}

View File

@ -1,39 +1,27 @@
/*
* PWM_control.h
*
* Created on: 07.07.2024
* Author: Hamza
*/
#include "PWM_control.h"
#include "stm32f3xx_hal.h"
#include <stdint.h>
uint8_t battery_cooling_status;
//uint32_t powerground1_CCR, powerground2_CCR, battery_cooling_CCR;
TIM_HandleTypeDef *powerground, *battery_cooling, *esc_cooling;
TIM_HandleTypeDef* powerground, *battery_cooling;
/*
Pulse width modulation mode allows for generating a signal with a frequency determined by
the value of the TIMx_ARR register and a duty cycle determined by the value of the TIMx_CCRx register.
*/
void PWM_control_init(TIM_HandleTypeDef* pg, TIM_HandleTypeDef* bat_cool, TIM_HandleTypeDef* esc_cool){
current_powerground_status = 0;
target_powerground_status = 0;
//battery_cooling_status = 0;
void PWM_control_init(TIM_HandleTypeDef* pg, TIM_HandleTypeDef* bat_cool){
powerground_status = 0;
battery_cooling_status = 0;
powerground = pg;
battery_cooling = bat_cool;
esc_cooling = esc_cool;
// htim2 CH3,4 BAT_COOLING_PWM,ENABLE
// htim3 CH3,4 ESC_L_PWM,R_PWM
// htim4 CH1,2,3 LED R,G,B
// htim15 CH1,2 ESC_COOLING_ENABLE,PWM
HAL_TIM_PWM_Start(powerground, TIM_CHANNEL_3); //TIM3CH3
HAL_TIM_PWM_Start(powerground, TIM_CHANNEL_4); //TIM3CH4
//HAL_TIM_PWM_Start(bat_cool, TIM_CHANNEL_3); //TIM1CH3
HAL_TIM_PWM_Start(pg, TIM_CHANNEL_1); //TIM15CH1
HAL_TIM_PWM_Start(pg, TIM_CHANNEL_2); //TIM15CH2
HAL_TIM_PWM_Start(bat_cool, TIM_CHANNEL_3); //TIM1CH3
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_1, 0);
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_2, 0);
@ -43,29 +31,33 @@ void PWM_control_init(TIM_HandleTypeDef* pg, TIM_HandleTypeDef* bat_cool, TIM_Ha
}
/*
controls the duty cycle of the fans by setting the CCR of the channel
6+percent/100 = x/ARR
controls the duty cycle of the fans by setting the CCR of the channel percent/100 = x/ARR
DUTYCYCLE = 40000 * X/100
*/
void PWM_powerground_control(uint8_t percent){
if (percent > 100){ //something went wrong
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_3, 0);
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_4, 0);
current_powerground_status = target_powerground_status = 0;
if (percent > 100) //something went wrong
return;
}
current_powerground_status = target_powerground_status = percent;
powerground_status = percent;
int ccr = 2000 + (20 * percent);
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_3, ccr);
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_4, ccr);
int ccr = 2000 + ((2000) * (percent/100.0));
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_1, ccr);
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_2, ccr);
//TIM15->CCR1 = (TIM15->ARR*POWERGROUND_MAX_DUTY_CYCLE-TIM15->ARR*POWERGROUND_MIN_DUTY_CYCLE) * (percent/100.0) + TIM15->ARR*POWERGROUND_MIN_DUTY_CYCLE;
}
void PWM_powerground_softcontrol(){
int ccr = 2000 + (20 * current_powerground_status);
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_3, ccr);
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_4, ccr);
void PWM_set_throttle(){
uint32_t timestamp = HAL_GetTick() + 5000;
while (timestamp > HAL_GetTick()) {}
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_1, 4000);
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_2, 4000);
timestamp = HAL_GetTick() + 2000;
while (timestamp > HAL_GetTick()) {}
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_1, 2000);
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_2, 2000);
timestamp = HAL_GetTick() + 1000;
while (timestamp > HAL_GetTick()) {}
}
void PWM_battery_cooling_control(uint8_t percent){}
void PWM_esc_cooling(uint8_t percent){}
void PWM_battery_cooling_control(uint8_t percent){}

View File

@ -1,13 +1,8 @@
#include "TMP1075.h"
#include "state_machine.h"
#define MAX_TEMP_DISCHARGING ((int16_t)(59 / 0.0625f))
#define MIN_TEMP_DISCHARGING ((int16_t)(-20 / 0.0625f))
#define MAX_TEMP_CHARGING ((int16_t)(45 / 0.0625f))
#define MIN_TEMP_CHARGING ((int16_t)(0 / 0.0625f))
#define MAX_FAILED_TEMP 2 //TODO: change value for compliance with the actual number of sensors
// TODO: "change value for compliance with the actual number of sensors", change temps to float
#define MAX_TEMP ((int16_t)(59 / 0.0625f))
#define MAX_FAILED_TEMP 12 //TODO: change value for compliance with the actual number of sensors
#warning "change value for compliance with the actual number of sensors"
int16_t tmp1075_temps[N_TEMP_SENSORS] = {0};
uint32_t tmp1075_failed_sensors = 0;
@ -38,36 +33,19 @@ HAL_StatusTypeDef tmp1075_measure() {
int err = 0;
int temp_error = 0;
for (int i = 0; i < N_TEMP_SENSORS; i++) {
if (tmp1075_sensor_read(i, &tmp1075_temps[i]) != HAL_OK || (tmp1075_temps[i] & 0x000F) != 0) {
if (tmp1075_sensor_read(i, &tmp1075_temps[i]) != HAL_OK ||
(tmp1075_temps[i] & 0x000F) != 0) {
tmp1075_failed_sensors |= 1 << i;
nfailed_temp_sensors++;
err = 1;
} else {
tmp1075_temps[i] >>= 4;
tmp1075_failed_sensors &= ~(1 << i);
if (state.current_state == STATE_CHARGING || state.current_state == STATE_CHARGING_PRECHARGE){
if (tmp1075_temps[i] >= MAX_TEMP_CHARGING) {
temp_error = 1;
handle_over_maxtemp(i, tmp1075_temps[i]);
}
} else {
if (tmp1075_temps[i] >= MAX_TEMP_DISCHARGING) {
temp_error = 1;
handle_over_maxtemp(i, tmp1075_temps[i]);
}
}
if (state.current_state == STATE_CHARGING || state.current_state == STATE_CHARGING_PRECHARGE){
if (tmp1075_temps[i] <= MIN_TEMP_CHARGING) {
temp_error = 1;
handle_over_maxtemp(i, tmp1075_temps[i]);
}
} else {
if (tmp1075_temps[i] <= MIN_TEMP_DISCHARGING) {
temp_error = 1;
handle_over_maxtemp(i, tmp1075_temps[i]);
}
if (tmp1075_temps[i] >= MAX_TEMP) {
temp_error = 1;
handle_over_maxtemp(i, tmp1075_temps[i]);
}
#warning "check for under temp"
}
}
if (nfailed_temp_sensors > MAX_FAILED_TEMP) {

View File

@ -1,47 +1,17 @@
/*
* can.h
*
* Created on: 07.07.2024
* can.c
* Created on: Mai 23, 2024
* Author: Hamza
*/
#include "can.h"
#include "AMS_HighLevel.h"
#include "PWM_control.h"
#include "TMP1075.h"
#include "can-halal.h"
#include "eeprom.h"
#include "soc_estimation.h"
#include "state_machine.h"
#include "stm32f3xx_hal.h"
#include "stm32f3xx_hal_def.h"
#include <stdint.h>
#define CAN_ID_IN 0x501
#define CAN_ID_OUT 0x502
#define CAN_ID_LOG 0x503
// Every X ms, send message
#define CAN_STATUS_FREQ 1000
#define CAN_LOGGING_FREQ 200
#define CAN_DUMP_FREQ 10
// Max time to wait for CAN messages. If we reach it then we target state is set to STATE_ERROR.
#define CAN_TIMEOUT 5000
uint8_t id_to_log;
uint8_t last_message[8];
uint32_t can_status_timer, can_log_timer, can_timeout_timer;
//#define CAN_ID_IN 0x501
//#define CAN_ID_OUT 0x502
int can_delay_manager = 0;
void can_init(CAN_HandleTypeDef* hcan) {
ftcan_init(hcan);
ftcan_add_filter(CAN_ID_IN, 0xFFF);
last_message[0] = -1;
last_message[1] = -1;
can_status_timer = HAL_GetTick() + CAN_STATUS_FREQ;
can_log_timer = HAL_GetTick() + CAN_LOGGING_FREQ;
can_timeout_timer = HAL_GetTick() + CAN_TIMEOUT;
id_to_log =0;
}
/*
@ -83,53 +53,62 @@ bit 52-63 (12b): empty
*/
void can_handle_send_status() {
if (can_status_timer > HAL_GetTick())
if (can_delay_manager > HAL_GetTick())
return;
else {
uint8_t data[8] = {};
can_status_timer = HAL_GetTick() + CAN_STATUS_FREQ;
else
can_delay_manager = HAL_GetTick() + CAN_STATUS_FREQ;
uint8_t id_highest_temp = 0;
uint16_t highest_temp = 0;
sm_check_battery_temperature(&id_highest_temp, &highest_temp);
uint8_t data[8] = {};
int8_t id_highest_temp = -1;
int16_t highest_temp = INT16_MIN;
sm_check_battery_temperature(&id_highest_temp, &highest_temp);
data[0] = ((state.current_state << 4) | (current_powerground_status >> 4)); // 1 bit emptyy | 3 bit state | 4 bit powerground
data[1] = ((current_powerground_status << 4) | (state.error_source >> 4)); // 4 bit powerground | 4 bit error
data[2] = ((state.error_source << 4)); // 4 bit error | 4 bit state of charge
data[3] = ((int) current_soc); // 8 bit state of charge
data[4] = (roundf(RELAY_BAT_SIDE_VOLTAGE / 1000.0)); // 8 bit battery voltage
data[5] = (roundf(RELAY_ESC_SIDE_VOLTAGE / 1000.0)); // 8 bit Inverter voltage
data[6] = (roundf(CURRENT_MEASUREMENT / 1000.0)); // 8 bit Current
data[7] = ((highest_temp) >> 4); // 8 bit highest cell temperature
//data[7] = state.error_source;
ftcan_transmit(CAN_ID_OUT, data, sizeof(data));
data[0] = ((state.current_state << 4) | (powerground_status >> 4)); // 1 bit emptyy | 3 bit state | 4 bit powerground
data[1] = ((powerground_status << 4) | (state.error_source >> 4)); // 4 bit powerground | 4 bit error
data[2] = ((state.error_source << 4) | (0)); // 4 bit error | 4 bit state of charge
data[3] = ((0) + (RELAY_BAT_SIDE_VOLTAGE >> 12)); // 4 bit state of charge | 4 bit battery voltage
data[4] = ((RELAY_BAT_SIDE_VOLTAGE >> 4));
data[5] = ((CURRENT_MEASUREMENT >> 8));
data[6] = ((CURRENT_MEASUREMENT & 0x00F0) | (highest_temp >> 12));
data[7] = ((highest_temp) >> 4);
ftcan_transmit(CAN_ID_OUT, data, sizeof(data));
int8_t id_lowest_temp = -1;
int16_t lowest_temp = INT16_MIN;
for (int i = 0; i < N_TEMP_SENSORS; i++) {
if (tmp1075_temps[i] < lowest_temp){
id_lowest_temp = i;
lowest_temp = tmp1075_temps[i];
}
}
}
void can_handle_send_log(){
if (can_log_timer > HAL_GetTick())
return;
else {
uint8_t data[8] = {};
can_log_timer = HAL_GetTick() + CAN_LOGGING_FREQ;
data[0] = id_to_log;
data[1] = module.cellVoltages[id_to_log] >> 8;
data[2] = module.cellVoltages[id_to_log];
data[3] = tmp1075_temps[id_to_log] >> 4;
ftcan_transmit(CAN_ID_LOG, data, 4);
id_to_log++;
if (id_to_log == 13)
id_to_log = 0;
}
/*
021E 30
0232 50
0238 60
0246 70
0250 80
025A 90
0264 100
*/
int8_t id_lowest_volt = -1;
int16_t lowest_volt = INT16_MIN;
int8_t id_highest_volt = -1;
int16_t highest_volt = INT16_MIN;
for (int i = 0; i < module.sumOfCellMeasurements; i++) {
if (sm_return_cell_voltage(i) < lowest_temp){
id_lowest_volt = i;
lowest_volt = sm_return_cell_voltage(i);
}
if (sm_return_cell_voltage(i) > highest_temp){
id_highest_volt = i;
highest_volt = sm_return_cell_voltage(i);
}
}
data[0] = ((id_highest_temp & 0x0F) << 4 | (id_lowest_temp & 0x0F));
data[1] = ((lowest_temp) >> 8);
data[2] = ((lowest_temp & 0x00F0) | (id_lowest_volt & 0x0F));
data[3] = (lowest_volt >> 8);
data[4] = ((lowest_volt & 0x00F0) | (id_highest_volt & 0x0F));
data[5] = ((highest_volt >> 8));
data[6] = ((highest_volt & 0x00F0));
data[7] = 0;
ftcan_transmit(CAN_ID_OUT, data, sizeof(data));
}
/*
@ -139,9 +118,9 @@ to the sm_handle_ams_in() which handles the state machine transition.
This function recieves a command from the Autobox with the CAN ID of 0x501.
with format of:
data[0] = target state
0x00 STATE_INACTIVE | disconnect power to the ESC of powerground. Send it to return the mvbms to idle/monitoring mode. If data[1] != 0 -> assume bad CAN message.
0x01 STATE_READY | conneect power to the ESC of powerground and but with no PWM signal. If data[1] != 0 -> assume bad CAN message.
0x02 STATE_ACTIVE | activate powerground at (data[1]) percent. If data[1] > 100 -> assume bad CAN message.
0x0 STATE_INACTIVE | disconnect power to the ESC of powerground. Send it to return the mvbms to idle/monitoring mode. If data[1] != 0 -> assume bad CAN message.
0x1 STATE_READY | conneect power to the ESC of powerground and but with no PWM signal. If data[1] != 0 -> assume bad CAN message.
0x2 STATE_ACTIVE | activate powerground at (data[1]) percent. If data[1] > 100 -> assume bad CAN message.
allowed transitions:
STATE_INACTIVE -> STATE_READY
@ -155,33 +134,9 @@ void can_handle_recieve_command(const uint8_t *data){
sm_handle_ams_in(data);
} else if (data[0] == 0x02 && data[1] <= 100) {
sm_handle_ams_in(data);
} else if (data[0] == 0xF0 && data[1] == 0x00) {
sm_handle_ams_in(data);
} else if (data[0] == 0xF1 && data[1] == 0x00) {
sm_handle_ams_in(data);
} else if (data[0] == 0xF2 && data[1] == 0x00) {
sm_handle_ams_in(data);
} else if (data[0] == 0xFA && data[1] == 0x00) {
sm_handle_ams_in(data);
} else if (data[0] == 0xFF && data[1] == 0x00) {
sm_handle_ams_in(data);
}
}
void can_handle_dump() {
uint8_t* data = {};
HAL_StatusTypeDef status = HAL_OK;
while (status == HAL_OK){
HAL_Delay(2);
eeprom_read(data, 62);
for (int i = 0; i < (EEPROM_MEMORY_SIZE-8)/8; i += 8) {
ftcan_transmit(CAN_ID_OUT, &data[i], 8);
}
ftcan_transmit(CAN_ID_OUT, &data[56], 6);
}
read_address = 0;
}
/*
implements the _weak method ftcan_msg_recieved_cb() which throws an interrupt when a CAN message is recieved.
it only checks if the id is and datalen is correct thans hands data over to can_handle_recieve_command().
@ -189,17 +144,7 @@ it only checks if the id is and datalen is correct thans hands data over to can_
in MXCUBE under CAN NVIC settings "USB low priority or CAN_RX0 interrupts" has to be on
*/
void ftcan_msg_received_cb(uint16_t id, size_t datalen, const uint8_t *data){
if (programming_mode == 1){
can_handle_recieve_command(data);
return;
}
if (id == 0x501 && datalen == 2){
can_timeout_timer = HAL_GetTick() + CAN_TIMEOUT;
if (last_message[0] != data[0] || last_message[1] != data[1]){
last_message[0] = data[0];
last_message[1] = data[1];
can_handle_recieve_command(data);
}
can_handle_recieve_command(data);
}
}

View File

@ -1,96 +0,0 @@
/*
* PWM_control.h
*
* Created on: 10.07.2024
* Author: Hamza
*/
#include <eeprom.h>
// TODO: test this
static I2C_HandleTypeDef* hi2c;
uint32_t write_address, read_address;
void eeprom_init(I2C_HandleTypeDef* handle) {
hi2c = handle;
write_address = 0;
read_address = 0;
}
void eeprom_write_status(){
uint8_t data_length = 62;
uint8_t data[data_length] = {};
// data 0-9
data[0] = ((state.current_state << 4) | (current_powerground_status >> 4));
data[1] = ((current_powerground_status << 4) | (state.error_source >> 4)); // 4 bit powerground | 4 bit error
data[2] = ((state.error_source << 4) | (0)); // 4 bit error | 4 bit state of charge
data[3] = ((int) current_soc); // 8 bit state of charge
data[4] = (RELAY_BAT_SIDE_VOLTAGE >> 8); // 16 bit battery voltage
data[5] = (RELAY_BAT_SIDE_VOLTAGE);
data[6] = (RELAY_ESC_SIDE_VOLTAGE >> 8); // 16 bit Inverter voltage
data[7] = (RELAY_ESC_SIDE_VOLTAGE);
data[8] = (CURRENT_MEASUREMENT >> 8); // 16 bit Inverter voltage
data[9] = (CURRENT_MEASUREMENT);
// data 10-35
for (int i = 0; i < 13; i++) {
data[(i*2)] = ((int) module.auxVoltages[i]) >> 8;
data[(i*2)+1] = ((int) module.auxVoltages[i]);
}
// data 36-61
for (int i = 0; i < 13; i++) {
data[(i*2)] = (tmp1075_temps[i]) >> 8;
data[(i*2)+1] = (tmp1075_temps[i]);
}
eeprom_write(data, 62);
write_address++;
}
HAL_StatusTypeDef eeprom_read(uint8_t* data, uint16_t data_length){
HAL_StatusTypeDef status = HAL_OK;
for (size_t i = 0; i < data_length; i++) {
if (read_address > EEPROM_MEMORY_SIZE){
read_address = 0;
return HAL_BUSY;
} else if (read_address <= 65535){
status = HAL_I2C_Mem_Read(
hi2c, EEPROM_I2C_ADDR,
read_address, EERROM_MEMORY_ADDR_SIZE,
&data[i], 1, 10);
} else if (read_address > 65535) {
status = HAL_I2C_Mem_Read(
hi2c, EEPROM_I2C_ADDR + 2,
read_address - 65535, EERROM_MEMORY_ADDR_SIZE,
&data[i], 1, 10);
}
read_address++;
}
return status;
}
HAL_StatusTypeDef eeprom_write(uint8_t* data, uint16_t data_length){
HAL_StatusTypeDef status = HAL_OK;
HAL_GPIO_WritePin(EEPROM___WC__GPIO_Port, EEPROM___WC__Pin, GPIO_PIN_RESET);
for (size_t i = 0; i < data_length; i++) {
if (write_address > EEPROM_MEMORY_SIZE){
write_address = 0;
return HAL_BUSY;
} else if (write_address <= 65535){
status = HAL_I2C_Mem_Write(
hi2c, EEPROM_I2C_ADDR,
write_address, EERROM_MEMORY_ADDR_SIZE,
&data[i], 1, 10);
} else if (write_address > 65535) {
status = HAL_I2C_Mem_Write(
hi2c, EEPROM_I2C_ADDR + 2,
write_address - 65535, EERROM_MEMORY_ADDR_SIZE,
&data[i], 1, 10);
}
write_address++;
}
HAL_GPIO_WritePin(EEPROM___WC__GPIO_Port, EEPROM___WC__Pin, GPIO_PIN_SET);
return status;
}

View File

@ -1,16 +1,13 @@
#include "errors.h"
#include "stm32f3xx_hal.h"
#warning move all errors here
SlaveErrorData error_data;
void set_error_source(SlaveErrorKind source) {
void set_error_source(int source) {
if (!error_data.error_sources) {
error_data.errors_since = HAL_GetTick();
}
error_data.error_sources |= (1 << source);
error_data.error_sources |= source;
}
void clear_error_source(SlaveErrorKind source) { error_data.error_sources &= ~(1 << source); }
void clear_error_source(int source) { error_data.error_sources &= ~source; }

View File

@ -26,10 +26,7 @@
#include "PWM_control.h"
#include "can.h"
#include "AMS_HighLevel.h"
#include "soc_estimation.h"
#include "state_machine.h"
#include <status_LED.h>
#include <stdint.h>
#include "TMP1075.h"
#include "errors.h"
#include "stm32f302xc.h"
@ -50,26 +47,20 @@
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
// htim2 CH3,4 BAT_COOLING_PWM,ENABLE
// htim3 CH3,4 ESC_L_PWM,R_PWM
// htim4 CH1,2,3 LED R,G,B
// htim15 CH1,2 ESC_COOLING_ENABLE,PWM
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
CAN_HandleTypeDef hcan;
I2C_HandleTypeDef hi2c1;
I2C_HandleTypeDef hi2c2;
SPI_HandleTypeDef hspi1;
TIM_HandleTypeDef htim2;
TIM_HandleTypeDef htim3;
TIM_HandleTypeDef htim4;
TIM_HandleTypeDef htim1;
TIM_HandleTypeDef htim15;
UART_HandleTypeDef huart1;
/* USER CODE BEGIN PV */
/* USER CODE END PV */
@ -81,10 +72,8 @@ static void MX_CAN_Init(void);
static void MX_I2C1_Init(void);
static void MX_SPI1_Init(void);
static void MX_TIM15_Init(void);
static void MX_I2C2_Init(void);
static void MX_TIM2_Init(void);
static void MX_TIM3_Init(void);
static void MX_TIM4_Init(void);
static void MX_USART1_UART_Init(void);
static void MX_TIM1_Init(void);
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
@ -127,23 +116,15 @@ int main(void)
MX_I2C1_Init();
MX_SPI1_Init();
MX_TIM15_Init();
MX_I2C2_Init();
MX_TIM2_Init();
MX_TIM3_Init();
MX_TIM4_Init();
MX_USART1_UART_Init();
MX_TIM1_Init();
/* USER CODE BEGIN 2 */
sm_init();
tmp1075_init(&hi2c1);
AMS_Init(&hspi1);
can_init(&hcan);
PWM_control_init(&htim3, &htim2, &htim15);
soc_init();
status_led_init(&htim4, &htim4, &htim4);
sm_program_powerground();
eeprom_init(&hi2c2);
AMS_Loop();
uint32_t startup_timer = 500 + HAL_GetTick();
while (startup_timer > HAL_GetTick());
PWM_control_init(&htim15, &htim1);
HAL_Delay(10);
/* USER CODE END 2 */
/* Infinite loop */
@ -156,6 +137,7 @@ int main(void)
AMS_Loop();
sm_update();
//sm_test_cycle_states();
can_handle_send_status();
}
/* USER CODE END 3 */
}
@ -173,9 +155,10 @@ void SystemClock_Config(void)
/** Initializes the RCC Oscillators according to the specified parameters
* in the RCC_OscInitTypeDef structure.
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI|RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
@ -195,9 +178,11 @@ void SystemClock_Config(void)
{
Error_Handler();
}
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_I2C1|RCC_PERIPHCLK_I2C2;
PeriphClkInit.I2c1ClockSelection = RCC_I2C1CLKSOURCE_SYSCLK;
PeriphClkInit.I2c2ClockSelection = RCC_I2C2CLKSOURCE_SYSCLK;
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_I2C1
|RCC_PERIPHCLK_TIM1;
PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2;
PeriphClkInit.I2c1ClockSelection = RCC_I2C1CLKSOURCE_HSI;
PeriphClkInit.Tim1ClockSelection = RCC_TIM1CLK_HCLK;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
@ -257,7 +242,7 @@ static void MX_I2C1_Init(void)
/* USER CODE END I2C1_Init 1 */
hi2c1.Instance = I2C1;
hi2c1.Init.Timing = 0x00303D5B;
hi2c1.Init.Timing = 0x2000090E;
hi2c1.Init.OwnAddress1 = 0;
hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
@ -289,54 +274,6 @@ static void MX_I2C1_Init(void)
}
/**
* @brief I2C2 Initialization Function
* @param None
* @retval None
*/
static void MX_I2C2_Init(void)
{
/* USER CODE BEGIN I2C2_Init 0 */
/* USER CODE END I2C2_Init 0 */
/* USER CODE BEGIN I2C2_Init 1 */
/* USER CODE END I2C2_Init 1 */
hi2c2.Instance = I2C2;
hi2c2.Init.Timing = 0x00303D5B;
hi2c2.Init.OwnAddress1 = 0;
hi2c2.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
hi2c2.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
hi2c2.Init.OwnAddress2 = 0;
hi2c2.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
hi2c2.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
hi2c2.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
if (HAL_I2C_Init(&hi2c2) != HAL_OK)
{
Error_Handler();
}
/** Configure Analogue filter
*/
if (HAL_I2CEx_ConfigAnalogFilter(&hi2c2, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
{
Error_Handler();
}
/** Configure Digital filter
*/
if (HAL_I2CEx_ConfigDigitalFilter(&hi2c2, 0) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN I2C2_Init 2 */
/* USER CODE END I2C2_Init 2 */
}
/**
* @brief SPI1 Initialization Function
* @param None
@ -378,165 +315,72 @@ static void MX_SPI1_Init(void)
}
/**
* @brief TIM2 Initialization Function
* @brief TIM1 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM2_Init(void)
static void MX_TIM1_Init(void)
{
/* USER CODE BEGIN TIM2_Init 0 */
/* USER CODE BEGIN TIM1_Init 0 */
/* USER CODE END TIM2_Init 0 */
/* USER CODE END TIM1_Init 0 */
TIM_MasterConfigTypeDef sMasterConfig = {0};
TIM_OC_InitTypeDef sConfigOC = {0};
TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0};
/* USER CODE BEGIN TIM2_Init 1 */
/* USER CODE BEGIN TIM1_Init 1 */
/* USER CODE END TIM2_Init 1 */
htim2.Instance = TIM2;
htim2.Init.Prescaler = 0;
htim2.Init.CounterMode = TIM_COUNTERMODE_UP;
htim2.Init.Period = 4294967295;
htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_PWM_Init(&htim2) != HAL_OK)
/* USER CODE END TIM1_Init 1 */
htim1.Instance = TIM1;
htim1.Init.Prescaler = 0;
htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
htim1.Init.Period = 65535;
htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim1.Init.RepetitionCounter = 0;
htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_PWM_Init(&htim1) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK)
if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK)
{
Error_Handler();
}
sConfigOC.OCMode = TIM_OCMODE_PWM1;
sConfigOC.Pulse = 0;
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
if (HAL_TIM_PWM_ConfigChannel(&htim2, &sConfigOC, TIM_CHANNEL_3) != HAL_OK)
sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_3) != HAL_OK)
{
Error_Handler();
}
if (HAL_TIM_PWM_ConfigChannel(&htim2, &sConfigOC, TIM_CHANNEL_4) != HAL_OK)
sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;
sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE;
sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;
sBreakDeadTimeConfig.DeadTime = 0;
sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
sBreakDeadTimeConfig.BreakFilter = 0;
sBreakDeadTimeConfig.Break2State = TIM_BREAK2_DISABLE;
sBreakDeadTimeConfig.Break2Polarity = TIM_BREAK2POLARITY_HIGH;
sBreakDeadTimeConfig.Break2Filter = 0;
sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
if (HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM2_Init 2 */
/* USER CODE BEGIN TIM1_Init 2 */
/* USER CODE END TIM2_Init 2 */
HAL_TIM_MspPostInit(&htim2);
}
/**
* @brief TIM3 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM3_Init(void)
{
/* USER CODE BEGIN TIM3_Init 0 */
/* USER CODE END TIM3_Init 0 */
TIM_MasterConfigTypeDef sMasterConfig = {0};
TIM_OC_InitTypeDef sConfigOC = {0};
/* USER CODE BEGIN TIM3_Init 1 */
/* USER CODE END TIM3_Init 1 */
htim3.Instance = TIM3;
htim3.Init.Prescaler = 7;
htim3.Init.CounterMode = TIM_COUNTERMODE_UP;
htim3.Init.Period = 39999;
htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_PWM_Init(&htim3) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK)
{
Error_Handler();
}
sConfigOC.OCMode = TIM_OCMODE_PWM1;
sConfigOC.Pulse = 0;
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
if (HAL_TIM_PWM_ConfigChannel(&htim3, &sConfigOC, TIM_CHANNEL_3) != HAL_OK)
{
Error_Handler();
}
if (HAL_TIM_PWM_ConfigChannel(&htim3, &sConfigOC, TIM_CHANNEL_4) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM3_Init 2 */
/* USER CODE END TIM3_Init 2 */
HAL_TIM_MspPostInit(&htim3);
}
/**
* @brief TIM4 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM4_Init(void)
{
/* USER CODE BEGIN TIM4_Init 0 */
/* USER CODE END TIM4_Init 0 */
TIM_MasterConfigTypeDef sMasterConfig = {0};
TIM_OC_InitTypeDef sConfigOC = {0};
/* USER CODE BEGIN TIM4_Init 1 */
/* USER CODE END TIM4_Init 1 */
htim4.Instance = TIM4;
htim4.Init.Prescaler = 624;
htim4.Init.CounterMode = TIM_COUNTERMODE_UP;
htim4.Init.Period = 255;
htim4.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim4.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_PWM_Init(&htim4) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK)
{
Error_Handler();
}
sConfigOC.OCMode = TIM_OCMODE_PWM1;
sConfigOC.Pulse = 0;
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
{
Error_Handler();
}
if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_2) != HAL_OK)
{
Error_Handler();
}
if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_3) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM4_Init 2 */
/* USER CODE END TIM4_Init 2 */
HAL_TIM_MspPostInit(&htim4);
/* USER CODE END TIM1_Init 2 */
HAL_TIM_MspPostInit(&htim1);
}
@ -560,9 +404,9 @@ static void MX_TIM15_Init(void)
/* USER CODE END TIM15_Init 1 */
htim15.Instance = TIM15;
htim15.Init.Prescaler = 0;
htim15.Init.Prescaler = 7;
htim15.Init.CounterMode = TIM_COUNTERMODE_UP;
htim15.Init.Period = 65535;
htim15.Init.Period = 39999;
htim15.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim15.Init.RepetitionCounter = 0;
htim15.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
@ -610,6 +454,41 @@ static void MX_TIM15_Init(void)
}
/**
* @brief USART1 Initialization Function
* @param None
* @retval None
*/
static void MX_USART1_UART_Init(void)
{
/* USER CODE BEGIN USART1_Init 0 */
/* USER CODE END USART1_Init 0 */
/* USER CODE BEGIN USART1_Init 1 */
/* USER CODE END USART1_Init 1 */
huart1.Instance = USART1;
huart1.Init.BaudRate = 38400;
huart1.Init.WordLength = UART_WORDLENGTH_8B;
huart1.Init.StopBits = UART_STOPBITS_1;
huart1.Init.Parity = UART_PARITY_NONE;
huart1.Init.Mode = UART_MODE_TX_RX;
huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE;
huart1.Init.OverSampling = UART_OVERSAMPLING_16;
huart1.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
huart1.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
if (HAL_UART_Init(&huart1) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN USART1_Init 2 */
/* USER CODE END USART1_Init 2 */
}
/**
* @brief GPIO Initialization Function
* @param None
@ -628,10 +507,13 @@ static void MX_GPIO_Init(void)
__HAL_RCC_GPIOB_CLK_ENABLE();
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOA, CSB_Pin|EEPROM___WC__Pin, GPIO_PIN_RESET);
HAL_GPIO_WritePin(GPIOA, RELAY_EN_Pin|_60V_EN_Pin|CSB_Pin, GPIO_PIN_RESET);
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOB, RELAY_ENABLE_Pin|PRECHARGE_ENABLE_Pin, GPIO_PIN_RESET);
HAL_GPIO_WritePin(GPIOB, STATUS_LED_R_Pin|STATUS_LED_B_Pin|STATUS_LED_G_Pin, GPIO_PIN_SET);
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(PRECHARGE_EN_GPIO_Port, PRECHARGE_EN_Pin, GPIO_PIN_RESET);
/*Configure GPIO pins : PC13 PC14 PC15 */
GPIO_InitStruct.Pin = GPIO_PIN_13|GPIO_PIN_14|GPIO_PIN_15;
@ -639,32 +521,34 @@ static void MX_GPIO_Init(void)
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
/*Configure GPIO pins : PA0 PA1 PA2 PA3 */
GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_3;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/*Configure GPIO pins : CSB_Pin EEPROM___WC__Pin */
GPIO_InitStruct.Pin = CSB_Pin|EEPROM___WC__Pin;
/*Configure GPIO pins : RELAY_EN_Pin _60V_EN_Pin CSB_Pin */
GPIO_InitStruct.Pin = RELAY_EN_Pin|_60V_EN_Pin|CSB_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/*Configure GPIO pins : PB2 PB12 PB13 */
GPIO_InitStruct.Pin = GPIO_PIN_2|GPIO_PIN_12|GPIO_PIN_13;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/*Configure GPIO pins : RELAY_ENABLE_Pin PRECHARGE_ENABLE_Pin */
GPIO_InitStruct.Pin = RELAY_ENABLE_Pin|PRECHARGE_ENABLE_Pin;
/*Configure GPIO pins : STATUS_LED_R_Pin STATUS_LED_B_Pin STATUS_LED_G_Pin PRECHARGE_EN_Pin */
GPIO_InitStruct.Pin = STATUS_LED_R_Pin|STATUS_LED_B_Pin|STATUS_LED_G_Pin|PRECHARGE_EN_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 pins : PB10 PB12 PB13 PB14
PB4 PB5 PB8 */
GPIO_InitStruct.Pin = GPIO_PIN_10|GPIO_PIN_12|GPIO_PIN_13|GPIO_PIN_14
|GPIO_PIN_4|GPIO_PIN_5|GPIO_PIN_8;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/*Configure GPIO pins : RELAY_BATT_SIDE_ON_Pin RELAY_ESC_SIDE_ON_Pin CURRENT_SENSOR_ON_Pin */
GPIO_InitStruct.Pin = RELAY_BATT_SIDE_ON_Pin|RELAY_ESC_SIDE_ON_Pin|CURRENT_SENSOR_ON_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* USER CODE BEGIN MX_GPIO_Init_2 */
/* USER CODE END MX_GPIO_Init_2 */
}

View File

@ -1,92 +0,0 @@
#include "soc_estimation.h"
#include <stdint.h>
#define SOC_ESTIMATION_NO_CURRENT_THRESH 1000 // mA
#define SOC_ESTIMATION_NO_CURRENT_TIME 100000 // ms
#define SOC_ESTIMATION_BATTERY_CAPACITY 28800 // mAs
#define MIN_CELL_VOLTAGE 3000
#define MAX_CELL_VOLTAGE 4130
// https://www.desmos.com/calculator/mm22vmxl2x
ocv_soc_pair_t OCV_SOC_PAIRS[] = {
{3000, 0.00f}, {3350, 10.00f}, {3450, 20.00f},
{3500, 30.00f}, {3530, 40.00f}, {3570, 50.00f},
{3600, 60.00f}, {3630, 70.00f}, {3700, 80.00f},
{3800, 90.00f}, {4130, 100.00f}
};
float current_soc;
int current_was_flowing;
uint32_t last_current_time;
float soc_before_current;
float mAs_before_current;
void soc_init() {
current_soc = 0;
last_current_time = 0;
current_was_flowing = 1;
}
void soc_update() {
uint32_t now = HAL_GetTick();
if (CURRENT_MEASUREMENT >= SOC_ESTIMATION_NO_CURRENT_THRESH) {
last_current_time = now;
if (!current_was_flowing) {
soc_before_current = current_soc;
mAs_before_current = CURRENT_MEASUREMENT;
}
current_was_flowing = 1;
} else {
current_was_flowing = 0;
}
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).
uint8_t id = 0;
uint16_t min_voltage = 0;
sm_check_battery_temperature(&id, &min_voltage);
current_soc = soc_for_ocv(min_voltage);
} else {
// Otherwise, use the current counter to update SoC
float as_delta = CURRENT_MEASUREMENT - 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

@ -1,124 +1,53 @@
/*
* state_machine.h
*
* Created on: 07.07.2024
* Author: Hamza
*/
#include <state_machine.h>
#include <stdint.h>
#include "state_machine.h"
#include "AMS_HighLevel.h"
#include "PWM_control.h"
#include "can.h"
#include "eeprom.h"
#include "TMP1075.h"
#include "errors.h"
#include "stm32f3xx_hal.h"
// 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_DURATION 8000 // ms
// Time to wait for discharge
#define DISCHARGE_DURATION 8000 // ms
// Time to wait between closing relays
#define RELAY_CLOSE_WAIT 10 // ms
// waiting time between to eeprom writes
#define EEPROM_WRITE_FREQ 1000
// how delay between steps of 5 -> 15ms * (100/5) = 300ms
#define POWERGROUND_SOFTSTART_INCREMENT_DELAY 15
// after errors are cleared wait for ERROR_LATCH_TIME ms before returning to inactive mode
#define ERROR_LATCH_TIME 10000 //ms
/*
10
20
30
40
50
60
70
80
90
100
*/
bool programming_mode;
bool debugging_mode;
#include <stdint.h>
#include <stdio.h>
StateHandle state;
int32_t RELAY_BAT_SIDE_VOLTAGE;
int32_t RELAY_ESC_SIDE_VOLTAGE;
int32_t CURRENT_MEASUREMENT;
bool CURRENT_MEASUREMENT_ON;
float base_offset = 0;
int16_t RELAY_BAT_SIDE_VOLTAGE;
int16_t RELAY_ESC_SIDE_VOLTAGE;
int16_t CURRENT_MEASUREMENT;
uint8_t powerground_status;
uint32_t error_timer;
uint32_t precharge_timer;
uint32_t discharge_timer;
uint32_t eeprom_timer;
uint32_t powerground_softstart_timer;
uint32_t powerground_calibration_timer;
uint8_t powerground_calibration_stage;
uint8_t current_powerground_status;
uint8_t target_powerground_status;
static uint32_t timestamp;
uint32_t timestamp;
void sm_init(){
state.current_state = STATE_INACTIVE;
state.target_state = STATE_INACTIVE;
state.error_source = 0;
precharge_timer = discharge_timer = powerground_calibration_timer = error_timer = eeprom_timer = 0;
programming_mode = 0;
debugging_mode = 0;
}
void sm_update(){
CURRENT_MEASUREMENT = (module.auxVoltages[0] > 2495) ? (module.auxVoltages[0] - (2495.0)) * (300.0) : 0;
CURRENT_MEASUREMENT_ON = (module.auxVoltages[1] > 2400);
RELAY_ESC_SIDE_VOLTAGE = module.auxVoltages[2] * 15.19;
RELAY_BAT_SIDE_VOLTAGE = module.auxVoltages[3] * 15.19; // the calculation says the factor is 11. 11.711 yields the better result
if (can_timeout_timer < HAL_GetTick())
state.current_state = state.target_state = STATE_ERROR;
/*
if (eeprom_timer < HAL_GetTick()){
eeprom_write_status();
eeprom_timer = HAL_GetTick() + EEPROM_WRITE_FREQ;
}
*/
can_handle_send_status();
can_handle_send_log();
void sm_update(){
sm_check_errors();
sm_precharge_discharge_manager();
//sm_calibrate_powerground();
sm_powerground_manager();
tmp1075_measure();
status_led_update();
soc_update();
RELAY_BAT_SIDE_VOLTAGE = module.auxVoltages[0] * 12.42; // the calculation says the factor is 11.989. 12.42 yields the better result
RELAY_ESC_SIDE_VOLTAGE = module.auxVoltages[1] * 12.42;
CURRENT_MEASUREMENT = (module.auxVoltages[2] - 2496) * 300;
switch (state.current_state) {
case STATE_INACTIVE:
state.current_state = sm_update_inactive(); // monitor only
break;
case STATE_PRECHARGE:
state.current_state = sm_update_precharge(); // set PRECHARGE
state.current_state = sm_update_precharge(); // set PRECHARGE and turn on cooling at 50% or such
break;
case STATE_READY:
state.current_state = sm_update_ready();
state.current_state = sm_update_ready(); // keep cooling at 50%, get ready to turn on powerground
break;
case STATE_ACTIVE:
state.current_state = sm_update_active();
state.current_state = sm_update_active(); // set PRECHARGE and turn on cooling at 50% or such
break;
case STATE_DISCHARGE:
state.current_state = sm_update_discharge();
state.current_state = sm_update_discharge(); // open the main relay, keep PRECHARGE closed
break;
case STATE_CHARGING_PRECHARGE:
state.current_state = sm_update_charging_precharge();
break;
case STATE_CHARGING:
state.current_state = sm_update_charging();
state.current_state = sm_update_charging(); // monitor and turn on cooling if needed.
break;
case STATE_ERROR:
state.current_state = sm_update_error(); // enter the correct ERROR state
@ -129,190 +58,12 @@ void sm_update(){
state.target_state = state.current_state;
}
void sm_handle_ams_in(const uint8_t *data){
if (programming_mode == 1 && (state.current_state == STATE_READY || state.current_state == STATE_ACTIVE)){ PWM_powerground_control(data[1]); }
switch (data[0]) {
case 0x00:
if (state.current_state != STATE_INACTIVE){
state.target_state = STATE_DISCHARGE;
PWM_powerground_control(255);
}
break;
case 0x01:
if (state.target_state == STATE_INACTIVE || state.target_state == STATE_DISCHARGE){
state.target_state = STATE_PRECHARGE;
PWM_powerground_control(0);
} else if (state.target_state == STATE_ACTIVE){
state.target_state = STATE_READY;
PWM_powerground_control(0);
}
break;
case 0x02:
if (state.current_state == STATE_READY || state.current_state == STATE_ACTIVE){
target_powerground_status = data[1];
state.target_state = STATE_ACTIVE; // READY -> ACTIVE
}
break;
case 0xF0:
if (state.current_state == STATE_INACTIVE){
state.target_state = STATE_CHARGING_PRECHARGE;
}
break;
case 0xF1: // EEPROM
break;
if (state.current_state == STATE_INACTIVE)
// can_handle_dump();
break;
case 0xFF: // EMERGENCY SHUTDOWN
state.current_state = STATE_DISCHARGE;
state.target_state = STATE_ERROR;
break;
}
}
void sm_precharge_discharge_manager(){
if (state.current_state != STATE_PRECHARGE && state.target_state == STATE_PRECHARGE){
precharge_timer = HAL_GetTick() + PRECHARGE_DURATION;
} else if (state.current_state == STATE_PRECHARGE && precharge_timer < HAL_GetTick()) {
state.target_state = STATE_READY;
precharge_timer = 0;
}
if (state.current_state != STATE_CHARGING_PRECHARGE && state.target_state == STATE_CHARGING_PRECHARGE){
precharge_timer = HAL_GetTick() + PRECHARGE_DURATION;
} else if (state.current_state == STATE_CHARGING_PRECHARGE && precharge_timer < HAL_GetTick()) {
state.target_state = STATE_CHARGING;
precharge_timer = 0;
}
if (state.current_state != STATE_DISCHARGE && state.target_state == STATE_DISCHARGE){
discharge_timer = HAL_GetTick() + DISCHARGE_DURATION;
} else if (state.current_state == STATE_DISCHARGE && discharge_timer < HAL_GetTick()) {
state.target_state = STATE_INACTIVE;
discharge_timer = 0;
}
}
void sm_powerground_manager(){
if (current_powerground_status == target_powerground_status)
return;
if ( current_powerground_status > 100 || target_powerground_status > 100){ //something went wrong
PWM_powerground_control(255);
current_powerground_status = target_powerground_status= 0;
return;
}
if (powerground_softstart_timer < HAL_GetTick()){
if (current_powerground_status < target_powerground_status){
current_powerground_status += 5;
PWM_powerground_softcontrol();
powerground_softstart_timer = HAL_GetTick() + POWERGROUND_SOFTSTART_INCREMENT_DELAY;
} else if (current_powerground_status > target_powerground_status) {
current_powerground_status -= 5;
PWM_powerground_softcontrol();
powerground_softstart_timer = HAL_GetTick() + POWERGROUND_SOFTSTART_INCREMENT_DELAY;
}
}
}
void sm_calibrate_powerground(){
if (powerground_calibration_stage != 4 && state.current_state == STATE_PRECHARGE){
switch (powerground_calibration_stage) {
case 0:
powerground_calibration_timer = HAL_GetTick() + 0;
powerground_calibration_stage = 1;
return;
case 1:
if (powerground_calibration_timer < HAL_GetTick()){
powerground_calibration_timer = HAL_GetTick() + 2000;
powerground_calibration_stage = 2;
PWM_powerground_control(100);
}
return;
case 2:
if (powerground_calibration_timer < HAL_GetTick()){
powerground_calibration_timer = HAL_GetTick() + 1000;
powerground_calibration_stage = 3;
PWM_powerground_control(0);
}
return;
case 3:
if (powerground_calibration_timer < HAL_GetTick()){
powerground_calibration_stage = 4;
}
return;
}
}
}
void sm_program_powerground(){
if (programming_mode == 0)
return;
PWM_powerground_control(100);
state.current_state = state.target_state = STATE_ACTIVE;
while (1) {
can_handle_send_status();
}
}
void sm_eeprom_write_status(){
if (eeprom_timer < HAL_GetTick()){
eeprom_write_status();
eeprom_timer = HAL_GetTick() + EEPROM_WRITE_FREQ;
}
}
void sm_check_errors(){
if (programming_mode == 1 || debugging_mode == 1) {return;} // to disable error checking
state.error_type.temperature_error = (error_data.error_sources & (1 << 0) || error_data.error_sources & (1 << 1) || error_data.error_sources & (1 << 4)) ? 1 : 0;
state.error_type.voltage_error = (error_data.error_sources & (1 << 2)|| error_data.error_sources & (1 << 3)|| error_data.error_sources & (1 << 5) || RELAY_BAT_SIDE_VOLTAGE < 30000) ? 1 : 0;
state.error_type.bms_timeout = (error_data.error_sources & (1 << 7)) ? 1 : 0;
state.error_type.bms_fault = (error_data.error_sources & (1 << 8) || error_data.error_sources & (1 << 10) || error_data.error_sources & (1 << 9)) ? 1 : 0;
//SEK_EEPROM_ERR: state.error_type.eeprom_error = 1;
//state.error_type.current_error = (powerground_status > 10 && CURRENT_MEASUREMENT < 500) ? 1 : 0;
state.error_type.current_sensor_missing = (!CURRENT_MEASUREMENT_ON) ? 1 : 0;
state.error_type.voltage_missing = (RELAY_BAT_SIDE_VOLTAGE < 1000) ? 1 : 0;
if (state.error_type.current_error == 1 || state.error_type.current_sensor_missing == 1 || //state.error_type.eeprom_error == 1 ||
state.error_type.state_transition_fail == 1 || state.error_type.temperature_error == 1 || state.error_type.voltage_error == 1 ||
state.error_type.voltage_missing == 1 || state.error_type.bms_fault == 1 || state.error_type.bms_timeout == 1)
{
if (state.current_state != STATE_INACTIVE && state.current_state != STATE_ERROR)
state.current_state = STATE_DISCHARGE;
state.target_state = STATE_ERROR;
PWM_powerground_control(255);
error_timer = HAL_GetTick() + ERROR_LATCH_TIME;
} else if (state.current_state == STATE_ERROR && error_timer < HAL_GetTick()){
state.target_state = STATE_INACTIVE;
}
sm_set_error_source();
}
void sm_set_error_source(){
state.error_source = 0;
state.error_source |= (state.error_type.bms_timeout << 0);
state.error_source |= (state.error_type.bms_fault << 1);
state.error_source |= (state.error_type.temperature_error << 2);
state.error_source |= (state.error_type.current_error << 3);
state.error_source |= (state.error_type.current_sensor_missing << 4);
state.error_source |= (state.error_type.voltage_error << 5);
state.error_source |= (state.error_type.voltage_missing << 6);
state.error_source |= (state.error_type.state_transition_fail << 7);
}
State sm_update_inactive(){
switch (state.target_state) {
case STATE_PRECHARGE:
return STATE_PRECHARGE;
case STATE_CHARGING_PRECHARGE:
return STATE_CHARGING_PRECHARGE;
case STATE_ERROR:
return STATE_ERROR;
default:
return STATE_INACTIVE;
}
@ -322,8 +73,14 @@ State sm_update_precharge(){
switch (state.target_state) {
case STATE_INACTIVE: // if CAN Signal 0000 0000 then immidiete shutdown
return STATE_DISCHARGE;
case STATE_READY:
return STATE_READY;
case STATE_PRECHARGE:
if (RELAY_BAT_SIDE_VOLTAGE-RELAY_ESC_SIDE_VOLTAGE < 100){
PWM_set_throttle();
return STATE_READY;
}
break;
case STATE_DISCHARGE:
return STATE_DISCHARGE;
default:
return STATE_PRECHARGE;
}
@ -353,10 +110,11 @@ State sm_update_active(){
State sm_update_discharge(){
switch (state.target_state) {
case STATE_INACTIVE:
return STATE_INACTIVE;
case STATE_ERROR:
return STATE_ERROR;
case STATE_DISCHARGE:
if (RELAY_ESC_SIDE_VOLTAGE < 5000)
return STATE_INACTIVE;
case STATE_PRECHARGE: // if CAN Signal 1000 0000 then get ready
return STATE_PRECHARGE;
default:
return STATE_DISCHARGE;
}
@ -376,20 +134,17 @@ State sm_update_charging_precharge(){
State sm_update_charging(){
switch (state.target_state) {
case STATE_DISCHARGE:
currentAMSState = AMSIDLE;
return STATE_DISCHARGE;
default:
currentAMSState = AMSCHARGING;
return STATE_CHARGING;
}
}
State sm_update_error(){
switch (state.target_state) {
case STATE_DISCHARGE:
return STATE_DISCHARGE;
case STATE_INACTIVE:
return STATE_INACTIVE;
default:
return STATE_ERROR;
}
@ -415,7 +170,7 @@ void sm_set_relay_positions(State current_state){
break;
case STATE_DISCHARGE:
sm_set_relay(RELAY_MAIN, 0);
sm_set_relay(RELAY_PRECHARGE, 1);
sm_set_relay(RELAY_PRECHARGE, 0);
break;
case STATE_CHARGING_PRECHARGE:
sm_set_relay(RELAY_MAIN, 0);
@ -436,16 +191,25 @@ void sm_set_relay(Relay relay, bool closed){
GPIO_PinState state = closed ? GPIO_PIN_SET : GPIO_PIN_RESET;
switch (relay) {
case RELAY_MAIN:
HAL_GPIO_WritePin(RELAY_ENABLE_GPIO_Port, RELAY_ENABLE_Pin, state);
HAL_GPIO_WritePin(RELAY_EN_GPIO_Port, RELAY_EN_Pin, state);
relay_closed = closed;
break;
case RELAY_PRECHARGE:
HAL_GPIO_WritePin(PRECHARGE_ENABLE_GPIO_Port, PRECHARGE_ENABLE_Pin, state);
HAL_GPIO_WritePin(PRECHARGE_EN_GPIO_Port, PRECHARGE_EN_Pin, state);
precharge_closed = closed;
break;
}
}
void sm_check_charging(){
if (RELAY_BAT_SIDE_VOLTAGE < RELAY_ESC_SIDE_VOLTAGE && timestamp == 0)
timestamp = HAL_GetTick() + 5000;
if (timestamp < HAL_GetTick())
state.target_state = STATE_CHARGING_PRECHARGE;
}
/* returns the ID and temperature of the hottest cell */
void sm_check_battery_temperature(uint8_t *id, uint16_t *temp){
void sm_check_battery_temperature(int8_t *id, int16_t *temp){
for (int i = 0; i < N_TEMP_SENSORS; i++) {
if (tmp1075_temps[i] > *temp){
*id = i;
@ -454,9 +218,75 @@ void sm_check_battery_temperature(uint8_t *id, uint16_t *temp){
}
}
int16_t sm_return_cell_temperature(int id){ return tmp1075_temps[id]; }
int16_t sm_return_cell_temperature(int id){
return tmp1075_temps[id];
}
int16_t sm_return_cell_voltage(int id){ return module.cellVoltages[id]; }
int16_t sm_return_cell_voltage(int id){
return module.cellVoltages[id];
}
void sm_handle_ams_in(const uint8_t *data){
switch (data[0]) {
case 0x00:
if (state.current_state != STATE_INACTIVE){
state.target_state = STATE_DISCHARGE;
}
break;
case 0x01:
if (state.target_state == STATE_INACTIVE || state.target_state == STATE_DISCHARGE){
state.target_state = STATE_PRECHARGE;
} else if (state.target_state == STATE_ACTIVE){
state.target_state = STATE_READY;
}
break;
case 0x02:
if (state.current_state == STATE_READY || state.current_state == STATE_ACTIVE){
PWM_powerground_control(data[1]);
state.target_state = STATE_ACTIVE; // READY -> ACTIVE
}
break;
}
}
void sm_set_error(ErrorKind error_kind, bool is_errored){}
#warning TODO: add error checking for everything here
void sm_check_errors(){
switch (error_data.data_kind) {
case SEK_OVERTEMP:
case SEK_UNDERTEMP:
case SEK_TOO_FEW_TEMPS:
state.error_type.temperature_error = 1;
case SEK_OVERVOLT:
case SEK_UNDERVOLT:
case SEK_OPENWIRE:
case SEK_EEPROM_ERR:
case SEK_INTERNAL_BMS_TIMEOUT:
state.error_type.bms_timeout = 1;
case SEK_INTERNAL_BMS_CHECKSUM_FAIL:
case SEK_INTERNAL_BMS_OVERTEMP:
case SEK_INTERNAL_BMS_FAULT:
state.error_type.bms_fault = 1;
break;
}
if (1){
state.error_type.current_error = 1;
}
if (1){
state.error_type.current_sensor_missing = 1;
}
if (RELAY_BAT_SIDE_VOLTAGE < 30000){
state.error_type.voltage_error = 1;
}
if (1){
state.error_type.voltage_missing = 1;
}
}
void sm_test_cycle_states(){
RELAY_BAT_SIDE_VOLTAGE = module.auxVoltages[0];
@ -483,17 +313,13 @@ void sm_test_cycle_states(){
case STATE_ACTIVE:
state.current_state = STATE_DISCHARGE;
timestamp = HAL_GetTick() + 10000;
PWM_powerground_control(10);
PWM_powerground_control(1);
break;
case STATE_DISCHARGE:
state.current_state = STATE_INACTIVE;
timestamp = HAL_GetTick() + 10000;
break;
case STATE_CHARGING_PRECHARGE:
case STATE_CHARGING:
case STATE_ERROR:
break;
}
}
state.target_state = state.current_state;
}

View File

@ -1,132 +0,0 @@
/*
* status_LED.h
*
* Created on: 07.07.2024
* Author: Hamza
*/
#include "ADBMS_LL_Driver.h"
#include "state_machine.h"
#include "stm32f3xx_hal.h"
#include <status_LED.h>
#include <stdint.h>
// TODO test out pulldown and pushpull settings
/* 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))
Prescaler:
(ARR + 1) * (PSC + 1) = (F_CLK)/(F_PWM)
(PSC + 1) = (F_CLK)/(F_PWM * (ARR + 1))
625 = (16MHz)/(100Hz * (255 + 1))
F_CLK = 16 MHz
*/
#define STATUS_LED_ARR 255
#define TIME_BLINK_SLOW 2000
#define TIME_BLINK_FAST 500
TIM_HandleTypeDef* red;
TIM_HandleTypeDef* green;
TIM_HandleTypeDef* blue;
uint32_t blink_timer;
bool blink_state;
void status_led_init(TIM_HandleTypeDef* r, TIM_HandleTypeDef* g, TIM_HandleTypeDef* b){
red = r;
green = g;
blue = b;
blink_timer = 0;
blink_state = 0;
HAL_TIM_PWM_Start(red, TIM_CHANNEL_1); //TIM4CH1
HAL_TIM_PWM_Start(green, TIM_CHANNEL_2); //TIM4CH2
HAL_TIM_PWM_Start(blue, TIM_CHANNEL_3); //TIM4CH3
status_led_set(255, 255, 255);
}
void status_led_update(){
if (state.current_state == STATE_ERROR){
status_led_set_color(RED);
return;
}
if(blink_timer > HAL_GetTick()){
return;
}
if (blink_state == 1){
if (state.current_state == STATE_INACTIVE)
blink_timer = HAL_GetTick() + TIME_BLINK_SLOW/10;
else
blink_timer = HAL_GetTick() + TIME_BLINK_FAST/10;
blink_state = 0;
status_led_set_color(OFF);
return;
} else {
if (state.current_state == STATE_INACTIVE)
blink_timer = HAL_GetTick() + TIME_BLINK_SLOW;
else
blink_timer = HAL_GetTick() + TIME_BLINK_FAST;
blink_state = 1;
}
switch (state.current_state) {
case STATE_INACTIVE:
status_led_set_color(GREEN);
break;
case STATE_CHARGING_PRECHARGE:
case STATE_PRECHARGE:
case STATE_DISCHARGE:
status_led_set_color( YELLOW);
break;
case STATE_CHARGING:
case STATE_READY:
case STATE_ACTIVE:
status_led_set_color(PINK);
break;
case STATE_ERROR:
status_led_set_color(RED);
break;
}
}
void status_led_set_color(color color){
switch (color) {
case RED:
status_led_set(0, 255, 255);
break;
case GREEN:
status_led_set(255, 0, 255);
break;
case BLUE:
status_led_set(255, 255, 0);
break;
case YELLOW:
status_led_set(0, 0, 255);
break;
case PINK:
status_led_set(0, 255, 0);
break;
case CYAN:
status_led_set(255, 0, 0);
break;
case WHITE:
status_led_set(0, 0, 0);
break;
case OFF:
status_led_set(255,255,255);
break;
}
}
void status_led_set(uint8_t r, uint8_t g, uint8_t b){
__HAL_TIM_SET_COMPARE(red, TIM_CHANNEL_1, r);
__HAL_TIM_SET_COMPARE(green, TIM_CHANNEL_2, g);
__HAL_TIM_SET_COMPARE(blue, TIM_CHANNEL_3, b);
}

View File

@ -59,7 +59,7 @@
/* USER CODE END 0 */
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
/**
/**
* Initializes the Global MSP.
*/
void HAL_MspInit(void)
@ -173,19 +173,19 @@ void HAL_I2C_MspInit(I2C_HandleTypeDef* hi2c)
PA15 ------> I2C1_SCL
PB9 ------> I2C1_SDA
*/
GPIO_InitStruct.Pin = TMP_SCL_Pin;
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(TMP_SCL_GPIO_Port, &GPIO_InitStruct);
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
GPIO_InitStruct.Pin = TMP_SDA_Pin;
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(TMP_SDA_GPIO_Port, &GPIO_InitStruct);
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* Peripheral clock enable */
__HAL_RCC_I2C1_CLK_ENABLE();
@ -193,30 +193,6 @@ void HAL_I2C_MspInit(I2C_HandleTypeDef* hi2c)
/* USER CODE END I2C1_MspInit 1 */
}
else if(hi2c->Instance==I2C2)
{
/* USER CODE BEGIN I2C2_MspInit 0 */
/* USER CODE END I2C2_MspInit 0 */
__HAL_RCC_GPIOA_CLK_ENABLE();
/**I2C2 GPIO Configuration
PA9 ------> I2C2_SCL
PA10 ------> I2C2_SDA
*/
GPIO_InitStruct.Pin = EEPROM_SCL_Pin|EEPROM_SDA_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF4_I2C2;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* Peripheral clock enable */
__HAL_RCC_I2C2_CLK_ENABLE();
/* USER CODE BEGIN I2C2_MspInit 1 */
/* USER CODE END I2C2_MspInit 1 */
}
}
@ -240,34 +216,14 @@ void HAL_I2C_MspDeInit(I2C_HandleTypeDef* hi2c)
PA15 ------> I2C1_SCL
PB9 ------> I2C1_SDA
*/
HAL_GPIO_DeInit(TMP_SCL_GPIO_Port, TMP_SCL_Pin);
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_15);
HAL_GPIO_DeInit(TMP_SDA_GPIO_Port, TMP_SDA_Pin);
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_9);
/* USER CODE BEGIN I2C1_MspDeInit 1 */
/* USER CODE END I2C1_MspDeInit 1 */
}
else if(hi2c->Instance==I2C2)
{
/* USER CODE BEGIN I2C2_MspDeInit 0 */
/* USER CODE END I2C2_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_I2C2_CLK_DISABLE();
/**I2C2 GPIO Configuration
PA9 ------> I2C2_SCL
PA10 ------> I2C2_SDA
*/
HAL_GPIO_DeInit(EEPROM_SCL_GPIO_Port, EEPROM_SCL_Pin);
HAL_GPIO_DeInit(EEPROM_SDA_GPIO_Port, EEPROM_SDA_Pin);
/* USER CODE BEGIN I2C2_MspDeInit 1 */
/* USER CODE END I2C2_MspDeInit 1 */
}
}
@ -346,38 +302,16 @@ void HAL_SPI_MspDeInit(SPI_HandleTypeDef* hspi)
*/
void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef* htim_pwm)
{
if(htim_pwm->Instance==TIM2)
if(htim_pwm->Instance==TIM1)
{
/* USER CODE BEGIN TIM2_MspInit 0 */
/* USER CODE BEGIN TIM1_MspInit 0 */
/* USER CODE END TIM2_MspInit 0 */
/* USER CODE END TIM1_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_TIM2_CLK_ENABLE();
/* USER CODE BEGIN TIM2_MspInit 1 */
__HAL_RCC_TIM1_CLK_ENABLE();
/* USER CODE BEGIN TIM1_MspInit 1 */
/* USER CODE END TIM2_MspInit 1 */
}
else if(htim_pwm->Instance==TIM3)
{
/* USER CODE BEGIN TIM3_MspInit 0 */
/* USER CODE END TIM3_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_TIM3_CLK_ENABLE();
/* USER CODE BEGIN TIM3_MspInit 1 */
/* USER CODE END TIM3_MspInit 1 */
}
else if(htim_pwm->Instance==TIM4)
{
/* USER CODE BEGIN TIM4_MspInit 0 */
/* USER CODE END TIM4_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_TIM4_CLK_ENABLE();
/* USER CODE BEGIN TIM4_MspInit 1 */
/* USER CODE END TIM4_MspInit 1 */
/* USER CODE END TIM1_MspInit 1 */
}
else if(htim_pwm->Instance==TIM15)
{
@ -396,71 +330,25 @@ void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef* htim_pwm)
void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(htim->Instance==TIM2)
if(htim->Instance==TIM1)
{
/* USER CODE BEGIN TIM2_MspPostInit 0 */
/* USER CODE BEGIN TIM1_MspPostInit 0 */
/* USER CODE END TIM2_MspPostInit 0 */
/* USER CODE END TIM1_MspPostInit 0 */
__HAL_RCC_GPIOB_CLK_ENABLE();
/**TIM2 GPIO Configuration
PB10 ------> TIM2_CH3
PB11 ------> TIM2_CH4
/**TIM1 GPIO Configuration
PB15 ------> TIM1_CH3N
*/
GPIO_InitStruct.Pin = BAT_COOLING_PWM_Pin|BAT_COOLING_ENABLE_Pin;
GPIO_InitStruct.Pin = PWM_Battery_Cooling_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF1_TIM2;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
GPIO_InitStruct.Alternate = GPIO_AF4_TIM1;
HAL_GPIO_Init(PWM_Battery_Cooling_GPIO_Port, &GPIO_InitStruct);
/* USER CODE BEGIN TIM2_MspPostInit 1 */
/* USER CODE BEGIN TIM1_MspPostInit 1 */
/* USER CODE END TIM2_MspPostInit 1 */
}
else if(htim->Instance==TIM3)
{
/* USER CODE BEGIN TIM3_MspPostInit 0 */
/* USER CODE END TIM3_MspPostInit 0 */
__HAL_RCC_GPIOB_CLK_ENABLE();
/**TIM3 GPIO Configuration
PB0 ------> TIM3_CH3
PB1 ------> TIM3_CH4
*/
GPIO_InitStruct.Pin = ESC_L_PWM_Pin|ESC_R_PWM_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF2_TIM3;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* USER CODE BEGIN TIM3_MspPostInit 1 */
/* USER CODE END TIM3_MspPostInit 1 */
}
else if(htim->Instance==TIM4)
{
/* USER CODE BEGIN TIM4_MspPostInit 0 */
/* USER CODE END TIM4_MspPostInit 0 */
__HAL_RCC_GPIOB_CLK_ENABLE();
/**TIM4 GPIO Configuration
PB6 ------> TIM4_CH1
PB7 ------> TIM4_CH2
PB8 ------> TIM4_CH3
*/
GPIO_InitStruct.Pin = STATUS_LED_R_Pin|STATUS_LED_G_Pin|STATUS_LED_B_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF2_TIM4;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* USER CODE BEGIN TIM4_MspPostInit 1 */
/* USER CODE END TIM4_MspPostInit 1 */
/* USER CODE END TIM1_MspPostInit 1 */
}
else if(htim->Instance==TIM15)
{
@ -468,17 +356,17 @@ void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim)
/* USER CODE END TIM15_MspPostInit 0 */
__HAL_RCC_GPIOB_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**TIM15 GPIO Configuration
PB14 ------> TIM15_CH1
PB15 ------> TIM15_CH2
PA2 ------> TIM15_CH1
PA3 ------> TIM15_CH2
*/
GPIO_InitStruct.Pin = ESC_COOLING_ENABLE_Pin|ESC_COOLING_PWM_Pin;
GPIO_InitStruct.Pin = PWM_PG_FAN1_Pin|PWM_PG_FAN2_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF1_TIM15;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
GPIO_InitStruct.Alternate = GPIO_AF9_TIM15;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* USER CODE BEGIN TIM15_MspPostInit 1 */
@ -494,38 +382,16 @@ void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim)
*/
void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef* htim_pwm)
{
if(htim_pwm->Instance==TIM2)
if(htim_pwm->Instance==TIM1)
{
/* USER CODE BEGIN TIM2_MspDeInit 0 */
/* USER CODE BEGIN TIM1_MspDeInit 0 */
/* USER CODE END TIM2_MspDeInit 0 */
/* USER CODE END TIM1_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM2_CLK_DISABLE();
/* USER CODE BEGIN TIM2_MspDeInit 1 */
__HAL_RCC_TIM1_CLK_DISABLE();
/* USER CODE BEGIN TIM1_MspDeInit 1 */
/* USER CODE END TIM2_MspDeInit 1 */
}
else if(htim_pwm->Instance==TIM3)
{
/* USER CODE BEGIN TIM3_MspDeInit 0 */
/* USER CODE END TIM3_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM3_CLK_DISABLE();
/* USER CODE BEGIN TIM3_MspDeInit 1 */
/* USER CODE END TIM3_MspDeInit 1 */
}
else if(htim_pwm->Instance==TIM4)
{
/* USER CODE BEGIN TIM4_MspDeInit 0 */
/* USER CODE END TIM4_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM4_CLK_DISABLE();
/* USER CODE BEGIN TIM4_MspDeInit 1 */
/* USER CODE END TIM4_MspDeInit 1 */
/* USER CODE END TIM1_MspDeInit 1 */
}
else if(htim_pwm->Instance==TIM15)
{
@ -541,6 +407,71 @@ void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef* htim_pwm)
}
/**
* @brief UART MSP Initialization
* This function configures the hardware resources used in this example
* @param huart: UART handle pointer
* @retval None
*/
void HAL_UART_MspInit(UART_HandleTypeDef* huart)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(huart->Instance==USART1)
{
/* USER CODE BEGIN USART1_MspInit 0 */
/* USER CODE END USART1_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_USART1_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/**USART1 GPIO Configuration
PB6 ------> USART1_TX
PB7 ------> USART1_RX
*/
GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF7_USART1;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* USER CODE BEGIN USART1_MspInit 1 */
/* USER CODE END USART1_MspInit 1 */
}
}
/**
* @brief UART MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param huart: UART handle pointer
* @retval None
*/
void HAL_UART_MspDeInit(UART_HandleTypeDef* huart)
{
if(huart->Instance==USART1)
{
/* USER CODE BEGIN USART1_MspDeInit 0 */
/* USER CODE END USART1_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_USART1_CLK_DISABLE();
/**USART1 GPIO Configuration
PB6 ------> USART1_TX
PB7 ------> USART1_RX
*/
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_6|GPIO_PIN_7);
/* USER CODE BEGIN USART1_MspDeInit 1 */
/* USER CODE END USART1_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

Binary file not shown.

Before

Width:  |  Height:  |  Size: 2.3 MiB

File diff suppressed because one or more lines are too long

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,513 @@
/**
******************************************************************************
* @file stm32f3xx_hal_uart_ex.h
* @author MCD Application Team
* @brief Header file of UART HAL Extended module.
******************************************************************************
* @attention
*
* Copyright (c) 2016 STMicroelectronics.
* All rights reserved.
*
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef STM32F3xx_HAL_UART_EX_H
#define STM32F3xx_HAL_UART_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f3xx_hal_def.h"
/** @addtogroup STM32F3xx_HAL_Driver
* @{
*/
/** @addtogroup UARTEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup UARTEx_Exported_Types UARTEx Exported Types
* @{
*/
/**
* @brief UART wake up from stop mode parameters
*/
typedef struct
{
uint32_t WakeUpEvent; /*!< Specifies which event will activate the Wakeup from Stop mode flag (WUF).
This parameter can be a value of @ref UART_WakeUp_from_Stop_Selection.
If set to UART_WAKEUP_ON_ADDRESS, the two other fields below must
be filled up. */
uint16_t AddressLength; /*!< Specifies whether the address is 4 or 7-bit long.
This parameter can be a value of @ref UARTEx_WakeUp_Address_Length. */
uint8_t Address; /*!< UART/USART node address (7-bit long max). */
} UART_WakeUpTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup UARTEx_Exported_Constants UARTEx Exported Constants
* @{
*/
/** @defgroup UARTEx_Word_Length UARTEx Word Length
* @{
*/
#if defined(USART_CR1_M1)
#define UART_WORDLENGTH_7B USART_CR1_M1 /*!< 7-bit long UART frame */
#endif /* USART_CR1_M1 */
#define UART_WORDLENGTH_8B 0x00000000U /*!< 8-bit long UART frame */
#if defined (USART_CR1_M0)
#define UART_WORDLENGTH_9B USART_CR1_M0 /*!< 9-bit long UART frame */
#else
#define UART_WORDLENGTH_9B USART_CR1_M /*!< 9-bit long UART frame */
#endif /* USART_CR1_M0 */
/**
* @}
*/
/** @defgroup UARTEx_WakeUp_Address_Length UARTEx WakeUp Address Length
* @{
*/
#define UART_ADDRESS_DETECT_4B 0x00000000U /*!< 4-bit long wake-up address */
#define UART_ADDRESS_DETECT_7B USART_CR2_ADDM7 /*!< 7-bit long wake-up address */
/**
* @}
*/
/**
* @}
*/
/* Exported macros -----------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/** @addtogroup UARTEx_Exported_Functions
* @{
*/
/** @addtogroup UARTEx_Exported_Functions_Group1
* @{
*/
/* Initialization and de-initialization functions ****************************/
HAL_StatusTypeDef HAL_RS485Ex_Init(UART_HandleTypeDef *huart, uint32_t Polarity, uint32_t AssertionTime,
uint32_t DeassertionTime);
/**
* @}
*/
/** @addtogroup UARTEx_Exported_Functions_Group2
* @{
*/
void HAL_UARTEx_WakeupCallback(UART_HandleTypeDef *huart);
/**
* @}
*/
/** @addtogroup UARTEx_Exported_Functions_Group3
* @{
*/
/* Peripheral Control functions **********************************************/
HAL_StatusTypeDef HAL_UARTEx_StopModeWakeUpSourceConfig(UART_HandleTypeDef *huart, UART_WakeUpTypeDef WakeUpSelection);
HAL_StatusTypeDef HAL_UARTEx_EnableStopMode(UART_HandleTypeDef *huart);
HAL_StatusTypeDef HAL_UARTEx_DisableStopMode(UART_HandleTypeDef *huart);
HAL_StatusTypeDef HAL_MultiProcessorEx_AddressLength_Set(UART_HandleTypeDef *huart, uint32_t AddressLength);
HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint16_t *RxLen,
uint32_t Timeout);
HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size);
HAL_UART_RxEventTypeTypeDef HAL_UARTEx_GetRxEventType(UART_HandleTypeDef *huart);
/**
* @}
*/
/**
* @}
*/
/* Private macros ------------------------------------------------------------*/
/** @defgroup UARTEx_Private_Macros UARTEx Private Macros
* @{
*/
/** @brief Report the UART clock source.
* @param __HANDLE__ specifies the UART Handle.
* @param __CLOCKSOURCE__ output variable.
* @retval UART clocking source, written in __CLOCKSOURCE__.
*/
#if defined(STM32F302xE) || defined(STM32F303xE) || defined(STM32F398xx) || defined(STM32F302xC) \
|| defined(STM32F303xC) || defined(STM32F358xx)
#define UART_GETCLOCKSOURCE(__HANDLE__,__CLOCKSOURCE__) \
do { \
if((__HANDLE__)->Instance == USART1) \
{ \
switch(__HAL_RCC_GET_USART1_SOURCE()) \
{ \
case RCC_USART1CLKSOURCE_PCLK2: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_PCLK2; \
break; \
case RCC_USART1CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_HSI; \
break; \
case RCC_USART1CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART1CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_LSE; \
break; \
default: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_UNDEFINED; \
break; \
} \
} \
else if((__HANDLE__)->Instance == USART2) \
{ \
switch(__HAL_RCC_GET_USART2_SOURCE()) \
{ \
case RCC_USART2CLKSOURCE_PCLK1: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_PCLK1; \
break; \
case RCC_USART2CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_HSI; \
break; \
case RCC_USART2CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART2CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_LSE; \
break; \
default: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_UNDEFINED; \
break; \
} \
} \
else if((__HANDLE__)->Instance == USART3) \
{ \
switch(__HAL_RCC_GET_USART3_SOURCE()) \
{ \
case RCC_USART3CLKSOURCE_PCLK1: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_PCLK1; \
break; \
case RCC_USART3CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_HSI; \
break; \
case RCC_USART3CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART3CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_LSE; \
break; \
default: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_UNDEFINED; \
break; \
} \
} \
else if((__HANDLE__)->Instance == UART4) \
{ \
switch(__HAL_RCC_GET_UART4_SOURCE()) \
{ \
case RCC_UART4CLKSOURCE_PCLK1: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_PCLK1; \
break; \
case RCC_UART4CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_HSI; \
break; \
case RCC_UART4CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_UART4CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_LSE; \
break; \
default: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_UNDEFINED; \
break; \
} \
} \
else if ((__HANDLE__)->Instance == UART5) \
{ \
switch(__HAL_RCC_GET_UART5_SOURCE()) \
{ \
case RCC_UART5CLKSOURCE_PCLK1: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_PCLK1; \
break; \
case RCC_UART5CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_HSI; \
break; \
case RCC_UART5CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_UART5CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_LSE; \
break; \
default: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_UNDEFINED; \
break; \
} \
} \
else \
{ \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_UNDEFINED; \
} \
} while(0U)
#elif defined(STM32F303x8) || defined(STM32F334x8) || defined(STM32F328xx) || defined(STM32F301x8) \
|| defined(STM32F302x8) || defined(STM32F318xx)
#define UART_GETCLOCKSOURCE(__HANDLE__,__CLOCKSOURCE__) \
do { \
if((__HANDLE__)->Instance == USART1) \
{ \
switch(__HAL_RCC_GET_USART1_SOURCE()) \
{ \
case RCC_USART1CLKSOURCE_PCLK1: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_PCLK1; \
break; \
case RCC_USART1CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_HSI; \
break; \
case RCC_USART1CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART1CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_LSE; \
break; \
default: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_UNDEFINED; \
break; \
} \
} \
else if((__HANDLE__)->Instance == USART2) \
{ \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_PCLK1; \
} \
else if((__HANDLE__)->Instance == USART3) \
{ \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_PCLK1; \
} \
else \
{ \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_UNDEFINED; \
} \
} while(0U)
#else
#define UART_GETCLOCKSOURCE(__HANDLE__,__CLOCKSOURCE__) \
do { \
if((__HANDLE__)->Instance == USART1) \
{ \
switch(__HAL_RCC_GET_USART1_SOURCE()) \
{ \
case RCC_USART1CLKSOURCE_PCLK2: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_PCLK2; \
break; \
case RCC_USART1CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_HSI; \
break; \
case RCC_USART1CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART1CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_LSE; \
break; \
default: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_UNDEFINED; \
break; \
} \
} \
else if((__HANDLE__)->Instance == USART2) \
{ \
switch(__HAL_RCC_GET_USART2_SOURCE()) \
{ \
case RCC_USART2CLKSOURCE_PCLK1: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_PCLK1; \
break; \
case RCC_USART2CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_HSI; \
break; \
case RCC_USART2CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART2CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_LSE; \
break; \
default: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_UNDEFINED; \
break; \
} \
} \
else if((__HANDLE__)->Instance == USART3) \
{ \
switch(__HAL_RCC_GET_USART3_SOURCE()) \
{ \
case RCC_USART3CLKSOURCE_PCLK1: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_PCLK1; \
break; \
case RCC_USART3CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_HSI; \
break; \
case RCC_USART3CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART3CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_LSE; \
break; \
default: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_UNDEFINED; \
break; \
} \
} \
else \
{ \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_UNDEFINED; \
} \
} while(0U)
#endif /* STM32F302xE || STM32F303xE || STM32F398xx || STM32F302xC || STM32F303xC || STM32F358xx */
/** @brief Report the UART mask to apply to retrieve the received data
* according to the word length and to the parity bits activation.
* @note If PCE = 1, the parity bit is not included in the data extracted
* by the reception API().
* This masking operation is not carried out in the case of
* DMA transfers.
* @param __HANDLE__ specifies the UART Handle.
* @retval None, the mask to apply to UART RDR register is stored in (__HANDLE__)->Mask field.
*/
#if defined (USART_CR1_M1)
#define UART_MASK_COMPUTATION(__HANDLE__) \
do { \
if ((__HANDLE__)->Init.WordLength == UART_WORDLENGTH_9B) \
{ \
if ((__HANDLE__)->Init.Parity == UART_PARITY_NONE) \
{ \
(__HANDLE__)->Mask = 0x01FFU ; \
} \
else \
{ \
(__HANDLE__)->Mask = 0x00FFU ; \
} \
} \
else if ((__HANDLE__)->Init.WordLength == UART_WORDLENGTH_8B) \
{ \
if ((__HANDLE__)->Init.Parity == UART_PARITY_NONE) \
{ \
(__HANDLE__)->Mask = 0x00FFU ; \
} \
else \
{ \
(__HANDLE__)->Mask = 0x007FU ; \
} \
} \
else if ((__HANDLE__)->Init.WordLength == UART_WORDLENGTH_7B) \
{ \
if ((__HANDLE__)->Init.Parity == UART_PARITY_NONE) \
{ \
(__HANDLE__)->Mask = 0x007FU ; \
} \
else \
{ \
(__HANDLE__)->Mask = 0x003FU ; \
} \
} \
else \
{ \
(__HANDLE__)->Mask = 0x0000U; \
} \
} while(0U)
#else
#define UART_MASK_COMPUTATION(__HANDLE__) \
do { \
if ((__HANDLE__)->Init.WordLength == UART_WORDLENGTH_9B) \
{ \
if ((__HANDLE__)->Init.Parity == UART_PARITY_NONE) \
{ \
(__HANDLE__)->Mask = 0x01FFU ; \
} \
else \
{ \
(__HANDLE__)->Mask = 0x00FFU ; \
} \
} \
else if ((__HANDLE__)->Init.WordLength == UART_WORDLENGTH_8B) \
{ \
if ((__HANDLE__)->Init.Parity == UART_PARITY_NONE) \
{ \
(__HANDLE__)->Mask = 0x00FFU ; \
} \
else \
{ \
(__HANDLE__)->Mask = 0x007FU ; \
} \
} \
else \
{ \
(__HANDLE__)->Mask = 0x0000U; \
} \
} while(0U)
#endif /* USART_CR1_M1 */
/**
* @brief Ensure that UART frame length is valid.
* @param __LENGTH__ UART frame length.
* @retval SET (__LENGTH__ is valid) or RESET (__LENGTH__ is invalid)
*/
#if defined (USART_CR1_M1)
#define IS_UART_WORD_LENGTH(__LENGTH__) (((__LENGTH__) == UART_WORDLENGTH_7B) || \
((__LENGTH__) == UART_WORDLENGTH_8B) || \
((__LENGTH__) == UART_WORDLENGTH_9B))
#else
#define IS_UART_WORD_LENGTH(__LENGTH__) (((__LENGTH__) == UART_WORDLENGTH_8B) || \
((__LENGTH__) == UART_WORDLENGTH_9B))
#endif /* USART_CR1_M1 */
/**
* @brief Ensure that UART wake-up address length is valid.
* @param __ADDRESS__ UART wake-up address length.
* @retval SET (__ADDRESS__ is valid) or RESET (__ADDRESS__ is invalid)
*/
#define IS_UART_ADDRESSLENGTH_DETECT(__ADDRESS__) (((__ADDRESS__) == UART_ADDRESS_DETECT_4B) || \
((__ADDRESS__) == UART_ADDRESS_DETECT_7B))
/**
* @}
*/
/* Private functions ---------------------------------------------------------*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* STM32F3xx_HAL_UART_EX_H */

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,775 @@
/**
******************************************************************************
* @file stm32f3xx_hal_uart_ex.c
* @author MCD Application Team
* @brief Extended UART HAL module driver.
* This file provides firmware functions to manage the following extended
* functionalities of the Universal Asynchronous Receiver Transmitter Peripheral (UART).
* + Initialization and de-initialization functions
* + Peripheral Control functions
*
*
******************************************************************************
* @attention
*
* Copyright (c) 2016 STMicroelectronics.
* All rights reserved.
*
* 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.
*
******************************************************************************
@verbatim
==============================================================================
##### UART peripheral extended features #####
==============================================================================
(#) Declare a UART_HandleTypeDef handle structure.
(#) For the UART RS485 Driver Enable mode, initialize the UART registers
by calling the HAL_RS485Ex_Init() API.
@endverbatim
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32f3xx_hal.h"
/** @addtogroup STM32F3xx_HAL_Driver
* @{
*/
/** @defgroup UARTEx UARTEx
* @brief UART Extended HAL module driver
* @{
*/
#ifdef HAL_UART_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macros ------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/** @defgroup UARTEx_Private_Functions UARTEx Private Functions
* @{
*/
static void UARTEx_Wakeup_AddressConfig(UART_HandleTypeDef *huart, UART_WakeUpTypeDef WakeUpSelection);
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup UARTEx_Exported_Functions UARTEx Exported Functions
* @{
*/
/** @defgroup UARTEx_Exported_Functions_Group1 Initialization and de-initialization functions
* @brief Extended Initialization and Configuration Functions
*
@verbatim
===============================================================================
##### Initialization and Configuration functions #####
===============================================================================
[..]
This subsection provides a set of functions allowing to initialize the USARTx or the UARTy
in asynchronous mode.
(+) For the asynchronous mode the parameters below can be configured:
(++) Baud Rate
(++) Word Length
(++) Stop Bit
(++) Parity: If the parity is enabled, then the MSB bit of the data written
in the data register is transmitted but is changed by the parity bit.
(++) Hardware flow control
(++) Receiver/transmitter modes
(++) Over Sampling Method
(++) One-Bit Sampling Method
(+) For the asynchronous mode, the following advanced features can be configured as well:
(++) TX and/or RX pin level inversion
(++) data logical level inversion
(++) RX and TX pins swap
(++) RX overrun detection disabling
(++) DMA disabling on RX error
(++) MSB first on communication line
(++) auto Baud rate detection
[..]
The HAL_RS485Ex_Init() API follows the UART RS485 mode configuration
procedures (details for the procedures are available in reference manual).
@endverbatim
Depending on the frame length defined by the M1 and M0 bits (7-bit,
8-bit or 9-bit), the possible UART formats are listed in the
following table.
Table 1. UART frame format.
+-----------------------------------------------------------------------+
| M1 bit | M0 bit | PCE bit | UART frame |
|---------|---------|-----------|---------------------------------------|
| 0 | 0 | 0 | | SB | 8 bit data | STB | |
|---------|---------|-----------|---------------------------------------|
| 0 | 0 | 1 | | SB | 7 bit data | PB | STB | |
|---------|---------|-----------|---------------------------------------|
| 0 | 1 | 0 | | SB | 9 bit data | STB | |
|---------|---------|-----------|---------------------------------------|
| 0 | 1 | 1 | | SB | 8 bit data | PB | STB | |
|---------|---------|-----------|---------------------------------------|
| 1 | 0 | 0 | | SB | 7 bit data | STB | |
|---------|---------|-----------|---------------------------------------|
| 1 | 0 | 1 | | SB | 6 bit data | PB | STB | |
+-----------------------------------------------------------------------+
* @{
*/
/**
* @brief Initialize the RS485 Driver enable feature according to the specified
* parameters in the UART_InitTypeDef and creates the associated handle.
* @param huart UART handle.
* @param Polarity Select the driver enable polarity.
* This parameter can be one of the following values:
* @arg @ref UART_DE_POLARITY_HIGH DE signal is active high
* @arg @ref UART_DE_POLARITY_LOW DE signal is active low
* @param AssertionTime Driver Enable assertion time:
* 5-bit value defining the time between the activation of the DE (Driver Enable)
* signal and the beginning of the start bit. It is expressed in sample time
* units (1/8 or 1/16 bit time, depending on the oversampling rate)
* @param DeassertionTime Driver Enable deassertion time:
* 5-bit value defining the time between the end of the last stop bit, in a
* transmitted message, and the de-activation of the DE (Driver Enable) signal.
* It is expressed in sample time units (1/8 or 1/16 bit time, depending on the
* oversampling rate).
* @retval HAL status
*/
HAL_StatusTypeDef HAL_RS485Ex_Init(UART_HandleTypeDef *huart, uint32_t Polarity, uint32_t AssertionTime,
uint32_t DeassertionTime)
{
uint32_t temp;
/* Check the UART handle allocation */
if (huart == NULL)
{
return HAL_ERROR;
}
/* Check the Driver Enable UART instance */
assert_param(IS_UART_DRIVER_ENABLE_INSTANCE(huart->Instance));
/* Check the Driver Enable polarity */
assert_param(IS_UART_DE_POLARITY(Polarity));
/* Check the Driver Enable assertion time */
assert_param(IS_UART_ASSERTIONTIME(AssertionTime));
/* Check the Driver Enable deassertion time */
assert_param(IS_UART_DEASSERTIONTIME(DeassertionTime));
if (huart->gState == HAL_UART_STATE_RESET)
{
/* Allocate lock resource and initialize it */
huart->Lock = HAL_UNLOCKED;
#if (USE_HAL_UART_REGISTER_CALLBACKS == 1)
UART_InitCallbacksToDefault(huart);
if (huart->MspInitCallback == NULL)
{
huart->MspInitCallback = HAL_UART_MspInit;
}
/* Init the low level hardware */
huart->MspInitCallback(huart);
#else
/* Init the low level hardware : GPIO, CLOCK, CORTEX */
HAL_UART_MspInit(huart);
#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */
}
huart->gState = HAL_UART_STATE_BUSY;
/* Disable the Peripheral */
__HAL_UART_DISABLE(huart);
/* Set the UART Communication parameters */
if (UART_SetConfig(huart) == HAL_ERROR)
{
return HAL_ERROR;
}
if (huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT)
{
UART_AdvFeatureConfig(huart);
}
/* Enable the Driver Enable mode by setting the DEM bit in the CR3 register */
SET_BIT(huart->Instance->CR3, USART_CR3_DEM);
/* Set the Driver Enable polarity */
MODIFY_REG(huart->Instance->CR3, USART_CR3_DEP, Polarity);
/* Set the Driver Enable assertion and deassertion times */
temp = (AssertionTime << UART_CR1_DEAT_ADDRESS_LSB_POS);
temp |= (DeassertionTime << UART_CR1_DEDT_ADDRESS_LSB_POS);
MODIFY_REG(huart->Instance->CR1, (USART_CR1_DEDT | USART_CR1_DEAT), temp);
/* Enable the Peripheral */
__HAL_UART_ENABLE(huart);
/* TEACK and/or REACK to check before moving huart->gState and huart->RxState to Ready */
return (UART_CheckIdleState(huart));
}
/**
* @}
*/
/** @defgroup UARTEx_Exported_Functions_Group2 IO operation functions
* @brief Extended functions
*
@verbatim
===============================================================================
##### IO operation functions #####
===============================================================================
This subsection provides a set of Wakeup and FIFO mode related callback functions.
(#) Wakeup from Stop mode Callback:
(+) HAL_UARTEx_WakeupCallback()
@endverbatim
* @{
*/
/**
* @brief UART wakeup from Stop mode callback.
* @param huart UART handle.
* @retval None
*/
__weak void HAL_UARTEx_WakeupCallback(UART_HandleTypeDef *huart)
{
/* Prevent unused argument(s) compilation warning */
UNUSED(huart);
/* NOTE : This function should not be modified, when the callback is needed,
the HAL_UARTEx_WakeupCallback can be implemented in the user file.
*/
}
/**
* @}
*/
/** @defgroup UARTEx_Exported_Functions_Group3 Peripheral Control functions
* @brief Extended Peripheral Control functions
*
@verbatim
===============================================================================
##### Peripheral Control functions #####
===============================================================================
[..] This section provides the following functions:
(+) HAL_MultiProcessorEx_AddressLength_Set() API optionally sets the UART node address
detection length to more than 4 bits for multiprocessor address mark wake up.
(+) HAL_UARTEx_StopModeWakeUpSourceConfig() API defines the wake-up from stop mode
trigger: address match, Start Bit detection or RXNE bit status.
(+) HAL_UARTEx_EnableStopMode() API enables the UART to wake up the MCU from stop mode
(+) HAL_UARTEx_DisableStopMode() API disables the above functionality
[..] This subsection also provides a set of additional functions providing enhanced reception
services to user. (For example, these functions allow application to handle use cases
where number of data to be received is unknown).
(#) Compared to standard reception services which only consider number of received
data elements as reception completion criteria, these functions also consider additional events
as triggers for updating reception status to caller :
(+) Detection of inactivity period (RX line has not been active for a given period).
(++) RX inactivity detected by IDLE event, i.e. RX line has been in idle state (normally high state)
for 1 frame time, after last received byte.
(++) RX inactivity detected by RTO, i.e. line has been in idle state
for a programmable time, after last received byte.
(+) Detection that a specific character has been received.
(#) There are two mode of transfer:
(+) Blocking mode: The reception is performed in polling mode, until either expected number of data is received,
or till IDLE event occurs. Reception is handled only during function execution.
When function exits, no data reception could occur. HAL status and number of actually received data elements,
are returned by function after finishing transfer.
(+) Non-Blocking mode: The reception is performed using Interrupts or DMA.
These API's return the HAL status.
The end of the data processing will be indicated through the
dedicated UART IRQ when using Interrupt mode or the DMA IRQ when using DMA mode.
The HAL_UARTEx_RxEventCallback() user callback will be executed during Receive process
The HAL_UART_ErrorCallback()user callback will be executed when a reception error is detected.
(#) Blocking mode API:
(+) HAL_UARTEx_ReceiveToIdle()
(#) Non-Blocking mode API with Interrupt:
(+) HAL_UARTEx_ReceiveToIdle_IT()
(#) Non-Blocking mode API with DMA:
(+) HAL_UARTEx_ReceiveToIdle_DMA()
@endverbatim
* @{
*/
/**
* @brief By default in multiprocessor mode, when the wake up method is set
* to address mark, the UART handles only 4-bit long addresses detection;
* this API allows to enable longer addresses detection (6-, 7- or 8-bit
* long).
* @note Addresses detection lengths are: 6-bit address detection in 7-bit data mode,
* 7-bit address detection in 8-bit data mode, 8-bit address detection in 9-bit data mode.
* @param huart UART handle.
* @param AddressLength This parameter can be one of the following values:
* @arg @ref UART_ADDRESS_DETECT_4B 4-bit long address
* @arg @ref UART_ADDRESS_DETECT_7B 6-, 7- or 8-bit long address
* @retval HAL status
*/
HAL_StatusTypeDef HAL_MultiProcessorEx_AddressLength_Set(UART_HandleTypeDef *huart, uint32_t AddressLength)
{
/* Check the UART handle allocation */
if (huart == NULL)
{
return HAL_ERROR;
}
/* Check the address length parameter */
assert_param(IS_UART_ADDRESSLENGTH_DETECT(AddressLength));
huart->gState = HAL_UART_STATE_BUSY;
/* Disable the Peripheral */
__HAL_UART_DISABLE(huart);
/* Set the address length */
MODIFY_REG(huart->Instance->CR2, USART_CR2_ADDM7, AddressLength);
/* Enable the Peripheral */
__HAL_UART_ENABLE(huart);
/* TEACK and/or REACK to check before moving huart->gState to Ready */
return (UART_CheckIdleState(huart));
}
/**
* @brief Set Wakeup from Stop mode interrupt flag selection.
* @note It is the application responsibility to enable the interrupt used as
* usart_wkup interrupt source before entering low-power mode.
* @param huart UART handle.
* @param WakeUpSelection Address match, Start Bit detection or RXNE/RXFNE bit status.
* This parameter can be one of the following values:
* @arg @ref UART_WAKEUP_ON_ADDRESS
* @arg @ref UART_WAKEUP_ON_STARTBIT
* @arg @ref UART_WAKEUP_ON_READDATA_NONEMPTY
* @retval HAL status
*/
HAL_StatusTypeDef HAL_UARTEx_StopModeWakeUpSourceConfig(UART_HandleTypeDef *huart, UART_WakeUpTypeDef WakeUpSelection)
{
HAL_StatusTypeDef status = HAL_OK;
uint32_t tickstart;
/* check the wake-up from stop mode UART instance */
assert_param(IS_UART_WAKEUP_FROMSTOP_INSTANCE(huart->Instance));
/* check the wake-up selection parameter */
assert_param(IS_UART_WAKEUP_SELECTION(WakeUpSelection.WakeUpEvent));
/* Process Locked */
__HAL_LOCK(huart);
huart->gState = HAL_UART_STATE_BUSY;
/* Disable the Peripheral */
__HAL_UART_DISABLE(huart);
/* Set the wake-up selection scheme */
MODIFY_REG(huart->Instance->CR3, USART_CR3_WUS, WakeUpSelection.WakeUpEvent);
if (WakeUpSelection.WakeUpEvent == UART_WAKEUP_ON_ADDRESS)
{
UARTEx_Wakeup_AddressConfig(huart, WakeUpSelection);
}
/* Enable the Peripheral */
__HAL_UART_ENABLE(huart);
/* Init tickstart for timeout management */
tickstart = HAL_GetTick();
/* Wait until REACK flag is set */
if (UART_WaitOnFlagUntilTimeout(huart, USART_ISR_REACK, RESET, tickstart, HAL_UART_TIMEOUT_VALUE) != HAL_OK)
{
status = HAL_TIMEOUT;
}
else
{
/* Initialize the UART State */
huart->gState = HAL_UART_STATE_READY;
}
/* Process Unlocked */
__HAL_UNLOCK(huart);
return status;
}
/**
* @brief Enable UART Stop Mode.
* @note The UART is able to wake up the MCU from Stop 1 mode as long as UART clock is HSI or LSE.
* @param huart UART handle.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_UARTEx_EnableStopMode(UART_HandleTypeDef *huart)
{
/* Process Locked */
__HAL_LOCK(huart);
/* Set UESM bit */
ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_UESM);
/* Process Unlocked */
__HAL_UNLOCK(huart);
return HAL_OK;
}
/**
* @brief Disable UART Stop Mode.
* @param huart UART handle.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_UARTEx_DisableStopMode(UART_HandleTypeDef *huart)
{
/* Process Locked */
__HAL_LOCK(huart);
/* Clear UESM bit */
ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_UESM);
/* Process Unlocked */
__HAL_UNLOCK(huart);
return HAL_OK;
}
/**
* @brief Receive an amount of data in blocking mode till either the expected number of data
* is received or an IDLE event occurs.
* @note HAL_OK is returned if reception is completed (expected number of data has been received)
* or if reception is stopped after IDLE event (less than the expected number of data has been received)
* In this case, RxLen output parameter indicates number of data available in reception buffer.
* @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01),
* the received data is handled as a set of uint16_t. In this case, Size must indicate the number
* of uint16_t available through pData.
* @param huart UART handle.
* @param pData Pointer to data buffer (uint8_t or uint16_t data elements).
* @param Size Amount of data elements (uint8_t or uint16_t) to be received.
* @param RxLen Number of data elements finally received
* (could be lower than Size, in case reception ends on IDLE event)
* @param Timeout Timeout duration expressed in ms (covers the whole reception sequence).
* @retval HAL status
*/
HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint16_t *RxLen,
uint32_t Timeout)
{
uint8_t *pdata8bits;
uint16_t *pdata16bits;
uint16_t uhMask;
uint32_t tickstart;
/* Check that a Rx process is not already ongoing */
if (huart->RxState == HAL_UART_STATE_READY)
{
if ((pData == NULL) || (Size == 0U))
{
return HAL_ERROR;
}
huart->ErrorCode = HAL_UART_ERROR_NONE;
huart->RxState = HAL_UART_STATE_BUSY_RX;
huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE;
huart->RxEventType = HAL_UART_RXEVENT_TC;
/* Init tickstart for timeout management */
tickstart = HAL_GetTick();
huart->RxXferSize = Size;
huart->RxXferCount = Size;
/* Computation of UART mask to apply to RDR register */
UART_MASK_COMPUTATION(huart);
uhMask = huart->Mask;
/* In case of 9bits/No Parity transfer, pRxData needs to be handled as a uint16_t pointer */
if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE))
{
pdata8bits = NULL;
pdata16bits = (uint16_t *) pData;
}
else
{
pdata8bits = pData;
pdata16bits = NULL;
}
/* Initialize output number of received elements */
*RxLen = 0U;
/* as long as data have to be received */
while (huart->RxXferCount > 0U)
{
/* Check if IDLE flag is set */
if (__HAL_UART_GET_FLAG(huart, UART_FLAG_IDLE))
{
/* Clear IDLE flag in ISR */
__HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_IDLEF);
/* If Set, but no data ever received, clear flag without exiting loop */
/* If Set, and data has already been received, this means Idle Event is valid : End reception */
if (*RxLen > 0U)
{
huart->RxEventType = HAL_UART_RXEVENT_IDLE;
huart->RxState = HAL_UART_STATE_READY;
return HAL_OK;
}
}
/* Check if RXNE flag is set */
if (__HAL_UART_GET_FLAG(huart, UART_FLAG_RXNE))
{
if (pdata8bits == NULL)
{
*pdata16bits = (uint16_t)(huart->Instance->RDR & uhMask);
pdata16bits++;
}
else
{
*pdata8bits = (uint8_t)(huart->Instance->RDR & (uint8_t)uhMask);
pdata8bits++;
}
/* Increment number of received elements */
*RxLen += 1U;
huart->RxXferCount--;
}
/* Check for the Timeout */
if (Timeout != HAL_MAX_DELAY)
{
if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U))
{
huart->RxState = HAL_UART_STATE_READY;
return HAL_TIMEOUT;
}
}
}
/* Set number of received elements in output parameter : RxLen */
*RxLen = huart->RxXferSize - huart->RxXferCount;
/* At end of Rx process, restore huart->RxState to Ready */
huart->RxState = HAL_UART_STATE_READY;
return HAL_OK;
}
else
{
return HAL_BUSY;
}
}
/**
* @brief Receive an amount of data in interrupt mode till either the expected number of data
* is received or an IDLE event occurs.
* @note Reception is initiated by this function call. Further progress of reception is achieved thanks
* to UART interrupts raised by RXNE and IDLE events. Callback is called at end of reception indicating
* number of received data elements.
* @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01),
* the received data is handled as a set of uint16_t. In this case, Size must indicate the number
* of uint16_t available through pData.
* @param huart UART handle.
* @param pData Pointer to data buffer (uint8_t or uint16_t data elements).
* @param Size Amount of data elements (uint8_t or uint16_t) to be received.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size)
{
HAL_StatusTypeDef status;
/* Check that a Rx process is not already ongoing */
if (huart->RxState == HAL_UART_STATE_READY)
{
if ((pData == NULL) || (Size == 0U))
{
return HAL_ERROR;
}
/* Set Reception type to reception till IDLE Event*/
huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE;
huart->RxEventType = HAL_UART_RXEVENT_TC;
status = UART_Start_Receive_IT(huart, pData, Size);
/* Check Rx process has been successfully started */
if (status == HAL_OK)
{
if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE)
{
__HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_IDLEF);
ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_IDLEIE);
}
else
{
/* In case of errors already pending when reception is started,
Interrupts may have already been raised and lead to reception abortion.
(Overrun error for instance).
In such case Reception Type has been reset to HAL_UART_RECEPTION_STANDARD. */
status = HAL_ERROR;
}
}
return status;
}
else
{
return HAL_BUSY;
}
}
/**
* @brief Receive an amount of data in DMA mode till either the expected number
* of data is received or an IDLE event occurs.
* @note Reception is initiated by this function call. Further progress of reception is achieved thanks
* to DMA services, transferring automatically received data elements in user reception buffer and
* calling registered callbacks at half/end of reception. UART IDLE events are also used to consider
* reception phase as ended. In all cases, callback execution will indicate number of received data elements.
* @note When the UART parity is enabled (PCE = 1), the received data contain
* the parity bit (MSB position).
* @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01),
* the received data is handled as a set of uint16_t. In this case, Size must indicate the number
* of uint16_t available through pData.
* @param huart UART handle.
* @param pData Pointer to data buffer (uint8_t or uint16_t data elements).
* @param Size Amount of data elements (uint8_t or uint16_t) to be received.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size)
{
HAL_StatusTypeDef status;
/* Check that a Rx process is not already ongoing */
if (huart->RxState == HAL_UART_STATE_READY)
{
if ((pData == NULL) || (Size == 0U))
{
return HAL_ERROR;
}
/* Set Reception type to reception till IDLE Event*/
huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE;
huart->RxEventType = HAL_UART_RXEVENT_TC;
status = UART_Start_Receive_DMA(huart, pData, Size);
/* Check Rx process has been successfully started */
if (status == HAL_OK)
{
if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE)
{
__HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_IDLEF);
ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_IDLEIE);
}
else
{
/* In case of errors already pending when reception is started,
Interrupts may have already been raised and lead to reception abortion.
(Overrun error for instance).
In such case Reception Type has been reset to HAL_UART_RECEPTION_STANDARD. */
status = HAL_ERROR;
}
}
return status;
}
else
{
return HAL_BUSY;
}
}
/**
* @brief Provide Rx Event type that has lead to RxEvent callback execution.
* @note When HAL_UARTEx_ReceiveToIdle_IT() or HAL_UARTEx_ReceiveToIdle_DMA() API are called, progress
* of reception process is provided to application through calls of Rx Event callback (either default one
* HAL_UARTEx_RxEventCallback() or user registered one). As several types of events could occur (IDLE event,
* Half Transfer, or Transfer Complete), this function allows to retrieve the Rx Event type that has lead
* to Rx Event callback execution.
* @note This function is expected to be called within the user implementation of Rx Event Callback,
* in order to provide the accurate value :
* In Interrupt Mode :
* - HAL_UART_RXEVENT_TC : when Reception has been completed (expected nb of data has been received)
* - HAL_UART_RXEVENT_IDLE : when Idle event occurred prior reception has been completed (nb of
* received data is lower than expected one)
* In DMA Mode :
* - HAL_UART_RXEVENT_TC : when Reception has been completed (expected nb of data has been received)
* - HAL_UART_RXEVENT_HT : when half of expected nb of data has been received
* - HAL_UART_RXEVENT_IDLE : when Idle event occurred prior reception has been completed (nb of
* received data is lower than expected one).
* In DMA mode, RxEvent callback could be called several times;
* When DMA is configured in Normal Mode, HT event does not stop Reception process;
* When DMA is configured in Circular Mode, HT, TC or IDLE events don't stop Reception process;
* @param huart UART handle.
* @retval Rx Event Type (return vale will be a value of @ref UART_RxEvent_Type_Values)
*/
HAL_UART_RxEventTypeTypeDef HAL_UARTEx_GetRxEventType(UART_HandleTypeDef *huart)
{
/* Return Rx Event type value, as stored in UART handle */
return (huart->RxEventType);
}
/**
* @}
*/
/**
* @}
*/
/** @addtogroup UARTEx_Private_Functions
* @{
*/
/**
* @brief Initialize the UART wake-up from stop mode parameters when triggered by address detection.
* @param huart UART handle.
* @param WakeUpSelection UART wake up from stop mode parameters.
* @retval None
*/
static void UARTEx_Wakeup_AddressConfig(UART_HandleTypeDef *huart, UART_WakeUpTypeDef WakeUpSelection)
{
assert_param(IS_UART_ADDRESSLENGTH_DETECT(WakeUpSelection.AddressLength));
/* Set the USART address length */
MODIFY_REG(huart->Instance->CR2, USART_CR2_ADDM7, WakeUpSelection.AddressLength);
/* Set the USART address node */
MODIFY_REG(huart->Instance->CR2, USART_CR2_ADD, ((uint32_t)WakeUpSelection.Address << UART_CR2_ADDRESS_LSB_POS));
}
/**
* @}
*/
#endif /* HAL_UART_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/

View File

@ -1,5 +1,5 @@
##########################################################################################################################
# File automatically-generated by tool: [projectgenerator] version: [4.3.0-B58] date: [Wed Jul 10 09:28:32 EEST 2024]
# File automatically-generated by tool: [projectgenerator] version: [4.3.0-B58] date: [Mon Jun 03 16:11:34 EEST 2024]
##########################################################################################################################
# ------------------------------------------------
@ -59,6 +59,8 @@ Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_spi.c \
Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_spi_ex.c \
Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_tim.c \
Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_tim_ex.c \
Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_uart.c \
Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_uart_ex.c \
Core/Src/system_stm32f3xx.c
# ASM sources

View File

@ -18,41 +18,42 @@ Mcu.IP3=RCC
Mcu.IP4=SPI1
Mcu.IP5=SYS
Mcu.IP6=TIM1
Mcu.IP7=TIM2
Mcu.IP7=TIM15
Mcu.IP8=USART1
Mcu.IPNb=9
Mcu.Name=STM32F302C(B-C)Tx
Mcu.Package=LQFP48
Mcu.Pin0=PF0-OSC_IN
Mcu.Pin1=PF1-OSC_OUT
Mcu.Pin10=PB1
Mcu.Pin11=PB2
Mcu.Pin12=PB11
Mcu.Pin13=PB13
Mcu.Pin14=PB14
Mcu.Pin15=PB15
Mcu.Pin16=PA8
Mcu.Pin17=PA9
Mcu.Pin18=PA10
Mcu.Pin19=PA11
Mcu.Pin10=PB0
Mcu.Pin11=PB1
Mcu.Pin12=PB2
Mcu.Pin13=PB11
Mcu.Pin14=PB13
Mcu.Pin15=PB14
Mcu.Pin16=PB15
Mcu.Pin17=PA8
Mcu.Pin18=PA9
Mcu.Pin19=PA10
Mcu.Pin2=PA0
Mcu.Pin20=PA12
Mcu.Pin21=PA13
Mcu.Pin22=PA14
Mcu.Pin23=PA15
Mcu.Pin24=PB3
Mcu.Pin25=PB6
Mcu.Pin26=PB7
Mcu.Pin27=PB9
Mcu.Pin28=VP_SYS_VS_Systick
Mcu.Pin20=PA11
Mcu.Pin21=PA12
Mcu.Pin22=PA13
Mcu.Pin23=PA14
Mcu.Pin24=PA15
Mcu.Pin25=PB3
Mcu.Pin26=PB6
Mcu.Pin27=PB7
Mcu.Pin28=PB9
Mcu.Pin29=VP_SYS_VS_Systick
Mcu.Pin3=PA1
Mcu.Pin4=PA2
Mcu.Pin5=PA4
Mcu.Pin6=PA5
Mcu.Pin7=PA6
Mcu.Pin8=PA7
Mcu.Pin9=PB0
Mcu.PinsNb=29
Mcu.Pin5=PA3
Mcu.Pin6=PA4
Mcu.Pin7=PA5
Mcu.Pin8=PA6
Mcu.Pin9=PA7
Mcu.PinsNb=30
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F302CBTx
@ -98,8 +99,14 @@ PA14.Signal=SYS_JTCK-SWCLK
PA15.Locked=true
PA15.Mode=I2C
PA15.Signal=I2C1_SCL
PA2.GPIOParameters=GPIO_Label
PA2.GPIO_Label=PWM_PG_FAN1
PA2.Locked=true
PA2.Signal=S_TIM2_CH3
PA2.Signal=S_TIM15_CH1
PA3.GPIOParameters=GPIO_Label
PA3.GPIO_Label=PWM_PG_FAN2
PA3.Locked=true
PA3.Signal=S_TIM15_CH2
PA4.GPIOParameters=GPIO_Label
PA4.GPIO_Label=CSB
PA4.Locked=true
@ -185,7 +192,7 @@ ProjectManager.FreePins=true
ProjectManager.HalAssertFull=false
ProjectManager.HeapSize=0x200
ProjectManager.KeepUserCode=true
ProjectManager.LastFirmware=false
ProjectManager.LastFirmware=true
ProjectManager.LibraryCopy=1
ProjectManager.MainLocation=Core/Src
ProjectManager.NoMain=false
@ -201,7 +208,7 @@ ProjectManager.ToolChainLocation=
ProjectManager.UAScriptAfterPath=
ProjectManager.UAScriptBeforePath=
ProjectManager.UnderRoot=false
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_CAN_Init-CAN-false-HAL-true,4-MX_I2C1_Init-I2C1-false-HAL-true,5-MX_SPI1_Init-SPI1-false-HAL-true,6-MX_TIM15_Init-TIM15-false-HAL-true,6-MX_USART1_UART_Init-USART1-false-HAL-true,7-MX_TIM1_Init-TIM1-false-HAL-true
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_CAN_Init-CAN-false-HAL-true,4-MX_I2C1_Init-I2C1-false-HAL-true,5-MX_SPI1_Init-SPI1-false-HAL-true,6-MX_TIM15_Init-TIM15-false-HAL-true,7-MX_USART1_UART_Init-USART1-false-HAL-true,8-MX_TIM1_Init-TIM1-false-HAL-true
RCC.ADC12outputFreq_Value=16000000
RCC.AHBFreq_Value=16000000
RCC.APB1Freq_Value=16000000
@ -236,8 +243,10 @@ RCC.USART2Freq_Value=16000000
RCC.USART3Freq_Value=16000000
RCC.USBFreq_Value=16000000
RCC.VCOOutput2Freq_Value=4000000
SH.S_TIM2_CH3.0=TIM2_CH3,PWM Generation3 CH3
SH.S_TIM2_CH3.ConfNb=1
SH.S_TIM15_CH1.0=TIM15_CH1,PWM Generation1 CH1
SH.S_TIM15_CH1.ConfNb=1
SH.S_TIM15_CH2.0=TIM15_CH2,PWM Generation2 CH2
SH.S_TIM15_CH2.ConfNb=1
SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_32
SPI1.CalculateBaudRate=500.0 KBits/s
SPI1.DataSize=SPI_DATASIZE_8BIT
@ -247,9 +256,9 @@ SPI1.Mode=SPI_MODE_MASTER
SPI1.VirtualType=VM_MASTER
TIM1.Channel-PWM\ Generation3\ CH3N=TIM_CHANNEL_3
TIM1.IPParameters=Channel-PWM Generation3 CH3N
TIM2.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3
TIM2.IPParameters=Channel-PWM Generation3 CH3,Period
TIM2.Period=65535
TIM15.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
TIM15.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
TIM15.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation2 CH2
USART1.IPParameters=VirtualMode-Asynchronous
USART1.VirtualMode-Asynchronous=VM_ASYNC
VP_SYS_VS_Systick.Mode=SysTick

229
mvbms.ioc
View File

@ -13,55 +13,49 @@ CAN.NART=ENABLE
CAN.Prescaler=2
File.Version=6
GPIO.groupedBy=Group By Peripherals
I2C1.IPParameters=Timing
I2C1.Timing=0x00303D5B
I2C2.IPParameters=Timing
I2C2.Timing=0x00303D5B
KeepUserPlacement=true
Mcu.CPN=STM32F302CBT6
Mcu.Family=STM32F3
Mcu.IP0=CAN
Mcu.IP1=I2C1
Mcu.IP10=TIM15
Mcu.IP2=I2C2
Mcu.IP3=NVIC
Mcu.IP4=RCC
Mcu.IP5=SPI1
Mcu.IP6=SYS
Mcu.IP7=TIM2
Mcu.IP8=TIM3
Mcu.IP9=TIM4
Mcu.IPNb=11
Mcu.IP2=NVIC
Mcu.IP3=RCC
Mcu.IP4=SPI1
Mcu.IP5=SYS
Mcu.IP6=TIM1
Mcu.IP7=TIM15
Mcu.IP8=USART1
Mcu.IPNb=9
Mcu.Name=STM32F302C(B-C)Tx
Mcu.Package=LQFP48
Mcu.Pin0=PF0-OSC_IN
Mcu.Pin1=PF1-OSC_OUT
Mcu.Pin10=PB14
Mcu.Pin11=PB15
Mcu.Pin12=PA8
Mcu.Pin13=PA9
Mcu.Pin14=PA10
Mcu.Pin15=PA11
Mcu.Pin16=PA12
Mcu.Pin17=PA13
Mcu.Pin18=PA14
Mcu.Pin19=PA15
Mcu.Pin2=PA4
Mcu.Pin20=PB3
Mcu.Pin21=PB4
Mcu.Pin22=PB5
Mcu.Pin23=PB6
Mcu.Pin24=PB7
Mcu.Pin25=PB8
Mcu.Pin10=PB0
Mcu.Pin11=PB1
Mcu.Pin12=PB2
Mcu.Pin13=PB11
Mcu.Pin14=PB15
Mcu.Pin15=PA8
Mcu.Pin16=PA9
Mcu.Pin17=PA10
Mcu.Pin18=PA11
Mcu.Pin19=PA12
Mcu.Pin2=PA0
Mcu.Pin20=PA13
Mcu.Pin21=PA14
Mcu.Pin22=PA15
Mcu.Pin23=PB3
Mcu.Pin24=PB6
Mcu.Pin25=PB7
Mcu.Pin26=PB9
Mcu.Pin27=VP_SYS_VS_Systick
Mcu.Pin3=PA5
Mcu.Pin4=PA6
Mcu.Pin5=PA7
Mcu.Pin6=PB0
Mcu.Pin7=PB1
Mcu.Pin8=PB10
Mcu.Pin9=PB11
Mcu.Pin3=PA1
Mcu.Pin4=PA2
Mcu.Pin5=PA3
Mcu.Pin6=PA4
Mcu.Pin7=PA5
Mcu.Pin8=PA6
Mcu.Pin9=PA7
Mcu.PinsNb=28
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
@ -81,10 +75,20 @@ 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.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=PinState,GPIO_Label
PA0.GPIO_Label=RELAY_EN
PA0.Locked=true
PA0.PinState=GPIO_PIN_RESET
PA0.Signal=GPIO_Output
PA1.GPIOParameters=PinState,GPIO_Label
PA1.GPIO_Label=_60V_EN
PA1.Locked=true
PA1.PinState=GPIO_PIN_RESET
PA1.Signal=GPIO_Output
PA10.GPIOParameters=GPIO_Label
PA10.GPIO_Label=EEPROM_SDA
PA10.Mode=I2C
PA10.Signal=I2C2_SDA
PA10.GPIO_Label=CURRENT_SENSOR_ON
PA10.Locked=true
PA10.Signal=GPIO_Input
PA11.Locked=true
PA11.Mode=CAN_Activate
PA11.Signal=CAN_RX
@ -97,14 +101,19 @@ PA13.Signal=SYS_JTMS-SWDIO
PA14.Locked=true
PA14.Mode=Trace_Asynchronous_SW
PA14.Signal=SYS_JTCK-SWCLK
PA15.GPIOParameters=GPIO_Label
PA15.GPIO_Label=TMP_SCL
PA15.Locked=true
PA15.Mode=I2C
PA15.Signal=I2C1_SCL
PA4.GPIOParameters=GPIO_Speed,GPIO_Label
PA2.GPIOParameters=GPIO_Label
PA2.GPIO_Label=PWM_PG_FAN1
PA2.Locked=true
PA2.Signal=S_TIM15_CH1
PA3.GPIOParameters=GPIO_Label
PA3.GPIO_Label=PWM_PG_FAN2
PA3.Locked=true
PA3.Signal=S_TIM15_CH2
PA4.GPIOParameters=GPIO_Label
PA4.GPIO_Label=CSB
PA4.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
PA4.Locked=true
PA4.Signal=GPIO_Output
PA5.Locked=true
@ -116,65 +125,48 @@ PA6.Signal=SPI1_MISO
PA7.Locked=true
PA7.Mode=Full_Duplex_Master
PA7.Signal=SPI1_MOSI
PA8.GPIOParameters=GPIO_Speed,PinState,GPIO_PuPd,GPIO_Label
PA8.GPIO_Label=EEPROM_~{WC}
PA8.GPIO_PuPd=GPIO_NOPULL
PA8.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
PA8.GPIOParameters=GPIO_Label
PA8.GPIO_Label=RELAY_BATT_SIDE_ON
PA8.Locked=true
PA8.PinState=GPIO_PIN_RESET
PA8.Signal=GPIO_Output
PA8.Signal=GPIO_Input
PA9.GPIOParameters=GPIO_Label
PA9.GPIO_Label=EEPROM_SCL
PA9.Mode=I2C
PA9.Signal=I2C2_SCL
PB0.GPIOParameters=GPIO_Label
PB0.GPIO_Label=ESC_L_PWM
PA9.GPIO_Label=RELAY_ESC_SIDE_ON
PA9.Locked=true
PA9.Signal=GPIO_Input
PB0.GPIOParameters=PinState,GPIO_Label
PB0.GPIO_Label=STATUS_LED_R
PB0.Locked=true
PB0.Signal=S_TIM3_CH3
PB1.GPIOParameters=GPIO_Label
PB1.GPIO_Label=ESC_R_PWM
PB0.PinState=GPIO_PIN_SET
PB0.Signal=GPIO_Output
PB1.GPIOParameters=PinState,GPIO_Label
PB1.GPIO_Label=STATUS_LED_B
PB1.Locked=true
PB1.Signal=S_TIM3_CH4
PB10.GPIOParameters=GPIO_Label
PB10.GPIO_Label=BAT_COOLING_PWM
PB10.Locked=true
PB10.Signal=S_TIM2_CH3
PB11.GPIOParameters=GPIO_Label
PB11.GPIO_Label=BAT_COOLING_ENABLE
PB1.PinState=GPIO_PIN_SET
PB1.Signal=GPIO_Output
PB11.GPIOParameters=PinState,GPIO_Label
PB11.GPIO_Label=PRECHARGE_EN
PB11.Locked=true
PB11.Signal=S_TIM2_CH4
PB14.GPIOParameters=GPIO_Label
PB14.GPIO_Label=ESC_COOLING_ENABLE
PB14.Locked=true
PB14.Signal=S_TIM15_CH1
PB11.PinState=GPIO_PIN_RESET
PB11.Signal=GPIO_Output
PB15.GPIOParameters=GPIO_Label
PB15.GPIO_Label=ESC_COOLING_PWM
PB15.Signal=S_TIM15_CH2
PB15.GPIO_Label=PWM_Battery_Cooling
PB15.Locked=true
PB15.Mode=PWM Generation3 CH3N
PB15.Signal=TIM1_CH3N
PB2.GPIOParameters=PinState,GPIO_Label
PB2.GPIO_Label=STATUS_LED_G
PB2.Locked=true
PB2.PinState=GPIO_PIN_SET
PB2.Signal=GPIO_Output
PB3.Locked=true
PB3.Mode=Trace_Asynchronous_SW
PB3.Signal=SYS_JTDO-TRACESWO
PB4.GPIOParameters=GPIO_Label
PB4.GPIO_Label=RELAY_ENABLE
PB4.Locked=true
PB4.Signal=GPIO_Output
PB5.GPIOParameters=GPIO_Label
PB5.GPIO_Label=PRECHARGE_ENABLE
PB5.Locked=true
PB5.Signal=GPIO_Output
PB6.GPIOParameters=GPIO_PuPd,GPIO_Label
PB6.GPIO_Label=STATUS_LED_R
PB6.GPIO_PuPd=GPIO_PULLDOWN
PB6.Signal=S_TIM4_CH1
PB7.GPIOParameters=GPIO_PuPd,GPIO_Label
PB7.GPIO_Label=STATUS_LED_G
PB7.GPIO_PuPd=GPIO_PULLDOWN
PB7.Signal=S_TIM4_CH2
PB8.GPIOParameters=GPIO_PuPd,GPIO_Label
PB8.GPIO_Label=STATUS_LED_B
PB8.GPIO_PuPd=GPIO_PULLDOWN
PB8.Signal=S_TIM4_CH3
PB9.GPIOParameters=GPIO_Label
PB9.GPIO_Label=TMP_SDA
PB6.Locked=true
PB6.Mode=Asynchronous
PB6.Signal=USART1_TX
PB7.Locked=true
PB7.Mode=Asynchronous
PB7.Signal=USART1_RX
PB9.Locked=true
PB9.Mode=I2C
PB9.Signal=I2C1_SDA
@ -215,7 +207,7 @@ ProjectManager.ToolChainLocation=
ProjectManager.UAScriptAfterPath=
ProjectManager.UAScriptBeforePath=
ProjectManager.UnderRoot=false
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_CAN_Init-CAN-false-HAL-true,4-MX_I2C1_Init-I2C1-false-HAL-true,5-MX_SPI1_Init-SPI1-false-HAL-true,6-MX_TIM15_Init-TIM15-false-HAL-true,7-MX_I2C2_Init-I2C2-false-HAL-true,8-MX_TIM2_Init-TIM2-false-HAL-true,9-MX_TIM3_Init-TIM3-false-HAL-true,10-MX_TIM4_Init-TIM4-false-HAL-true
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_CAN_Init-CAN-false-HAL-true,4-MX_I2C1_Init-I2C1-false-HAL-true,5-MX_SPI1_Init-SPI1-false-HAL-true,6-MX_TIM15_Init-TIM15-false-HAL-true,7-MX_USART1_UART_Init-USART1-false-HAL-true,8-MX_TIM1_Init-TIM1-false-HAL-true
RCC.ADC12outputFreq_Value=16000000
RCC.AHBFreq_Value=16000000
RCC.APB1Freq_Value=16000000
@ -230,11 +222,9 @@ RCC.HSEPLLFreq_Value=16000000
RCC.HSE_VALUE=16000000
RCC.HSIPLLFreq_Value=4000000
RCC.HSI_VALUE=8000000
RCC.I2C1Freq_Value=16000000
RCC.I2C2Freq_Value=16000000
RCC.I2c1ClockSelection=RCC_I2C1CLKSOURCE_SYSCLK
RCC.I2c2ClockSelection=RCC_I2C2CLKSOURCE_SYSCLK
RCC.IPParameters=ADC12outputFreq_Value,AHBFreq_Value,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CortexFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,HSEPLLFreq_Value,HSE_VALUE,HSIPLLFreq_Value,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2c1ClockSelection,I2c2ClockSelection,LSE_VALUE,LSI_VALUE,MCOFreq_Value,PLLCLKFreq_Value,PLLMCOFreq_Value,PLLMUL,RTCFreq_Value,RTCHSEDivFreq_Value,SYSCLKFreq_VALUE,SYSCLKSourceVirtual,TIM1Freq_Value,TIM2Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOOutput2Freq_Value
RCC.I2C1Freq_Value=8000000
RCC.I2C2Freq_Value=8000000
RCC.IPParameters=ADC12outputFreq_Value,AHBFreq_Value,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CortexFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,HSEPLLFreq_Value,HSE_VALUE,HSIPLLFreq_Value,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,LSE_VALUE,LSI_VALUE,MCOFreq_Value,PLLCLKFreq_Value,PLLMCOFreq_Value,PLLMUL,RTCFreq_Value,RTCHSEDivFreq_Value,SYSCLKFreq_VALUE,SYSCLKSourceVirtual,TIM1Freq_Value,TIM2Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOOutput2Freq_Value
RCC.LSE_VALUE=32768
RCC.LSI_VALUE=40000
RCC.MCOFreq_Value=16000000
@ -256,20 +246,6 @@ SH.S_TIM15_CH1.0=TIM15_CH1,PWM Generation1 CH1
SH.S_TIM15_CH1.ConfNb=1
SH.S_TIM15_CH2.0=TIM15_CH2,PWM Generation2 CH2
SH.S_TIM15_CH2.ConfNb=1
SH.S_TIM2_CH3.0=TIM2_CH3,PWM Generation3 CH3
SH.S_TIM2_CH3.ConfNb=1
SH.S_TIM2_CH4.0=TIM2_CH4,PWM Generation4 CH4
SH.S_TIM2_CH4.ConfNb=1
SH.S_TIM3_CH3.0=TIM3_CH3,PWM Generation3 CH3
SH.S_TIM3_CH3.ConfNb=1
SH.S_TIM3_CH4.0=TIM3_CH4,PWM Generation4 CH4
SH.S_TIM3_CH4.ConfNb=1
SH.S_TIM4_CH1.0=TIM4_CH1,PWM Generation1 CH1
SH.S_TIM4_CH1.ConfNb=1
SH.S_TIM4_CH2.0=TIM4_CH2,PWM Generation2 CH2
SH.S_TIM4_CH2.ConfNb=1
SH.S_TIM4_CH3.0=TIM4_CH3,PWM Generation3 CH3
SH.S_TIM4_CH3.ConfNb=1
SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_32
SPI1.CalculateBaudRate=500.0 KBits/s
SPI1.DataSize=SPI_DATASIZE_8BIT
@ -277,23 +253,16 @@ SPI1.Direction=SPI_DIRECTION_2LINES
SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,DataSize,BaudRatePrescaler
SPI1.Mode=SPI_MODE_MASTER
SPI1.VirtualType=VM_MASTER
TIM1.Channel-PWM\ Generation3\ CH3N=TIM_CHANNEL_3
TIM1.IPParameters=Channel-PWM Generation3 CH3N
TIM15.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
TIM15.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
TIM15.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation2 CH2
TIM2.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3
TIM2.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
TIM2.IPParameters=Channel-PWM Generation3 CH3,Channel-PWM Generation4 CH4
TIM3.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3
TIM3.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
TIM3.IPParameters=Channel-PWM Generation3 CH3,Channel-PWM Generation4 CH4,Period,Prescaler
TIM3.Period=39999
TIM3.Prescaler=7
TIM4.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
TIM4.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
TIM4.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3
TIM4.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation2 CH2,Channel-PWM Generation3 CH3,Period,Prescaler
TIM4.Period=255
TIM4.Prescaler=624
TIM15.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation2 CH2,Prescaler,Period,Pulse-PWM Generation1 CH1
TIM15.Period=39999
TIM15.Prescaler=7
TIM15.Pulse-PWM\ Generation1\ CH1=0
USART1.IPParameters=VirtualMode-Asynchronous
USART1.VirtualMode-Asynchronous=VM_ASYNC
VP_SYS_VS_Systick.Mode=SysTick
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
board=custom