restructured repo

This commit is contained in:
n.jayaprakash
2024-05-12 14:08:58 +02:00
parent ae73476c42
commit fdab1c3a7b
1088 changed files with 184190 additions and 193 deletions

View File

@ -0,0 +1,110 @@
/*
* CAN_Communication.c
*
* Created on: 24. April, 2024
* Author: nived
*/
#include "CAN_Communication.h"
#include "Channel_Control.h"
#include "Current_Monitoring.h"
rx_status_frame rxstate = {};
volatile uint8_t canmsg_received = 0;
extern PortExtenderGPIO EN_Ports;
extern CurrentMeasurements current_measurements_adc_val;
void can_init(CAN_HandleTypeDef* hcan) {
ftcan_init(hcan);
ftcan_add_filter(0x00, 0x00); // No Filter
}
void can_sendloop() {
static uint8_t additionaltxcouter = 0;
uint8_t status_data[7];
status_data[0] = EN_Ports.porta.porta;
status_data[1] = EN_Ports.portb.portb;
status_data[2] = rxstate.tsacfans;
status_data[3] = rxstate.radiatorfans;
status_data[4] = rxstate.pwmaggregat;
status_data[5] = rxstate.pwmpumps;
status_data[6] = 0xFF ^ rxstate.checksum;
ftcan_transmit(TX_STATUS_MSG_ID, status_data, 7);
uint8_t data[8];
return;
if (additionaltxcouter < 4) {
switch (additionaltxcouter) {
case 0:
data[0] = current_measurements_adc_val.always_on >> 8;
data[1] = current_measurements_adc_val.always_on & 0xFF;
data[2] = current_measurements_adc_val.misc >> 8;
data[3] = current_measurements_adc_val.misc & 0xFF;
data[4] = current_measurements_adc_val.inverter >> 8;
data[5] = current_measurements_adc_val.inverter & 0xFF;
data[6] = current_measurements_adc_val.shutdown_circuit >> 8;
data[7] = current_measurements_adc_val.shutdown_circuit & 0xFF;
ftcan_transmit(CUR_CHANNELS_1_ID, data, 8);
break;
case 1:
data[0] = current_measurements_adc_val.fans >> 8;
data[1] = current_measurements_adc_val.fans & 0xFF;
data[2] = current_measurements_adc_val.pumps >> 8;
data[3] = current_measurements_adc_val.pumps & 0xFF;
data[4] = current_measurements_adc_val.aggregat >> 8;
data[5] = current_measurements_adc_val.aggregat & 0xFF;
data[6] = current_measurements_adc_val.steering >> 8;
data[7] = current_measurements_adc_val.steering & 0xFF;
ftcan_transmit(CUR_CHANNELS_2_ID, data, 8);
break;
case 2:
data[0] = current_measurements_adc_val.ebsvalve_1 >> 8;
data[1] = current_measurements_adc_val.ebsvalve_1 & 0xFF;
data[2] = current_measurements_adc_val.ebsvalve_2 >> 8;
data[3] = current_measurements_adc_val.ebsvalve_2 & 0xFF;
data[4] = current_measurements_adc_val.modevalve_1 >> 8;
data[5] = current_measurements_adc_val.modevalve_1 & 0xFF;
data[6] = current_measurements_adc_val.modevalve_2 >> 8;
data[7] = current_measurements_adc_val.modevalve_2 & 0xFF;
ftcan_transmit(CUR_CHANNELS_3_ID, data, 8);
break;
case 3:
data[0] = current_measurements_adc_val.sensorbox >> 8;
data[1] = current_measurements_adc_val.sensorbox & 0xFF;
data[2] = current_measurements_adc_val.servicebrake >> 8;
data[3] = current_measurements_adc_val.servicebrake & 0xFF;
data[4] = current_measurements_adc_val.servos >> 8;
data[5] = current_measurements_adc_val.servos & 0xFF;
data[6] = current_measurements_adc_val.shutdown_circuit >> 8;
data[7] = current_measurements_adc_val.shutdown_circuit & 0xFF;
ftcan_transmit(CUR_CHANNELS_4_ID, data, 8);
break;
default:
break;
}
additionaltxcouter++;
} else {
additionaltxcouter = 0;
}
}
void ftcan_msg_received_cb(uint16_t id, size_t datalen, const uint8_t* data) {
canmsg_received = 1;
if ((id == RX_STATUS_MSG_ID) && (datalen == 7)) {
rxstate.iostatus.porta.porta = data[0];
rxstate.iostatus.portb.portb = data[1];
rxstate.radiatorfans = data[2];
rxstate.tsacfans = data[3];
rxstate.pwmaggregat = data[4];
rxstate.pwmpumps = data[5];
rxstate.checksum = data[6];
}
}

View File

@ -0,0 +1,86 @@
/*
* Channel_Control.c
*
* Created on: 24. April, 2024
* Author: nived
*/
#include "Channel_Control.h"
#include "PCA9535D_Driver.h"
PortExtenderGPIO EN_Ports;
uint8_t timer3_running = 0;
uint8_t timer2_running = 0;
TIM_HandleTypeDef* pwmtimer3;
TIM_HandleTypeDef* pwmtimer2;
void ChannelControl_init(I2C_HandleTypeDef* hi2c, TIM_HandleTypeDef* timer3,
TIM_HandleTypeDef* timer2) {
pwmtimer3 = timer3;
pwmtimer2 = timer2;
PCA9535_init(hi2c, 0);
PCA9535_setGPIOPortOutput(PC9535_PORTA, 0x00);
PCA9535_setGPIOPortOutput(PC9535_PORTB, 0x00);
PCA9535_setGPIOPortDirection(PC9535_PORTA, 0x00);
PCA9535_setGPIOPortDirection(PC9535_PORTB, 0x00);
EN_Ports.porta.porta = 0;
EN_Ports.portb.portb = 0;
EN_Ports.porta.alwayson = 1;
ChannelControl_UpdateGPIOs(EN_Ports);
ChannelControl_UpdatePWMs(0, 0, 0, 0);
}
void ChannelControl_UpdateGPIOs(PortExtenderGPIO UpdatePorts) { // ctrl + left click auf portextender
EN_Ports = UpdatePorts;
UpdatePorts.porta.alwayson = 1; // Always on stays always on
// PCA9535_setGPIOPortOutput(PC9535_PORTA, UpdatePorts.porta.porta);
// PCA9535_setGPIOPortOutput(PC9535_PORTB, UpdatePorts.portb.portb);
gpio_port_b testb={};
testb.en14=1;
PCA9535_setGPIOPortOutput(PC9535_PORTB, testb.portb);
gpio_port_a testa={};
testa.en13=1;
PCA9535_setGPIOPortOutput(PC9535_PORTA, testa.porta);
}
void ChannelControl_UpdatePWMs(uint8_t radiatorfans,uint8_t tsacfans , uint8_t pwmaggregat,
uint8_t pwmpumps){
return;
pwmtimer3->Instance->CCR4 = pwmpumps << 8;
pwmtimer3->Instance->CCR1 = radiatorfans << 8;
pwmtimer2->Instance->CCR2 = tsacfans << 8;
if (timer3_running) {
if ((pwmpumps == 0) && (radiatorfans == 0)) {
timer3_running = 0;
HAL_TIM_PWM_Stop(pwmtimer3, TIM_CHANNEL_4);
HAL_TIM_PWM_Stop(pwmtimer3, TIM_CHANNEL_1);
}
} else {
if ( (pwmpumps != 0) || (radiatorfans != 0)) {
timer3_running = 1;
HAL_TIM_PWM_Start(pwmtimer3, TIM_CHANNEL_4);
HAL_TIM_PWM_Start(pwmtimer3, TIM_CHANNEL_1);
}
}
if (timer2_running) {
if (tsacfans == 0) {
timer2_running = 0;
HAL_TIM_PWM_Stop(pwmtimer2, TIM_CHANNEL_2);
}
} else {
if (tsacfans != 0) {
timer2_running = 1;
HAL_TIM_PWM_Start(pwmtimer2, TIM_CHANNEL_2);
}
}
}

View File

@ -0,0 +1,124 @@
/*
* Current_Monitoring.c
*
* Created on: 24. April, 2024
* Author: nived
*/
#include "Current_Monitoring.h"
#include "main.h"
volatile union adc1_channels {
struct {
uint16_t isense9;
uint16_t isense8;
uint16_t isense2;
uint16_t isense3;
uint16_t dietemp;
uint16_t vbat;
uint16_t vrefint;
} adcbank1;
uint16_t adcbuffer[7]; // array 7*16 bit
} adc_channels1;
// ADC's anpassen adc1 - 9, adc2 ist halt 5 , buffer anpassen und namen auch ( isense usw)
volatile union adc2_channels {
struct {
uint16_t isense11;
uint16_t isense10;
uint16_t isense5;
uint16_t isense4;
uint16_t isense1;
uint16_t isense7;
uint16_t isense6;
} adcbank1;
uint16_t adcbuffer[7];
} adc_channels2;
CurrentMeasurements current_measurements_adc_val;
GPIO_PinState adcbank1 = GPIO_PIN_RESET;
GPIO_PinState adcbank2 = GPIO_PIN_RESET;
ADC_HandleTypeDef* adc1;
ADC_HandleTypeDef* adc2;
void currentMonitor_init(ADC_HandleTypeDef* hadc1, ADC_HandleTypeDef* hadc2, // init ist initilisierung
TIM_HandleTypeDef* trigtim) {
HAL_GPIO_WritePin(DSEL_3_GPIO_Port, DSEL_3_Pin, adcbank1); //DSELs zu adc's neu zuordnen
HAL_GPIO_WritePin(DSEL_4_GPIO_Port, DSEL_4_Pin, adcbank2);
HAL_GPIO_WritePin(DSEL_5_GPIO_Port, DSEL_5_Pin, adcbank2);
HAL_GPIO_WritePin(DSEL_6_GPIO_Port, DSEL_6_Pin, adcbank2);
adc1 = hadc1;
adc2 = hadc2;
HAL_TIM_Base_Start(trigtim);
HAL_ADC_Start_DMA(hadc1, (uint32_t*)adc_channels1.adcbuffer, 7);
HAL_ADC_Start_DMA(hadc2, (uint32_t*)adc_channels2.adcbuffer, 7); // wie adc mit dma geht , red mit jasper
}
uint8_t currentMonitor_checklimits() { return 0; }
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc) {
if (hadc == adc2) {
if (adcbank2 == GPIO_PIN_RESET) {
current_measurements_adc_val.always_on =
adc_channels2.adcbank1.isense10 * CURR_SENSE_FACTOR_2A;
current_measurements_adc_val.modevalve_1 =
adc_channels2.adcbank1.isense5 * CURR_SENSE_FACTOR_5A;
current_measurements_adc_val.ebsvalve_1 =
adc_channels2.adcbank1.isense4 * CURR_SENSE_FACTOR_5A;
adcbank2 = GPIO_PIN_SET;
} else {
current_measurements_adc_val.shutdown_circuit =
adc_channels2.adcbank1.isense10 * CURR_SENSE_FACTOR_2A;
current_measurements_adc_val.modevalve_2 =
adc_channels2.adcbank1.isense5 * CURR_SENSE_FACTOR_5A;
current_measurements_adc_val.ebsvalve_2 =
adc_channels2.adcbank1.isense4 * CURR_SENSE_FACTOR_5A;
adcbank2 = GPIO_PIN_RESET;
}
current_measurements_adc_val.fans =
adc_channels2.adcbank1.isense6 * CURR_SENSE_FACTOR_21A;
current_measurements_adc_val.aggregat =
adc_channels2.adcbank1.isense1 * CURR_SENSE_FACTOR_21A;
current_measurements_adc_val.inverter =
adc_channels2.adcbank1.isense11 * CURR_SENSE_FACTOR_10A;
current_measurements_adc_val.steering =
adc_channels2.adcbank1.isense7 * CURR_SENSE_FACTOR_10A;
HAL_GPIO_WritePin(DSEL_4_GPIO_Port, DSEL_4_Pin,
adcbank2);
HAL_GPIO_WritePin(DSEL_5_GPIO_Port, DSEL_5_Pin,
adcbank2);
HAL_GPIO_WritePin(DSEL_6_GPIO_Port, DSEL_6_Pin,
adcbank2);
}
if (hadc == adc1) {
if (adcbank1 == GPIO_PIN_RESET) {
current_measurements_adc_val.servos =
adc_channels1.adcbank1.isense8 * CURR_SENSE_FACTOR_5A;
adcbank1 = GPIO_PIN_SET;
} else {
current_measurements_adc_val.misc =
adc_channels1.adcbank1.isense8 * CURR_SENSE_FACTOR_5A;
adcbank1 = GPIO_PIN_RESET;
}
current_measurements_adc_val.servicebrake =
adc_channels1.adcbank1.isense3 * CURR_SENSE_FACTOR_2A;
current_measurements_adc_val.sensorbox =
adc_channels1.adcbank1.isense2 * CURR_SENSE_FACTOR_21A;
current_measurements_adc_val.pumps =
adc_channels1.adcbank1.isense9 * CURR_SENSE_FACTOR_10A;
HAL_GPIO_WritePin(DSEL_3_GPIO_Port, DSEL_3_Pin,
adcbank1);
}
}
// current monitoring c und h anpassen

167
Core/Src/PCA9535D_Driver.c Normal file
View File

@ -0,0 +1,167 @@
/**
* @file PCA9535D_Driver.c
*
* Driver Software for the PCA9535D Port exteneder Peripheral
*
* @author Maximilian Mönikes
*/
#include "PCA9535D_Driver.h"
static I2C_HandleTypeDef* pcai2c;
static uint8_t deviceadr = 0;
static uint8_t gpioa_shadow_reg_out = 0;
static uint8_t gpiob_shadow_reg_out = 0;
static uint8_t gpioa_shadow_reg_dir = 0xFF;
static uint8_t gpiob_shadow_reg_dir = 0xFF;
static uint8_t gpioa_shadow_reg_inv = 0;
static uint8_t gpiob_shadow_reg_inv = 0;
/**@brief Initalize the PCA9535 Port extender
*
* All GPIOs are Initialized as Inputs with normal Polarity
*
* @param hi2c Pointer to I2C Handle struct for the peripheral in
* @param subaddress of the port expander
* @retval none
*/
void PCA9535_init(I2C_HandleTypeDef* hi2c, uint8_t subadr) {
pcai2c = hi2c;
deviceadr = PCA_I2C_BASE_ADDRESS | (subadr << 1);
uint8_t initalizationconfig[7] = {0x02, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF};
HAL_I2C_Master_Transmit(pcai2c, deviceadr, initalizationconfig, 7, 1000);
}
void PCA9535_setGPIOPinDirection(uint8_t Port, uint8_t pin, uint8_t state) {
if (Port == PC9535_PORTA) {
if (state)
gpioa_shadow_reg_dir |= (1 << pin);
else
gpioa_shadow_reg_dir &= ~(1 << pin);
uint8_t data[2] = {CONFIGURATION_REG_BASE_ADDRESS, gpioa_shadow_reg_dir};
HAL_I2C_Master_Transmit(pcai2c, deviceadr, data, 2, 1000);
} else if (Port == PC9535_PORTB) {
if (state)
gpiob_shadow_reg_dir |= (1 << pin);
else
gpiob_shadow_reg_dir &= ~(1 << pin);
uint8_t data[2] = {CONFIGURATION_REG_BASE_ADDRESS | 1,
gpiob_shadow_reg_dir};
HAL_I2C_Master_Transmit(pcai2c, deviceadr, data, 2, 1000);
}
}
void PCA9535_setGPIOPinOutput(uint8_t Port, uint8_t pin, uint8_t state) {
if (Port == PC9535_PORTA) {
if (state)
gpioa_shadow_reg_out |= (1 << pin);
else
gpioa_shadow_reg_out &= ~(1 << pin);
uint8_t data[2] = {OUTPUT_REG_BASE_ADDRESS, gpioa_shadow_reg_out};
HAL_I2C_Master_Transmit(pcai2c, deviceadr, data, 2, 1000);
} else if (Port == PC9535_PORTB) {
if (state)
gpiob_shadow_reg_out |= (1 << pin);
else
gpiob_shadow_reg_out &= ~(1 << pin);
uint8_t data[2] = {OUTPUT_REG_BASE_ADDRESS | 1, gpiob_shadow_reg_out};
HAL_I2C_Master_Transmit(pcai2c, deviceadr, data, 2, 1000);
}
}
void PCA9535_invertGPIOPinPolarity(uint8_t Port, uint8_t pin, uint8_t state) {
if (Port == PC9535_PORTA) {
if (state)
gpioa_shadow_reg_inv |= (1 << pin);
else
gpioa_shadow_reg_inv &= ~(1 << pin);
uint8_t data[2] = {INPUT_POLARITY_INVERSION_REG_BASE_ADDRESS,
gpioa_shadow_reg_inv};
HAL_I2C_Master_Transmit(pcai2c, deviceadr, data, 2, 1000);
} else if (Port == PC9535_PORTB) {
if (state)
gpiob_shadow_reg_inv |= (1 << pin);
else
gpiob_shadow_reg_inv &= ~(1 << pin);
uint8_t data[2] = {INPUT_POLARITY_INVERSION_REG_BASE_ADDRESS | 1,
gpiob_shadow_reg_inv};
HAL_I2C_Master_Transmit(pcai2c, deviceadr, data, 2, 1000);
}
}
uint8_t PCA9535_readGPIOPinInput(uint8_t Port, uint8_t pin) {
if (Port == PC9535_PORTA) {
uint8_t command = INPUT_REG_BASE_ADDRESS;
HAL_I2C_Master_Transmit(pcai2c, deviceadr, &command, 1, 1000);
} else if (Port == PC9535_PORTB) {
uint8_t command = INPUT_REG_BASE_ADDRESS | 1;
HAL_I2C_Master_Transmit(pcai2c, deviceadr, &command, 1, 1000);
}
uint8_t reval = 0;
HAL_I2C_Master_Receive(pcai2c, deviceadr, &reval, 1, 1000);
reval &= (1 << pin);
reval = reval >> (pin);
return reval;
}
void PCA9535_setGPIOPortDirection(uint8_t Port, uint8_t bitmask) {
uint8_t command[2] = {0x00, bitmask};
if (Port == PC9535_PORTA) {
gpioa_shadow_reg_dir = bitmask;
command[0] = CONFIGURATION_REG_BASE_ADDRESS;
} else if (Port == PC9535_PORTB) {
gpiob_shadow_reg_dir = bitmask;
command[0] = CONFIGURATION_REG_BASE_ADDRESS | 1;
}
HAL_I2C_Master_Transmit(pcai2c, deviceadr, command, 2, 1000);
}
void PCA9535_setGPIOPortOutput(uint8_t Port, uint8_t bitmask) {
uint8_t command[2] = {0x00, bitmask};
if (Port == PC9535_PORTA) {
gpioa_shadow_reg_out = bitmask;
command[0] = OUTPUT_REG_BASE_ADDRESS;
} else if (Port == PC9535_PORTB) {
gpiob_shadow_reg_out = bitmask;
command[0] = OUTPUT_REG_BASE_ADDRESS | 1;
}
HAL_I2C_Master_Transmit(pcai2c, deviceadr, command, 2, 1000);
}
void PCA9535_invertGPIOPortPolarity(uint8_t Port, uint8_t bitmask) {
uint8_t command[2] = {0x00, bitmask};
if (Port == PC9535_PORTA) {
gpioa_shadow_reg_inv = bitmask;
command[0] = INPUT_POLARITY_INVERSION_REG_BASE_ADDRESS;
} else if (Port == PC9535_PORTB) {
gpiob_shadow_reg_inv = bitmask;
command[0] = INPUT_POLARITY_INVERSION_REG_BASE_ADDRESS | 1;
}
HAL_I2C_Master_Transmit(pcai2c, deviceadr, command, 2, 1000);
}
uint8_t PCA9535_readGPIOPortInput(uint8_t Port) {
uint8_t command = 0;
if (Port == PC9535_PORTB)
command |= INPUT_REG_BASE_ADDRESS;
else if (Port == PC9535_PORTA)
command |= INPUT_REG_BASE_ADDRESS | 1;
HAL_I2C_Master_Transmit(pcai2c, deviceadr, &command, 1, 1000);
uint8_t reval = 0;
HAL_I2C_Master_Receive(pcai2c, deviceadr, &reval, 1, 1000);
return reval;
}

273
Core/Src/can-halal.c Normal file
View File

@ -0,0 +1,273 @@
#include "can-halal.h"
#include <string.h>
#if defined(FTCAN_IS_BXCAN)
static CAN_HandleTypeDef *hcan;
HAL_StatusTypeDef ftcan_init(CAN_HandleTypeDef *handle) {
hcan = handle;
HAL_StatusTypeDef status =
HAL_CAN_ActivateNotification(hcan, CAN_IT_RX_FIFO0_MSG_PENDING);
if (status != HAL_OK) {
return status;
}
return HAL_CAN_Start(hcan);
}
HAL_StatusTypeDef ftcan_transmit(uint16_t id, const uint8_t *data,
size_t datalen) {
static CAN_TxHeaderTypeDef header;
header.StdId = id;
header.IDE = CAN_ID_STD;
header.RTR = CAN_RTR_DATA;
header.DLC = datalen;
uint32_t mailbox;
return HAL_CAN_AddTxMessage(hcan, &header, data, &mailbox);
}
HAL_StatusTypeDef ftcan_add_filter(uint16_t id, uint16_t mask) {
static uint32_t next_filter_no = 0;
static CAN_FilterTypeDef filter;
if (next_filter_no % 2 == 0) {
filter.FilterIdHigh = id << 5;
filter.FilterMaskIdHigh = mask << 5;
filter.FilterIdLow = id << 5;
filter.FilterMaskIdLow = mask << 5;
} else {
// Leave high filter untouched from the last configuration
filter.FilterIdLow = id << 5;
filter.FilterMaskIdLow = mask << 5;
}
filter.FilterFIFOAssignment = CAN_FILTER_FIFO0;
filter.FilterBank = next_filter_no / 2;
if (filter.FilterBank > FTCAN_NUM_FILTERS + 1) {
return HAL_ERROR;
}
filter.FilterMode = CAN_FILTERMODE_IDMASK;
filter.FilterScale = CAN_FILTERSCALE_16BIT;
filter.FilterActivation = CAN_FILTER_ENABLE;
// Disable slave filters
// TODO: Some STM32 have multiple CAN peripherals, and one uses the slave
// filter bank
filter.SlaveStartFilterBank = FTCAN_NUM_FILTERS;
HAL_StatusTypeDef status = HAL_CAN_ConfigFilter(hcan, &filter);
if (status == HAL_OK) {
next_filter_no++;
}
return status;
}
void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *handle) {
if (handle != hcan) {
return;
}
CAN_RxHeaderTypeDef header;
uint8_t data[8];
if (HAL_CAN_GetRxMessage(hcan, CAN_RX_FIFO0, &header, data) != HAL_OK) {
return;
}
if (header.IDE != CAN_ID_STD) {
return;
}
ftcan_msg_received_cb(header.StdId, header.DLC, data);
}
#elif defined(FTCAN_IS_FDCAN)
static FDCAN_HandleTypeDef *hcan;
HAL_StatusTypeDef ftcan_init(FDCAN_HandleTypeDef *handle) {
hcan = handle;
HAL_StatusTypeDef status =
HAL_FDCAN_ActivateNotification(hcan, FDCAN_IT_RX_FIFO0_NEW_MESSAGE, 0);
if (status != HAL_OK) {
return status;
}
// Reject non-matching messages
status =
HAL_FDCAN_ConfigGlobalFilter(hcan, FDCAN_REJECT, FDCAN_REJECT,
FDCAN_REJECT_REMOTE, FDCAN_REJECT_REMOTE);
if (status != HAL_OK) {
return status;
}
return HAL_FDCAN_Start(hcan);
}
HAL_StatusTypeDef ftcan_transmit(uint16_t id, const uint8_t *data,
size_t datalen) {
static FDCAN_TxHeaderTypeDef header;
header.Identifier = id;
header.IdType = FDCAN_STANDARD_ID;
header.TxFrameType = FDCAN_DATA_FRAME;
switch (datalen) {
case 0:
header.DataLength = FDCAN_DLC_BYTES_0;
break;
case 1:
header.DataLength = FDCAN_DLC_BYTES_1;
break;
case 2:
header.DataLength = FDCAN_DLC_BYTES_2;
break;
case 3:
header.DataLength = FDCAN_DLC_BYTES_3;
break;
case 4:
header.DataLength = FDCAN_DLC_BYTES_4;
break;
case 5:
header.DataLength = FDCAN_DLC_BYTES_5;
break;
case 6:
header.DataLength = FDCAN_DLC_BYTES_6;
break;
case 7:
header.DataLength = FDCAN_DLC_BYTES_7;
break;
case 8:
default:
header.DataLength = FDCAN_DLC_BYTES_8;
break;
}
header.ErrorStateIndicator = FDCAN_ESI_PASSIVE;
header.BitRateSwitch = FDCAN_BRS_OFF;
header.FDFormat = FDCAN_CLASSIC_CAN;
header.TxEventFifoControl = FDCAN_NO_TX_EVENTS;
// HAL_FDCAN_AddMessageToTxFifoQ doesn't modify the data, but it's not marked
// as const for some reason.
uint8_t *data_nonconst = (uint8_t *)data;
return HAL_FDCAN_AddMessageToTxFifoQ(hcan, &header, data_nonconst);
}
HAL_StatusTypeDef ftcan_add_filter(uint16_t id, uint16_t mask) {
static uint32_t next_filter_no = 0;
static FDCAN_FilterTypeDef filter;
filter.IdType = FDCAN_STANDARD_ID;
filter.FilterIndex = next_filter_no;
if (filter.FilterIndex > FTCAN_NUM_FILTERS + 1) {
return HAL_ERROR;
}
filter.FilterType = FDCAN_FILTER_MASK;
filter.FilterConfig = FDCAN_FILTER_TO_RXFIFO0;
filter.FilterID1 = id;
filter.FilterID2 = mask;
HAL_StatusTypeDef status = HAL_FDCAN_ConfigFilter(hcan, &filter);
if (status == HAL_OK) {
next_filter_no++;
}
return status;
}
void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef *handle,
uint32_t RxFifo0ITs) {
if (handle != hcan || (RxFifo0ITs & FDCAN_IT_RX_FIFO0_NEW_MESSAGE) == RESET) {
return;
}
static FDCAN_RxHeaderTypeDef header;
static uint8_t data[8];
if (HAL_FDCAN_GetRxMessage(hcan, FDCAN_RX_FIFO0, &header, data) != HAL_OK) {
return;
}
if (header.FDFormat != FDCAN_CLASSIC_CAN ||
header.RxFrameType != FDCAN_DATA_FRAME ||
header.IdType != FDCAN_STANDARD_ID) {
return;
}
size_t datalen;
switch (header.DataLength) {
case FDCAN_DLC_BYTES_0:
datalen = 0;
break;
case FDCAN_DLC_BYTES_1:
datalen = 1;
break;
case FDCAN_DLC_BYTES_2:
datalen = 2;
break;
case FDCAN_DLC_BYTES_3:
datalen = 3;
break;
case FDCAN_DLC_BYTES_4:
datalen = 4;
break;
case FDCAN_DLC_BYTES_5:
datalen = 5;
break;
case FDCAN_DLC_BYTES_6:
datalen = 6;
break;
case FDCAN_DLC_BYTES_7:
datalen = 7;
break;
case FDCAN_DLC_BYTES_8:
datalen = 8;
break;
default:
return;
}
ftcan_msg_received_cb(header.Identifier, datalen, data);
}
#endif
__weak void ftcan_msg_received_cb(uint16_t id, size_t datalen,
const uint8_t *data) {}
uint64_t ftcan_unmarshal_unsigned(const uint8_t **data_ptr, size_t num_bytes) {
if (num_bytes > 8) {
num_bytes = 8;
}
const uint8_t *data = *data_ptr;
uint64_t result = 0;
for (size_t i = 0; i < num_bytes; i++) {
result <<= 8;
result |= data[i];
}
*data_ptr += num_bytes;
return result;
}
int64_t ftcan_unmarshal_signed(const uint8_t **data_ptr, size_t num_bytes) {
if (num_bytes > 8) {
num_bytes = 8;
}
uint64_t result_unsigned = ftcan_unmarshal_unsigned(data_ptr, num_bytes);
// Sign extend by shifting left, then copying to a signed int and shifting
// back to the right
size_t diff_to_64 = 64 - num_bytes * 8;
result_unsigned <<= diff_to_64;
int64_t result;
memcpy(&result, &result_unsigned, 8);
return result >> diff_to_64;
}
uint8_t *ftcan_marshal_unsigned(uint8_t *data, uint64_t val, size_t num_bytes) {
if (num_bytes > 8) {
num_bytes = 8;
}
for (int i = num_bytes - 1; i >= 0; i--) {
data[i] = val & 0xFF;
val >>= 8;
}
return data + num_bytes;
}
uint8_t *ftcan_marshal_signed(uint8_t *data, int64_t val, size_t num_bytes) {
return ftcan_marshal_unsigned(data, val, num_bytes);
}

634
Core/Src/main.c Normal file
View File

@ -0,0 +1,634 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.c
* @brief : Main program body
******************************************************************************
* @attention
*
* Copyright (c) 2024 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.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "CAN_Communication.h"
#include "Channel_Control.h"
#include "PCA9535D_Driver.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
ADC_HandleTypeDef hadc1;
ADC_HandleTypeDef hadc2;
CAN_HandleTypeDef hcan;
I2C_HandleTypeDef hi2c1;
TIM_HandleTypeDef htim2;
TIM_HandleTypeDef htim3;
UART_HandleTypeDef huart1;
//Test
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_ADC1_Init(void);
static void MX_ADC2_Init(void);
static void MX_CAN_Init(void);
static void MX_TIM2_Init(void);
static void MX_TIM3_Init(void);
static void MX_I2C1_Init(void);
static void MX_USART1_UART_Init(void);
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
uint16_t adc1_buffer[7];
uint16_t adc2_buffer[7]; // data type specific to 16 bit integer with no sign ( vorzeichen )
extern rx_status_frame rxstate;
extern volatile uint8_t canmsg_received;
/* USER CODE END 0 */
/**
* @brief The application entry point.
* @retval int
*/
int main(void)
{
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
/* MCU Configuration--------------------------------------------------------*/
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
HAL_Init();
/* USER CODE BEGIN Init */
/* USER CODE END Init */
/* Configure the system clock */
SystemClock_Config();
/* USER CODE BEGIN SysInit */
/* USER CODE END SysInit */
/* Initialize all configured peripherals */
MX_GPIO_Init();
MX_ADC1_Init();
MX_ADC2_Init();
MX_CAN_Init();
MX_TIM2_Init();
MX_TIM3_Init();
MX_I2C1_Init();
MX_USART1_UART_Init();
/* USER CODE BEGIN 2 */
// HAL_GPIO_WritePin(Status_LED_GPIO_Port, Status_LED_Pin, GPIO_PIN_SET); // status led wird an gemacht , das leuchtet
// currentMonitor_init(&hadc1, &hadc2, &htim7); // handler struktur ( handler adc1 .... usw )
ChannelControl_init(&hi2c1, &htim3, &htim2);
can_init(&hcan); // can bus initilisiert , kommunikation zum hauptsteuergeraet ( autobox )
uint32_t lasttick = HAL_GetTick(); // gibt dir zuruck die milisekunden seit start. ( es fangt an und dann milisekunden + 1 usw....)
// HAL_TIM_Base_Start(&htim2);
// HAL_TIM_Base_Start(&htim3);
HAL_GPIO_WritePin(STATUS_LED1_GPIO_Port , STATUS_LED1_Pin , GPIO_PIN_SET);
// Turn everything on manually (debug)
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
while(1)
{
/* USER CODE END WHILE */
/* USER CODE BEGIN 3 */
if (canmsg_received) { // USB zu CAN wandler , und dann CAN testen , validieren ob der code macht was es soll , red mit oskar/jasper
canmsg_received = 0;
ChannelControl_UpdateGPIOs(rxstate.iostatus);
ChannelControl_UpdatePWMs(rxstate.radiatorfans, rxstate.tsacfans, rxstate.pwmaggregat,
rxstate.pwmpumps); // gotta change , to see whats left of it and whats not
}
if ((HAL_GetTick() - lasttick) > 100U) {
lasttick = HAL_GetTick();
//can_sendloop();
}
currentMonitor_checklimits(); // ob irgnwo ueberstrom getreten ist
}
/* USER CODE END 3 */
}
/**
* @brief System Clock Configuration
* @retval None
*/
void SystemClock_Config(void)
{
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
/** Initializes the RCC Oscillators according to the specified parameters
* in the RCC_OscInitTypeDef structure.
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.HSEPredivValue = RCC_HSE_PREDIV_DIV1;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL4;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
Error_Handler();
}
/** Initializes the CPU, AHB and APB buses clocks
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSE;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK)
{
Error_Handler();
}
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_I2C1
|RCC_PERIPHCLK_ADC12;
PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2;
PeriphClkInit.Adc12ClockSelection = RCC_ADC12PLLCLK_DIV1;
PeriphClkInit.I2c1ClockSelection = RCC_I2C1CLKSOURCE_SYSCLK;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
}
/** Enables the Clock Security System
*/
HAL_RCC_EnableCSS();
}
/**
* @brief ADC1 Initialization Function
* @param None
* @retval None
*/
static void MX_ADC1_Init(void)
{
/* USER CODE BEGIN ADC1_Init 0 */
/* USER CODE END ADC1_Init 0 */
ADC_MultiModeTypeDef multimode = {0};
ADC_ChannelConfTypeDef sConfig = {0};
/* USER CODE BEGIN ADC1_Init 1 */
/* USER CODE END ADC1_Init 1 */
/** Common config
*/
hadc1.Instance = ADC1;
hadc1.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV1;
hadc1.Init.Resolution = ADC_RESOLUTION_12B;
hadc1.Init.ScanConvMode = ADC_SCAN_DISABLE;
hadc1.Init.ContinuousConvMode = DISABLE;
hadc1.Init.DiscontinuousConvMode = DISABLE;
hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
hadc1.Init.ExternalTrigConv = ADC_SOFTWARE_START;
hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT;
hadc1.Init.NbrOfConversion = 1;
hadc1.Init.DMAContinuousRequests = DISABLE;
hadc1.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
hadc1.Init.LowPowerAutoWait = DISABLE;
hadc1.Init.Overrun = ADC_OVR_DATA_OVERWRITTEN;
if (HAL_ADC_Init(&hadc1) != HAL_OK)
{
Error_Handler();
}
/** Configure the ADC multi-mode
*/
multimode.Mode = ADC_MODE_INDEPENDENT;
if (HAL_ADCEx_MultiModeConfigChannel(&hadc1, &multimode) != HAL_OK)
{
Error_Handler();
}
/** Configure Regular Channel
*/
sConfig.Channel = ADC_CHANNEL_1;
sConfig.Rank = ADC_REGULAR_RANK_1;
sConfig.SingleDiff = ADC_SINGLE_ENDED;
sConfig.SamplingTime = ADC_SAMPLETIME_1CYCLE_5;
sConfig.OffsetNumber = ADC_OFFSET_NONE;
sConfig.Offset = 0;
if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN ADC1_Init 2 */
/* USER CODE END ADC1_Init 2 */
}
/**
* @brief ADC2 Initialization Function
* @param None
* @retval None
*/
static void MX_ADC2_Init(void)
{
/* USER CODE BEGIN ADC2_Init 0 */
/* USER CODE END ADC2_Init 0 */
ADC_ChannelConfTypeDef sConfig = {0};
/* USER CODE BEGIN ADC2_Init 1 */
/* USER CODE END ADC2_Init 1 */
/** Common config
*/
hadc2.Instance = ADC2;
hadc2.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV1;
hadc2.Init.Resolution = ADC_RESOLUTION_12B;
hadc2.Init.ScanConvMode = ADC_SCAN_DISABLE;
hadc2.Init.ContinuousConvMode = DISABLE;
hadc2.Init.DiscontinuousConvMode = DISABLE;
hadc2.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
hadc2.Init.ExternalTrigConv = ADC_SOFTWARE_START;
hadc2.Init.DataAlign = ADC_DATAALIGN_RIGHT;
hadc2.Init.NbrOfConversion = 1;
hadc2.Init.DMAContinuousRequests = DISABLE;
hadc2.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
hadc2.Init.LowPowerAutoWait = DISABLE;
hadc2.Init.Overrun = ADC_OVR_DATA_OVERWRITTEN;
if (HAL_ADC_Init(&hadc2) != HAL_OK)
{
Error_Handler();
}
/** Configure Regular Channel
*/
sConfig.Channel = ADC_CHANNEL_1;
sConfig.Rank = ADC_REGULAR_RANK_1;
sConfig.SingleDiff = ADC_SINGLE_ENDED;
sConfig.SamplingTime = ADC_SAMPLETIME_1CYCLE_5;
sConfig.OffsetNumber = ADC_OFFSET_NONE;
sConfig.Offset = 0;
if (HAL_ADC_ConfigChannel(&hadc2, &sConfig) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN ADC2_Init 2 */
/* USER CODE END ADC2_Init 2 */
}
/**
* @brief CAN Initialization Function
* @param None
* @retval None
*/
static void MX_CAN_Init(void)
{
/* USER CODE BEGIN CAN_Init 0 */
/* USER CODE END CAN_Init 0 */
/* USER CODE BEGIN CAN_Init 1 */
/* USER CODE END CAN_Init 1 */
hcan.Instance = CAN;
hcan.Init.Prescaler = 2;
hcan.Init.Mode = CAN_MODE_NORMAL;
hcan.Init.SyncJumpWidth = CAN_SJW_1TQ;
hcan.Init.TimeSeg1 = CAN_BS1_13TQ;
hcan.Init.TimeSeg2 = CAN_BS2_2TQ;
hcan.Init.TimeTriggeredMode = DISABLE;
hcan.Init.AutoBusOff = ENABLE;
hcan.Init.AutoWakeUp = DISABLE;
hcan.Init.AutoRetransmission = DISABLE;
hcan.Init.ReceiveFifoLocked = DISABLE;
hcan.Init.TransmitFifoPriority = DISABLE;
if (HAL_CAN_Init(&hcan) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN CAN_Init 2 */
/* USER CODE END CAN_Init 2 */
}
/**
* @brief I2C1 Initialization Function
* @param None
* @retval None
*/
static void MX_I2C1_Init(void)
{
/* USER CODE BEGIN I2C1_Init 0 */
/* USER CODE END I2C1_Init 0 */
/* USER CODE BEGIN I2C1_Init 1 */
/* USER CODE END I2C1_Init 1 */
hi2c1.Instance = I2C1;
hi2c1.Init.Timing = 0x00303D5B;
hi2c1.Init.OwnAddress1 = 0;
hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
hi2c1.Init.OwnAddress2 = 0;
hi2c1.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
if (HAL_I2C_Init(&hi2c1) != HAL_OK)
{
Error_Handler();
}
/** Configure Analogue filter
*/
if (HAL_I2CEx_ConfigAnalogFilter(&hi2c1, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
{
Error_Handler();
}
/** Configure Digital filter
*/
if (HAL_I2CEx_ConfigDigitalFilter(&hi2c1, 0) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN I2C1_Init 2 */
/* USER CODE END I2C1_Init 2 */
}
/**
* @brief TIM2 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM2_Init(void)
{
/* USER CODE BEGIN TIM2_Init 0 */
/* USER CODE END TIM2_Init 0 */
TIM_MasterConfigTypeDef sMasterConfig = {0};
TIM_OC_InitTypeDef sConfigOC = {0};
/* USER CODE BEGIN TIM2_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)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &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(&htim2, &sConfigOC, TIM_CHANNEL_2) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM2_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 = 0;
htim3.Init.CounterMode = TIM_COUNTERMODE_UP;
htim3.Init.Period = 65535;
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_1) != 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 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_MultiProcessor_Init(&huart1, 0, UART_WAKEUPMETHOD_IDLELINE) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN USART1_Init 2 */
/* USER CODE END USART1_Init 2 */
}
/**
* @brief GPIO Initialization Function
* @param None
* @retval None
*/
static void MX_GPIO_Init(void)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
/* USER CODE BEGIN MX_GPIO_Init_1 */
/* USER CODE END MX_GPIO_Init_1 */
/* GPIO Ports Clock Enable */
__HAL_RCC_GPIOF_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_0|DSEL_3_Pin|DSEL_4_Pin|DSEL_5_Pin
|DSEL_6_Pin|DSEL_7_Pin, GPIO_PIN_RESET);
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOC, STATUS_LED1_Pin|STATUS_LED2_Pin|STATUS_LED3_Pin|STATUS_LED4_Pin, GPIO_PIN_RESET);
/*Configure GPIO pins : PB0 DSEL_3_Pin DSEL_4_Pin DSEL_5_Pin
DSEL_6_Pin DSEL_7_Pin */
GPIO_InitStruct.Pin = GPIO_PIN_0|DSEL_3_Pin|DSEL_4_Pin|DSEL_5_Pin
|DSEL_6_Pin|DSEL_7_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 : STATUS_LED1_Pin STATUS_LED2_Pin STATUS_LED3_Pin STATUS_LED4_Pin */
GPIO_InitStruct.Pin = STATUS_LED1_Pin|STATUS_LED2_Pin|STATUS_LED3_Pin|STATUS_LED4_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
/* USER CODE BEGIN MX_GPIO_Init_2 */
/* USER CODE END MX_GPIO_Init_2 */
}
/* USER CODE BEGIN 4 */
/* USER CODE END 4 */
/**
* @brief This function is executed in case of error occurrence.
* @retval None
*/
void Error_Handler(void)
{
/* USER CODE BEGIN Error_Handler_Debug */
/* User can add his own implementation to report the HAL error return state */
__disable_irq();
while (1)
{
}
/* USER CODE END Error_Handler_Debug */
}
#ifdef USE_FULL_ASSERT
/**
* @brief Reports the name of the source file and the source line number
* where the assert_param error has occurred.
* @param file: pointer to the source file name
* @param line: assert_param error line source number
* @retval None
*/
void assert_failed(uint8_t *file, uint32_t line)
{
/* USER CODE BEGIN 6 */
/* User can add his own implementation to report the file name and line number,
ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
/* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */

View File

@ -0,0 +1,571 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f3xx_hal_msp.c
* @brief This file provides code for the MSP Initialization
* and de-Initialization codes.
******************************************************************************
* @attention
*
* Copyright (c) 2024 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.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN TD */
/* USER CODE END TD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN Define */
/* USER CODE END Define */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN Macro */
/* USER CODE END Macro */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* External functions --------------------------------------------------------*/
/* USER CODE BEGIN ExternalFunctions */
/* USER CODE END ExternalFunctions */
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
/**
* Initializes the Global MSP.
*/
void HAL_MspInit(void)
{
/* USER CODE BEGIN MspInit 0 */
/* USER CODE END MspInit 0 */
__HAL_RCC_SYSCFG_CLK_ENABLE();
__HAL_RCC_PWR_CLK_ENABLE();
/* System interrupt init*/
/* USER CODE BEGIN MspInit 1 */
/* USER CODE END MspInit 1 */
}
static uint32_t HAL_RCC_ADC12_CLK_ENABLED=0;
/**
* @brief ADC MSP Initialization
* This function configures the hardware resources used in this example
* @param hadc: ADC handle pointer
* @retval None
*/
void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hadc->Instance==ADC1)
{
/* USER CODE BEGIN ADC1_MspInit 0 */
/* USER CODE END ADC1_MspInit 0 */
/* Peripheral clock enable */
HAL_RCC_ADC12_CLK_ENABLED++;
if(HAL_RCC_ADC12_CLK_ENABLED==1){
__HAL_RCC_ADC12_CLK_ENABLE();
}
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**ADC1 GPIO Configuration
PC0 ------> ADC1_IN6
PC1 ------> ADC1_IN7
PC2 ------> ADC1_IN8
PC3 ------> ADC1_IN9
PA0 ------> ADC1_IN1
PA1 ------> ADC1_IN2
PA2 ------> ADC1_IN3
PA3 ------> ADC1_IN4
*/
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(GPIOC, &GPIO_InitStruct);
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);
/* USER CODE BEGIN ADC1_MspInit 1 */
/* USER CODE END ADC1_MspInit 1 */
}
else if(hadc->Instance==ADC2)
{
/* USER CODE BEGIN ADC2_MspInit 0 */
/* USER CODE END ADC2_MspInit 0 */
/* Peripheral clock enable */
HAL_RCC_ADC12_CLK_ENABLED++;
if(HAL_RCC_ADC12_CLK_ENABLED==1){
__HAL_RCC_ADC12_CLK_ENABLE();
}
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
/**ADC2 GPIO Configuration
PA4 ------> ADC2_IN1
PA5 ------> ADC2_IN2
PA6 ------> ADC2_IN3
PA7 ------> ADC2_IN4
PC4 ------> ADC2_IN5
*/
GPIO_InitStruct.Pin = GPIO_PIN_4|GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_4;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
/* USER CODE BEGIN ADC2_MspInit 1 */
/* USER CODE END ADC2_MspInit 1 */
}
}
/**
* @brief ADC MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hadc: ADC handle pointer
* @retval None
*/
void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc)
{
if(hadc->Instance==ADC1)
{
/* USER CODE BEGIN ADC1_MspDeInit 0 */
/* USER CODE END ADC1_MspDeInit 0 */
/* Peripheral clock disable */
HAL_RCC_ADC12_CLK_ENABLED--;
if(HAL_RCC_ADC12_CLK_ENABLED==0){
__HAL_RCC_ADC12_CLK_DISABLE();
}
/**ADC1 GPIO Configuration
PC0 ------> ADC1_IN6
PC1 ------> ADC1_IN7
PC2 ------> ADC1_IN8
PC3 ------> ADC1_IN9
PA0 ------> ADC1_IN1
PA1 ------> ADC1_IN2
PA2 ------> ADC1_IN3
PA3 ------> ADC1_IN4
*/
HAL_GPIO_DeInit(GPIOC, GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_3);
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_3);
/* USER CODE BEGIN ADC1_MspDeInit 1 */
/* USER CODE END ADC1_MspDeInit 1 */
}
else if(hadc->Instance==ADC2)
{
/* USER CODE BEGIN ADC2_MspDeInit 0 */
/* USER CODE END ADC2_MspDeInit 0 */
/* Peripheral clock disable */
HAL_RCC_ADC12_CLK_ENABLED--;
if(HAL_RCC_ADC12_CLK_ENABLED==0){
__HAL_RCC_ADC12_CLK_DISABLE();
}
/**ADC2 GPIO Configuration
PA4 ------> ADC2_IN1
PA5 ------> ADC2_IN2
PA6 ------> ADC2_IN3
PA7 ------> ADC2_IN4
PC4 ------> ADC2_IN5
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_4|GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7);
HAL_GPIO_DeInit(GPIOC, GPIO_PIN_4);
/* USER CODE BEGIN ADC2_MspDeInit 1 */
/* USER CODE END ADC2_MspDeInit 1 */
}
}
/**
* @brief CAN MSP Initialization
* This function configures the hardware resources used in this example
* @param hcan: CAN handle pointer
* @retval None
*/
void HAL_CAN_MspInit(CAN_HandleTypeDef* hcan)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hcan->Instance==CAN)
{
/* USER CODE BEGIN CAN_MspInit 0 */
/* USER CODE END CAN_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_CAN1_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**CAN GPIO Configuration
PA11 ------> CAN_RX
PA12 ------> CAN_TX
*/
GPIO_InitStruct.Pin = GPIO_PIN_11;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF9_CAN;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_12;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF9_CAN;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* CAN interrupt Init */
HAL_NVIC_SetPriority(USB_LP_CAN_RX0_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(USB_LP_CAN_RX0_IRQn);
HAL_NVIC_SetPriority(CAN_RX1_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(CAN_RX1_IRQn);
HAL_NVIC_SetPriority(CAN_SCE_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(CAN_SCE_IRQn);
/* USER CODE BEGIN CAN_MspInit 1 */
/* USER CODE END CAN_MspInit 1 */
}
}
/**
* @brief CAN MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hcan: CAN handle pointer
* @retval None
*/
void HAL_CAN_MspDeInit(CAN_HandleTypeDef* hcan)
{
if(hcan->Instance==CAN)
{
/* USER CODE BEGIN CAN_MspDeInit 0 */
/* USER CODE END CAN_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_CAN1_CLK_DISABLE();
/**CAN GPIO Configuration
PA11 ------> CAN_RX
PA12 ------> CAN_TX
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11|GPIO_PIN_12);
/* CAN interrupt DeInit */
HAL_NVIC_DisableIRQ(USB_LP_CAN_RX0_IRQn);
HAL_NVIC_DisableIRQ(CAN_RX1_IRQn);
HAL_NVIC_DisableIRQ(CAN_SCE_IRQn);
/* USER CODE BEGIN CAN_MspDeInit 1 */
/* USER CODE END CAN_MspDeInit 1 */
}
}
/**
* @brief I2C MSP Initialization
* This function configures the hardware resources used in this example
* @param hi2c: I2C handle pointer
* @retval None
*/
void HAL_I2C_MspInit(I2C_HandleTypeDef* hi2c)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hi2c->Instance==I2C1)
{
/* USER CODE BEGIN I2C1_MspInit 0 */
/* USER CODE END I2C1_MspInit 0 */
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/**I2C1 GPIO Configuration
PA15 ------> I2C1_SCL
PB7 ------> I2C1_SDA
*/
GPIO_InitStruct.Pin = GPIO_PIN_15;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF4_I2C1;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF4_I2C1;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* Peripheral clock enable */
__HAL_RCC_I2C1_CLK_ENABLE();
/* USER CODE BEGIN I2C1_MspInit 1 */
/* USER CODE END I2C1_MspInit 1 */
}
}
/**
* @brief I2C MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hi2c: I2C handle pointer
* @retval None
*/
void HAL_I2C_MspDeInit(I2C_HandleTypeDef* hi2c)
{
if(hi2c->Instance==I2C1)
{
/* USER CODE BEGIN I2C1_MspDeInit 0 */
/* USER CODE END I2C1_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_I2C1_CLK_DISABLE();
/**I2C1 GPIO Configuration
PA15 ------> I2C1_SCL
PB7 ------> I2C1_SDA
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_15);
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_7);
/* USER CODE BEGIN I2C1_MspDeInit 1 */
/* USER CODE END I2C1_MspDeInit 1 */
}
}
/**
* @brief TIM_PWM MSP Initialization
* This function configures the hardware resources used in this example
* @param htim_pwm: TIM_PWM handle pointer
* @retval None
*/
void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef* htim_pwm)
{
if(htim_pwm->Instance==TIM2)
{
/* USER CODE BEGIN TIM2_MspInit 0 */
/* USER CODE END TIM2_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_TIM2_CLK_ENABLE();
/* USER CODE BEGIN TIM2_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 */
}
}
void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(htim->Instance==TIM2)
{
/* USER CODE BEGIN TIM2_MspPostInit 0 */
/* USER CODE END TIM2_MspPostInit 0 */
__HAL_RCC_GPIOB_CLK_ENABLE();
/**TIM2 GPIO Configuration
PB3 ------> TIM2_CH2
*/
GPIO_InitStruct.Pin = GPIO_PIN_3;
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);
/* USER CODE BEGIN TIM2_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
PB1 ------> TIM3_CH4
PB4 ------> TIM3_CH1
*/
GPIO_InitStruct.Pin = GPIO_PIN_1|GPIO_PIN_4;
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 */
}
}
/**
* @brief TIM_PWM MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param htim_pwm: TIM_PWM handle pointer
* @retval None
*/
void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef* htim_pwm)
{
if(htim_pwm->Instance==TIM2)
{
/* USER CODE BEGIN TIM2_MspDeInit 0 */
/* USER CODE END TIM2_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM2_CLK_DISABLE();
/* USER CODE BEGIN TIM2_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 */
}
}
/**
* @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_GPIOA_CLK_ENABLE();
/**USART1 GPIO Configuration
PA9 ------> USART1_TX
PA10 ------> USART1_RX
*/
GPIO_InitStruct.Pin = GPIO_PIN_9|GPIO_PIN_10;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF7_USART1;
HAL_GPIO_Init(GPIOA, &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
PA9 ------> USART1_TX
PA10 ------> USART1_RX
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_9|GPIO_PIN_10);
/* USER CODE BEGIN USART1_MspDeInit 1 */
/* USER CODE END USART1_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

246
Core/Src/stm32f3xx_it.c Normal file
View File

@ -0,0 +1,246 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f3xx_it.c
* @brief Interrupt Service Routines.
******************************************************************************
* @attention
*
* Copyright (c) 2024 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.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "stm32f3xx_it.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN TD */
/* USER CODE END TD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/* External variables --------------------------------------------------------*/
extern CAN_HandleTypeDef hcan;
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/******************************************************************************/
/* Cortex-M4 Processor Interruption and Exception Handlers */
/******************************************************************************/
/**
* @brief This function handles Non maskable interrupt.
*/
void NMI_Handler(void)
{
/* USER CODE BEGIN NonMaskableInt_IRQn 0 */
/* USER CODE END NonMaskableInt_IRQn 0 */
HAL_RCC_NMI_IRQHandler();
/* USER CODE BEGIN NonMaskableInt_IRQn 1 */
while (1)
{
}
/* USER CODE END NonMaskableInt_IRQn 1 */
}
/**
* @brief This function handles Hard fault interrupt.
*/
void HardFault_Handler(void)
{
/* USER CODE BEGIN HardFault_IRQn 0 */
/* USER CODE END HardFault_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_HardFault_IRQn 0 */
/* USER CODE END W1_HardFault_IRQn 0 */
}
}
/**
* @brief This function handles Memory management fault.
*/
void MemManage_Handler(void)
{
/* USER CODE BEGIN MemoryManagement_IRQn 0 */
/* USER CODE END MemoryManagement_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_MemoryManagement_IRQn 0 */
/* USER CODE END W1_MemoryManagement_IRQn 0 */
}
}
/**
* @brief This function handles Pre-fetch fault, memory access fault.
*/
void BusFault_Handler(void)
{
/* USER CODE BEGIN BusFault_IRQn 0 */
/* USER CODE END BusFault_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_BusFault_IRQn 0 */
/* USER CODE END W1_BusFault_IRQn 0 */
}
}
/**
* @brief This function handles Undefined instruction or illegal state.
*/
void UsageFault_Handler(void)
{
/* USER CODE BEGIN UsageFault_IRQn 0 */
/* USER CODE END UsageFault_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_UsageFault_IRQn 0 */
/* USER CODE END W1_UsageFault_IRQn 0 */
}
}
/**
* @brief This function handles System service call via SWI instruction.
*/
void SVC_Handler(void)
{
/* USER CODE BEGIN SVCall_IRQn 0 */
/* USER CODE END SVCall_IRQn 0 */
/* USER CODE BEGIN SVCall_IRQn 1 */
/* USER CODE END SVCall_IRQn 1 */
}
/**
* @brief This function handles Debug monitor.
*/
void DebugMon_Handler(void)
{
/* USER CODE BEGIN DebugMonitor_IRQn 0 */
/* USER CODE END DebugMonitor_IRQn 0 */
/* USER CODE BEGIN DebugMonitor_IRQn 1 */
/* USER CODE END DebugMonitor_IRQn 1 */
}
/**
* @brief This function handles Pendable request for system service.
*/
void PendSV_Handler(void)
{
/* USER CODE BEGIN PendSV_IRQn 0 */
/* USER CODE END PendSV_IRQn 0 */
/* USER CODE BEGIN PendSV_IRQn 1 */
/* USER CODE END PendSV_IRQn 1 */
}
/**
* @brief This function handles System tick timer.
*/
void SysTick_Handler(void)
{
/* USER CODE BEGIN SysTick_IRQn 0 */
/* USER CODE END SysTick_IRQn 0 */
HAL_IncTick();
/* USER CODE BEGIN SysTick_IRQn 1 */
/* USER CODE END SysTick_IRQn 1 */
}
/******************************************************************************/
/* STM32F3xx Peripheral Interrupt Handlers */
/* Add here the Interrupt Handlers for the used peripherals. */
/* For the available peripheral interrupt handler names, */
/* please refer to the startup file (startup_stm32f3xx.s). */
/******************************************************************************/
/**
* @brief This function handles USB low priority or CAN_RX0 interrupts.
*/
void USB_LP_CAN_RX0_IRQHandler(void)
{
/* USER CODE BEGIN USB_LP_CAN_RX0_IRQn 0 */
/* USER CODE END USB_LP_CAN_RX0_IRQn 0 */
HAL_CAN_IRQHandler(&hcan);
/* USER CODE BEGIN USB_LP_CAN_RX0_IRQn 1 */
/* USER CODE END USB_LP_CAN_RX0_IRQn 1 */
}
/**
* @brief This function handles CAN RX1 interrupt.
*/
void CAN_RX1_IRQHandler(void)
{
/* USER CODE BEGIN CAN_RX1_IRQn 0 */
/* USER CODE END CAN_RX1_IRQn 0 */
HAL_CAN_IRQHandler(&hcan);
/* USER CODE BEGIN CAN_RX1_IRQn 1 */
/* USER CODE END CAN_RX1_IRQn 1 */
}
/**
* @brief This function handles CAN SCE interrupt.
*/
void CAN_SCE_IRQHandler(void)
{
/* USER CODE BEGIN CAN_SCE_IRQn 0 */
/* USER CODE END CAN_SCE_IRQn 0 */
HAL_CAN_IRQHandler(&hcan);
/* USER CODE BEGIN CAN_SCE_IRQn 1 */
/* USER CODE END CAN_SCE_IRQn 1 */
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

287
Core/Src/system_stm32f3xx.c Normal file
View File

@ -0,0 +1,287 @@
/**
******************************************************************************
* @file system_stm32f3xx.c
* @author MCD Application Team
* @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
*
* 1. This file provides two functions and one global variable to be called from
* user application:
* - SystemInit(): This function is called at startup just after reset and
* before branch to main program. This call is made inside
* the "startup_stm32f3xx.s" file.
*
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
* by the user application to setup the SysTick
* timer or configure other parameters.
*
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
* be called whenever the core clock is changed
* during program execution.
*
* 2. After each device reset the HSI (8 MHz) is used as system clock source.
* Then SystemInit() function is called, in "startup_stm32f3xx.s" file, to
* configure the system clock before to branch to main program.
*
* 3. This file configures the system clock as follows:
*=============================================================================
* Supported STM32F3xx device
*-----------------------------------------------------------------------------
* System Clock source | HSI
*-----------------------------------------------------------------------------
* SYSCLK(Hz) | 8000000
*-----------------------------------------------------------------------------
* HCLK(Hz) | 8000000
*-----------------------------------------------------------------------------
* AHB Prescaler | 1
*-----------------------------------------------------------------------------
* APB2 Prescaler | 1
*-----------------------------------------------------------------------------
* APB1 Prescaler | 1
*-----------------------------------------------------------------------------
* USB Clock | DISABLE
*-----------------------------------------------------------------------------
*=============================================================================
******************************************************************************
* @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.
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f3xx_system
* @{
*/
/** @addtogroup STM32F3xx_System_Private_Includes
* @{
*/
#include "stm32f3xx.h"
/**
* @}
*/
/** @addtogroup STM32F3xx_System_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F3xx_System_Private_Defines
* @{
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz.
This value can be provided and adapted by the user application. */
#endif /* HSE_VALUE */
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)8000000) /*!< Default value of the Internal oscillator in Hz.
This value can be provided and adapted by the user application. */
#endif /* HSI_VALUE */
/* Note: Following vector table addresses must be defined in line with linker
configuration. */
/*!< Uncomment the following line if you need to relocate the vector table
anywhere in Flash or Sram, else the vector table is kept at the automatic
remap of boot address selected */
/* #define USER_VECT_TAB_ADDRESS */
#if defined(USER_VECT_TAB_ADDRESS)
/*!< Uncomment the following line if you need to relocate your vector Table
in Sram else user remap will be done in Flash. */
/* #define VECT_TAB_SRAM */
#if defined(VECT_TAB_SRAM)
#define VECT_TAB_BASE_ADDRESS SRAM_BASE /*!< Vector Table base address field.
This value must be a multiple of 0x200. */
#define VECT_TAB_OFFSET 0x00000000U /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */
#else
#define VECT_TAB_BASE_ADDRESS FLASH_BASE /*!< Vector Table base address field.
This value must be a multiple of 0x200. */
#define VECT_TAB_OFFSET 0x00000000U /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */
#endif /* VECT_TAB_SRAM */
#endif /* USER_VECT_TAB_ADDRESS */
/******************************************************************************/
/**
* @}
*/
/** @addtogroup STM32F3xx_System_Private_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F3xx_System_Private_Variables
* @{
*/
/* This variable is updated in three ways:
1) by calling CMSIS function SystemCoreClockUpdate()
2) by calling HAL API function HAL_RCC_GetHCLKFreq()
3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
Note: If you use this function to configure the system clock there is no need to
call the 2 first functions listed above, since SystemCoreClock variable is
updated automatically.
*/
uint32_t SystemCoreClock = 8000000;
const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4};
/**
* @}
*/
/** @addtogroup STM32F3xx_System_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F3xx_System_Private_Functions
* @{
*/
/**
* @brief Setup the microcontroller system
* @param None
* @retval None
*/
void SystemInit(void)
{
/* FPU settings --------------------------------------------------------------*/
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
#endif
/* Configure the Vector Table location -------------------------------------*/
#if defined(USER_VECT_TAB_ADDRESS)
SCB->VTOR = VECT_TAB_BASE_ADDRESS | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
#endif /* USER_VECT_TAB_ADDRESS */
}
/**
* @brief Update SystemCoreClock variable according to Clock Register Values.
* The SystemCoreClock variable contains the core clock (HCLK), it can
* be used by the user application to setup the SysTick timer or configure
* other parameters.
*
* @note Each time the core clock (HCLK) changes, this function must be called
* to update SystemCoreClock variable value. Otherwise, any configuration
* based on this variable will be incorrect.
*
* @note - The system frequency computed by this function is not the real
* frequency in the chip. It is calculated based on the predefined
* constant and the selected clock source:
*
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
*
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
*
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
*
* (*) HSI_VALUE is a constant defined in stm32f3xx_hal.h file (default value
* 8 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* (**) HSE_VALUE is a constant defined in stm32f3xx_hal.h file (default value
* 8 MHz), user has to ensure that HSE_VALUE is same as the real
* frequency of the crystal used. Otherwise, this function may
* have wrong result.
*
* - The result of this function could be not correct when using fractional
* value for HSE crystal.
*
* @param None
* @retval None
*/
void SystemCoreClockUpdate (void)
{
uint32_t tmp = 0, pllmull = 0, pllsource = 0, predivfactor = 0;
/* Get SYSCLK source -------------------------------------------------------*/
tmp = RCC->CFGR & RCC_CFGR_SWS;
switch (tmp)
{
case RCC_CFGR_SWS_HSI: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE;
break;
case RCC_CFGR_SWS_HSE: /* HSE used as system clock */
SystemCoreClock = HSE_VALUE;
break;
case RCC_CFGR_SWS_PLL: /* PLL used as system clock */
/* Get PLL clock source and multiplication factor ----------------------*/
pllmull = RCC->CFGR & RCC_CFGR_PLLMUL;
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
pllmull = ( pllmull >> 18) + 2;
#if defined (STM32F302xE) || defined (STM32F303xE) || defined (STM32F398xx)
predivfactor = (RCC->CFGR2 & RCC_CFGR2_PREDIV) + 1;
if (pllsource == RCC_CFGR_PLLSRC_HSE_PREDIV)
{
/* HSE oscillator clock selected as PREDIV1 clock entry */
SystemCoreClock = (HSE_VALUE / predivfactor) * pllmull;
}
else
{
/* HSI oscillator clock selected as PREDIV1 clock entry */
SystemCoreClock = (HSI_VALUE / predivfactor) * pllmull;
}
#else
if (pllsource == RCC_CFGR_PLLSRC_HSI_DIV2)
{
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
}
else
{
predivfactor = (RCC->CFGR2 & RCC_CFGR2_PREDIV) + 1;
/* HSE oscillator clock selected as PREDIV1 clock entry */
SystemCoreClock = (HSE_VALUE / predivfactor) * pllmull;
}
#endif /* STM32F302xE || STM32F303xE || STM32F398xx */
break;
default: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE;
break;
}
/* Compute HCLK clock frequency ----------------*/
/* Get HCLK prescaler */
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
/* HCLK clock frequency */
SystemCoreClock >>= tmp;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/