Initial commit

This should be the state of the code from the end of the FT23 season
This commit is contained in:
2024-07-11 21:03:57 +02:00
commit 1cbfd28288
142 changed files with 213831 additions and 0 deletions

205
Core/Src/b_cccv_algo.c Normal file
View File

@ -0,0 +1,205 @@
/*
* b_cccv_algo.c
*
* Created on: 16.06.2023
* Author: max
*/
#include "b_cccv_algo.h"
#include "charger_control.h"
#include "main.h"
static uint32_t dt;
static uint32_t lasttick;
static float errorintegration = 0;
static float finalvoltage = 4.15;
static float chargevoltage = 430;
static float chargecurrentlimit = CHARGE_CURRENT_LIMIT;
static float resistancelut[1024];
static float voltageresistancelut[1024];
#define CURRENT_R 2.2
#define VOLTAGE_R 18
CCCV_CONTROL_STATE chargerstate = NO_CHARGING;
#ifdef SIMULINKTEST
CCCV_CONTROL_STATE cccvloop(float maxcellvoltage, float voltagesetpoint, float maxcurrent, float*ccurrent)
#else
CCCV_CONTROL_STATE cccvloop(float maxcellvoltage, float voltagesetpoint, float maxcurrent)
#endif
{
#ifdef SIMULINKTEST
dt = 1000;
#else
dt = HAL_GetTick() - lasttick;
lasttick = HAL_GetTick();
#endif
float chargecurrent = 0;
//Calculate Voltage Error and I and P Factors
float voltageerror = voltagesetpoint-maxcellvoltage;
float errorproportional = P_GAIN * voltageerror;
errorintegration += I_GAIN*voltageerror * ((float)dt)/1000;
//Limit I and P Factors to maximum charge current
if(errorintegration > maxcurrent)
errorintegration = maxcurrent;
if(errorproportional > maxcurrent)
errorproportional = maxcurrent;
if(errorproportional <= -maxcurrent)
errorproportional = -maxcurrent;
if(errorintegration <= -maxcurrent)
errorintegration = -maxcurrent;
float errorintegrationout = errorintegration;
chargecurrent = (errorproportional + errorintegrationout);
if(chargecurrent > maxcurrent)
chargecurrent = maxcurrent;
if(chargecurrent <= 0)
chargecurrent = 0;
if(chargecurrent < 0.01) //If Charge Current ist below minimum threshold, stop charging
return CHARGING_COMPLETED;
#ifdef SIMULINKTEST
*ccurrent = chargecurrent;
#else
setchargevoltage(103,finalvoltage+0.05);
setchargecurrent(chargecurrent);
#endif
return CHARGING_IN_PROGRESS;
}
#ifndef SIMULINKTEST
void initChargerAlgo(uint8_t numberofcells, float maximumcellvoltage)
{
chargerstate = NO_CHARGING;
chargevoltage = numberofcells * maximumcellvoltage;
for(uint32_t i = 0; i < 1024; i++)
{
resistancelut[i] = 10*CURRENT_R/(CURRENT_R+(20*((float)i)/1024));
}
for(uint32_t i = 0; i < 1024; i++)
{
voltageresistancelut[i] = (600*VOLTAGE_R)/(VOLTAGE_R+(20*((float)i)/1024));
}
}
void setchargecurrent(float chargecurrent)
{
float targetresistance;
if(chargecurrent != 0)
{
for(uint32_t setpoint = 0; setpoint < 1024; setpoint++)
{
if(resistancelut[setpoint] <= chargecurrent)
{
targetresistance = (20000*((float)setpoint)/1024);
break;
}
}
}
else
{
targetresistance = 20000;
}
float wiperpos = targetresistance/20000 * (1023);
charger_control_set_current((uint32_t) wiperpos);
}
void setchargevoltage(uint8_t numberofcells,float maximumcellvoltage)
{
float chargevoltage = numberofcells * maximumcellvoltage;
float targetresistance;
if(chargevoltage != 0)
{
for(uint32_t setpoint = 0; setpoint < 1024; setpoint++)
{
if(voltageresistancelut[setpoint] <= chargevoltage)
{
targetresistance = (20000*((float)setpoint)/1024);
break;
}
}
}
else
{
targetresistance = 20000;
}
float wiperpos = targetresistance/20000 * (1023);
charger_control_set_voltage((uint32_t) wiperpos);
//@TODO Call Function to set Resistance for Voltage
}
void chargingloop(float maximumcellvoltage)
{
switch(chargerstate)
{
case NO_CHARGING: //Do Nothing IDLE Loop
chargerstate = NO_CHARGING;
charger_control_disable_remote();
errorintegration = 0;
break;
case CHARGING_IN_PROGRESS: //Run charging algo periodically
charger_control_enable_remote();
chargerstate = cccvloop(maximumcellvoltage, finalvoltage, chargecurrentlimit);
break;
case CHARGING_COMPLETED: //Signal Completion of Charging here
chargerstate = NO_CHARGING;
charger_control_disable_remote();
errorintegration = 0;
break;
}
}
void startcharging(float endvoltage)
{
chargerstate = CHARGING_IN_PROGRESS;
finalvoltage = endvoltage;
}
void stopcharging()
{
chargerstate = NO_CHARGING;
charger_control_disable_remote();
}
#endif
#ifdef SIMULINKTEST
float matlabvalidationwrapper(float maxcellvoltage, float voltagesetpoint, float maxcurrent)
{
float chargecurrent = 0;
(void*) cccvloop(maxcellvoltage,voltagesetpoint,maxcurrent, &chargecurrent);
return chargecurrent;
}
#endif

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);
}

40
Core/Src/can.c Normal file
View File

@ -0,0 +1,40 @@
/*
* can.c
*
* Created on: 21.06.2023
* Author: max
*/
#include "can.h"
#include "can-halal.h"
#include "slave_handler.h"
#include "b_cccv_algo.h"
void initCan(FDCAN_HandleTypeDef *hcan)
{
ftcan_init(hcan);
ftcan_add_filter(0, 0);
}
void ftcan_msg_received_cb(uint16_t id, size_t datalen, const uint8_t *data)
{
if ((id & 0xFF0) == CAN_ID_SLAVE_STATUS_BASE) {
slaves_handle_status(data);
return;
}
if (id == CAN_ID_CHARGER_ACTIVE)
{
if(data[0] == 1)
{
uint8_t* ptr = &data[1];
startcharging(((float) ftcan_unmarshal_unsigned(&ptr, 2))/10000);
}
else
{
stopcharging();
}
return;
}
}

View File

@ -0,0 +1,69 @@
/*
* charge_ctrl_test_shell.c
*
* Created on: May 21, 2023
* Author: max
*/
#include "charge_ctrl_test_shell.h"
#include "charger_control.h"
UART_HandleTypeDef *suart;
void charge_shell_init(UART_HandleTypeDef *huart)
{
suart = huart;
}
void charge_shell_loop()
{
uint8_t command[3];
HAL_StatusTypeDef status = HAL_UART_Receive(suart, command, 3, 100);
if(status == HAL_OK)
{
switch(command[0])
{
case 'r':
if(command[1] == 'c') //enable remote control
{
charger_control_enable_remote();
}
else if(command[1] == 'o') //disable remote control
{
charger_control_disable_remote();
}
break;
case 'e':
if(command[1] == 'c')
{
charger_control_enable_charger_relay();
}
else if(command[1] == 'o')
{
charger_control_disable_charger_relay();
}
break;
case 'v':
;uint16_t voltage = (command[1]<<8) | command[2];
charger_control_set_voltage(voltage);
break;
case 'c':
;uint16_t current = (command[1]<<8 | command[2]);
charger_control_set_current(current);
break;
case 's':
;ChargerStatusHandleTypeDef charg = charger_control_get_state();
uint8_t txbuffer[9] = {charg.acfail, charg.dcfail, charg.cc_status,
charg.lim_status, charg.ot_status, (uint8_t)(charg.current>>8),
(uint8_t)charg.current&0xFF,(uint8_t)(charg.voltage>>8),
(uint8_t)charg.voltage&0xFF
};
HAL_UART_Transmit(suart, txbuffer, 9, 1000);
}
}
}

168
Core/Src/charger_control.c Normal file
View File

@ -0,0 +1,168 @@
/*
* charger_control.c
*
* Created on: May 21, 2023
* Author: MaxMax
*/
#include "charger_control.h"
#include "main.h"
I2C_HandleTypeDef* charger_i2c;
/*** @brief Start ADC Conversion on Charger Current Channel and returns the result
* @note The ADC has a PGA leading to an input range of +-6.144 in twos complement. With single ended measurements, the range is 15 bit and
* Voltage = 6.144/(2^(15)-1)
* @note The charger maps a voltage range of 0-5V to the output current of 0-10A
* @retval ADC Conversion register value
*/
uint16_t readADCCurrent()
{
uint8_t writeconfigreg[3] = {0x01, 0xC1, 0xE3};
uint8_t readconfigreg[1] = {0x01};
uint8_t readconversionreg[1] = {0x00};
uint8_t configreg[2];
uint8_t conversionreg[2];
HAL_I2C_Master_Transmit(charger_i2c, CHARGER_ADC_ADR, writeconfigreg, 3, 1000); //Set Config Register and Start conversion
HAL_I2C_Master_Transmit(charger_i2c, CHARGER_ADC_ADR, readconfigreg, 1, 1000); //Read Back Config Reg to check for conversion completion
HAL_I2C_Master_Receive(charger_i2c, CHARGER_ADC_ADR, configreg, 2, 1000);
HAL_Delay(1);//@TODO Remove if ADC Works
HAL_I2C_Master_Transmit(charger_i2c, CHARGER_ADC_ADR, readconversionreg, 1, 1000); //Read Result from conversion register
HAL_I2C_Master_Receive(charger_i2c, CHARGER_ADC_ADR, conversionreg, 2, 1000);
return (uint16_t)(conversionreg[0]<<8 | conversionreg[1]);
}
/*** @brief Start ADC Conversion on Charger Voltage Channel and returns the result
* @note The ADC has a PGA leading to an input range of +-6.144 in twos complement. With single ended measurements, the range is 15 bit and
* Voltage = 6.144/(2^(15)-1)
* @note The charger maps a voltage range of 0-5V to the output voltage range of 0-600V
* @retval ADC Conversion register value
*/
uint16_t readADCVoltage()
{
uint8_t writeconfigreg[3] = {0x01, 0xC1, 0xE3};
uint8_t readconfigreg[1] = {0x01};
uint8_t readconversionreg[1] = {0x00};
uint8_t configreg[2];
uint8_t conversionreg[2];
HAL_I2C_Master_Transmit(charger_i2c, CHARGER_ADC_ADR, writeconfigreg, 3, 1000); //Set Config Register and Start conversion
HAL_I2C_Master_Transmit(charger_i2c, CHARGER_ADC_ADR, readconfigreg, 1, 1000); //Read Back Config Reg to check for conversion completion
HAL_I2C_Master_Receive(charger_i2c, CHARGER_ADC_ADR, configreg, 2, 1000);
HAL_Delay(1);//@TODO Remove if ADC Works
HAL_I2C_Master_Transmit(charger_i2c, CHARGER_ADC_ADR, readconversionreg, 1, 1000); //Read Result from conversion register
HAL_I2C_Master_Receive(charger_i2c, CHARGER_ADC_ADR, conversionreg, 2, 1000);
return (uint16_t)(conversionreg[0]<<8 | conversionreg[1]);
}
/*** @brief Initilization Routine of the charger
* @note initially all outputs are set to 0, remote control and charger relay are deactivated
* @param hi2c Handler to I2C struct for ADC and DAC communication
*/
void charger_control_init(I2C_HandleTypeDef* hi2c)
{
charger_i2c = hi2c;
charger_control_disable_remote();
charger_control_disable_charger_relay();
charger_control_setup_DACs();
charger_control_set_current(0);
charger_control_set_voltage(0);
}
/*** @brief Get State of voltage, current and error flags of the charger
* @retval Struct Containing charger information
*/
ChargerStatusHandleTypeDef charger_control_get_state()
{
ChargerStatusHandleTypeDef chargerstate;
chargerstate.voltage = readADCVoltage();
chargerstate.current = readADCCurrent();
chargerstate.acfail = HAL_GPIO_ReadPin(Charger_AC_Fail_GPIO_Port, Charger_AC_Fail_Pin);
chargerstate.dcfail = HAL_GPIO_ReadPin(Charger_DC_FAIL_GPIO_Port, Charger_DC_FAIL_Pin);
chargerstate.cc_status = HAL_GPIO_ReadPin(Charger_CC_Status_GPIO_Port, Charger_CC_Status_Pin);
chargerstate.lim_status = HAL_GPIO_ReadPin(Charger_LIM_GPIO_Port, Charger_LIM_Pin);
chargerstate.ot_status = HAL_GPIO_ReadPin(Charger_OT_GPIO_Port, Charger_OT_Pin);
return chargerstate;
}
void charger_control_setup_DACs()
{
uint8_t enabledacs[2] = {0x1C, 0x02};
HAL_I2C_Master_Transmit(charger_i2c, CURRENT_DAC_ADR, enabledacs, 2, 1000);
HAL_I2C_Master_Transmit(charger_i2c, VOLTAGE_DAC_ADR, enabledacs, 2, 1000);
}
/*** @brief set current channel using the DAC
* @param current value in 10 bit => 0-5V are equal to 0-10A so 1 bit is approx 49mA
*
*/
void charger_control_set_current(uint32_t current)
{
uint8_t currentlow = current & 0xFF;
uint8_t currenthigh = ((current>>8) & 0x03) | 0x04;
uint8_t current_dac_data[2] = {currenthigh,currentlow};
HAL_I2C_Master_Transmit(charger_i2c, CURRENT_DAC_ADR, current_dac_data, 2, 1000);
}
/** @brief set voltage channel using the DAC
* @param voltage value in 10 bit => 0-5V are equal to 0-600V so 1 bit is approx. 2.93V
*
*/
void charger_control_set_voltage(uint32_t voltage)
{
uint8_t voltagelow = voltage & 0xFF;
uint8_t voltagehigh = ((voltage>>8) & 0x03) | 0x04;
uint8_t voltage_dac_data[2] = {voltagehigh,voltagelow};
HAL_I2C_Master_Transmit(charger_i2c, VOLTAGE_DAC_ADR, voltage_dac_data, 2, 1000);
}
/** @brief Closes the main charger Relay
* @note The relay is also dependend on the Shutdown Circuit
*/
void charger_control_enable_charger_relay()
{
HAL_GPIO_WritePin(Charger_Relay_GPIO_Port, Charger_Relay_Pin, GPIO_PIN_SET);
}
/** @brief opens the main charger Relay
* @note The relay is also dependend on the Shutdown Circuit
*/
void charger_control_disable_charger_relay()
{
HAL_GPIO_WritePin(Charger_Relay_GPIO_Port, Charger_Relay_Pin, GPIO_PIN_RESET);
}
/** @brief enables remote control of the charger
* @note The relay is also dependend on the Shutdown Circuit
*/
void charger_control_enable_remote()
{
HAL_GPIO_WritePin(Charger_Remote_Shutdown_GPIO_Port, Charger_Remote_Shutdown_Pin, GPIO_PIN_SET);
}
/** @brief disable remote control of the charger
* @note The relay is also dependend on the Shutdown Circuit
*/
void charger_control_disable_remote()
{
HAL_GPIO_WritePin(Charger_Remote_Shutdown_GPIO_Port, Charger_Remote_Shutdown_Pin, GPIO_PIN_RESET);
}

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

@ -0,0 +1,811 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.c
* @brief : Main program body
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2022 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "charger_control.h"
#include "slave_handler.h"
#include "can.h"
#include "b_cccv_algo.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 ---------------------------------------------------------*/
FDCAN_HandleTypeDef hfdcan1;
I2C_HandleTypeDef hi2c4;
LTDC_HandleTypeDef hltdc;
SD_HandleTypeDef hsd2;
UART_HandleTypeDef huart5;
UART_HandleTypeDef huart10;
PCD_HandleTypeDef hpcd_USB_OTG_HS;
SDRAM_HandleTypeDef hsdram1;
uint16_t setpoint = 0;
float currentsetpoint = 0.0;
float voltagesetpoint = 3.8;
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
void PeriphCommonClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_FDCAN1_Init(void);
static void MX_FMC_Init(void);
static void MX_I2C4_Init(void);
static void MX_SDMMC2_SD_Init(void);
static void MX_USART10_UART_Init(void);
static void MX_USB_OTG_HS_PCD_Init(void);
static void MX_UART5_Init(void);
static void MX_LTDC_Init(void);
/* USER CODE BEGIN PFP */
uint32_t MemoryCheck(UART_HandleTypeDef *uart_console, SDRAM_HandleTypeDef *sram);
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
#define RAM_TEST_BLOCKSIZE 4096
__attribute__((section(".ahb_sec"))) uint32_t testarray[RAM_TEST_BLOCKSIZE];
/* 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();
/* Configure the peripherals common clocks */
PeriphCommonClock_Config();
/* USER CODE BEGIN SysInit */
/* USER CODE END SysInit */
/* Initialize all configured peripherals */
MX_GPIO_Init();
MX_FDCAN1_Init();
//MX_FMC_Init();
MX_I2C4_Init();
//MX_SDMMC2_SD_Init();
MX_USART10_UART_Init();
MX_USB_OTG_HS_PCD_Init();
MX_UART5_Init();
//MX_LTDC_Init();
/* USER CODE BEGIN 2 */
//uint32_t sdramcheck = MemoryCheck(&huart5, &hsdram1);
//MX_LTDC_Init();
slave_handler_init();
initCan(&hfdcan1);
charger_control_init(&hi2c4);
initChargerAlgo(102, 4.15);
setchargecurrent(0.0);
setchargevoltage(102, 0);
charger_control_disable_remote();
//HAL_LTDC_Reload(&hltdc, LTDC_RELOAD_IMMEDIATE);
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
uint32_t lasttick = HAL_GetTick();
while (1)
{
/* USER CODE END WHILE */
/* USER CODE BEGIN 3 */
if((HAL_GetTick() - lasttick) > 1000)
{
float maxvoltage = slaves_get_maximum_voltage();
lasttick = HAL_GetTick();
chargingloop(slaves_get_maximum_voltage());
}
// HAL_GPIO_TogglePin(STATUS_LED_2_GPIO_Port, STATUS_LED_2_Pin);
// HAL_Delay(500);
}
/* USER CODE END 3 */
}
/**
* @brief System Clock Configuration
* @retval None
*/
void SystemClock_Config(void)
{
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
/*AXI clock gating */
RCC->CKGAENR = 0xFFFFFFFF;
/** Supply configuration update enable
*/
HAL_PWREx_ConfigSupply(PWR_LDO_SUPPLY);
/** Configure the main internal regulator output voltage
*/
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2);
while(!__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY)) {}
/** Macro to configure the PLL clock source
*/
__HAL_RCC_PLL_PLLSOURCE_CONFIG(RCC_PLLSOURCE_HSE);
/** Initializes the RCC Oscillators according to the specified parameters
* in the RCC_OscInitTypeDef structure.
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI48|RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.HSI48State = RCC_HSI48_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = 1;
RCC_OscInitStruct.PLL.PLLN = 20;
RCC_OscInitStruct.PLL.PLLP = 2;
RCC_OscInitStruct.PLL.PLLQ = 4;
RCC_OscInitStruct.PLL.PLLR = 2;
RCC_OscInitStruct.PLL.PLLRGE = RCC_PLL1VCIRANGE_3;
RCC_OscInitStruct.PLL.PLLVCOSEL = RCC_PLL1VCOWIDE;
RCC_OscInitStruct.PLL.PLLFRACN = 0;
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_CLOCKTYPE_D3PCLK1|RCC_CLOCKTYPE_D1PCLK1;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.SYSCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.AHBCLKDivider = RCC_HCLK_DIV1;
RCC_ClkInitStruct.APB3CLKDivider = RCC_APB3_DIV2;
RCC_ClkInitStruct.APB1CLKDivider = RCC_APB1_DIV2;
RCC_ClkInitStruct.APB2CLKDivider = RCC_APB2_DIV2;
RCC_ClkInitStruct.APB4CLKDivider = RCC_APB4_DIV2;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_4) != HAL_OK)
{
Error_Handler();
}
}
/**
* @brief Peripherals Common Clock Configuration
* @retval None
*/
void PeriphCommonClock_Config(void)
{
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
/** Initializes the peripherals clock
*/
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_FMC|RCC_PERIPHCLK_SDMMC;
PeriphClkInitStruct.PLL2.PLL2M = 1;
PeriphClkInitStruct.PLL2.PLL2N = 20;
PeriphClkInitStruct.PLL2.PLL2P = 2;
PeriphClkInitStruct.PLL2.PLL2Q = 4;
PeriphClkInitStruct.PLL2.PLL2R = 2;
PeriphClkInitStruct.PLL2.PLL2RGE = RCC_PLL2VCIRANGE_3;
PeriphClkInitStruct.PLL2.PLL2VCOSEL = RCC_PLL2VCOWIDE;
PeriphClkInitStruct.PLL2.PLL2FRACN = 0;
PeriphClkInitStruct.FmcClockSelection = RCC_FMCCLKSOURCE_PLL2;
PeriphClkInitStruct.SdmmcClockSelection = RCC_SDMMCCLKSOURCE_PLL2;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
{
Error_Handler();
}
}
/**
* @brief FDCAN1 Initialization Function
* @param None
* @retval None
*/
static void MX_FDCAN1_Init(void)
{
/* USER CODE BEGIN FDCAN1_Init 0 */
/* USER CODE END FDCAN1_Init 0 */
/* USER CODE BEGIN FDCAN1_Init 1 */
/* USER CODE END FDCAN1_Init 1 */
hfdcan1.Instance = FDCAN1;
hfdcan1.Init.FrameFormat = FDCAN_FRAME_CLASSIC;
hfdcan1.Init.Mode = FDCAN_MODE_NORMAL;
hfdcan1.Init.AutoRetransmission = DISABLE;
hfdcan1.Init.TransmitPause = DISABLE;
hfdcan1.Init.ProtocolException = DISABLE;
hfdcan1.Init.NominalPrescaler = 2;
hfdcan1.Init.NominalSyncJumpWidth = 1;
hfdcan1.Init.NominalTimeSeg1 = 63;
hfdcan1.Init.NominalTimeSeg2 = 16;
hfdcan1.Init.DataPrescaler = 1;
hfdcan1.Init.DataSyncJumpWidth = 1;
hfdcan1.Init.DataTimeSeg1 = 1;
hfdcan1.Init.DataTimeSeg2 = 1;
hfdcan1.Init.MessageRAMOffset = 0;
hfdcan1.Init.StdFiltersNbr = 32;
hfdcan1.Init.ExtFiltersNbr = 0;
hfdcan1.Init.RxFifo0ElmtsNbr = 16;
hfdcan1.Init.RxFifo0ElmtSize = FDCAN_DATA_BYTES_8;
hfdcan1.Init.RxFifo1ElmtsNbr = 0;
hfdcan1.Init.RxFifo1ElmtSize = FDCAN_DATA_BYTES_8;
hfdcan1.Init.RxBuffersNbr = 0;
hfdcan1.Init.RxBufferSize = FDCAN_DATA_BYTES_8;
hfdcan1.Init.TxEventsNbr = 0;
hfdcan1.Init.TxBuffersNbr = 0;
hfdcan1.Init.TxFifoQueueElmtsNbr = 1;
hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION;
hfdcan1.Init.TxElmtSize = FDCAN_DATA_BYTES_8;
if (HAL_FDCAN_Init(&hfdcan1) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN FDCAN1_Init 2 */
/* USER CODE END FDCAN1_Init 2 */
}
/**
* @brief I2C4 Initialization Function
* @param None
* @retval None
*/
static void MX_I2C4_Init(void)
{
/* USER CODE BEGIN I2C4_Init 0 */
/* USER CODE END I2C4_Init 0 */
/* USER CODE BEGIN I2C4_Init 1 */
/* USER CODE END I2C4_Init 1 */
hi2c4.Instance = I2C4;
hi2c4.Init.Timing = 0x10909CEC;
hi2c4.Init.OwnAddress1 = 0;
hi2c4.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
hi2c4.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
hi2c4.Init.OwnAddress2 = 0;
hi2c4.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
hi2c4.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
hi2c4.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
if (HAL_I2C_Init(&hi2c4) != HAL_OK)
{
Error_Handler();
}
/** Configure Analogue filter
*/
if (HAL_I2CEx_ConfigAnalogFilter(&hi2c4, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
{
Error_Handler();
}
/** Configure Digital filter
*/
if (HAL_I2CEx_ConfigDigitalFilter(&hi2c4, 0) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN I2C4_Init 2 */
/* USER CODE END I2C4_Init 2 */
}
/**
* @brief LTDC Initialization Function
* @param None
* @retval None
*/
static void MX_LTDC_Init(void)
{
/* USER CODE BEGIN LTDC_Init 0 */
/* USER CODE END LTDC_Init 0 */
LTDC_LayerCfgTypeDef pLayerCfg = {0};
/* USER CODE BEGIN LTDC_Init 1 */
/* USER CODE END LTDC_Init 1 */
hltdc.Instance = LTDC;
hltdc.Init.HSPolarity = LTDC_HSPOLARITY_AL;
hltdc.Init.VSPolarity = LTDC_VSPOLARITY_AL;
hltdc.Init.DEPolarity = LTDC_DEPOLARITY_AL;
hltdc.Init.PCPolarity = LTDC_PCPOLARITY_IPC;
hltdc.Init.HorizontalSync = 19;
hltdc.Init.VerticalSync = 2;
hltdc.Init.AccumulatedHBP = 159;
hltdc.Init.AccumulatedVBP = 22;
hltdc.Init.AccumulatedActiveW = 1183;
hltdc.Init.AccumulatedActiveH = 622;
hltdc.Init.TotalWidth = 1343;
hltdc.Init.TotalHeigh = 634;
hltdc.Init.Backcolor.Blue = 0;
hltdc.Init.Backcolor.Green = 0;
hltdc.Init.Backcolor.Red = 0;
if (HAL_LTDC_Init(&hltdc) != HAL_OK)
{
Error_Handler();
}
pLayerCfg.WindowX0 = 0;
pLayerCfg.WindowX1 = 0;
pLayerCfg.WindowY0 = 0;
pLayerCfg.WindowY1 = 0;
pLayerCfg.PixelFormat = LTDC_PIXEL_FORMAT_RGB888;
pLayerCfg.Alpha = 0;
pLayerCfg.Alpha0 = 0;
pLayerCfg.BlendingFactor1 = LTDC_BLENDING_FACTOR1_CA;
pLayerCfg.BlendingFactor2 = LTDC_BLENDING_FACTOR2_CA;
pLayerCfg.FBStartAdress = 201326592;
pLayerCfg.ImageWidth = 1024;
pLayerCfg.ImageHeight = 600;
pLayerCfg.Backcolor.Blue = 100;
pLayerCfg.Backcolor.Green = 0;
pLayerCfg.Backcolor.Red = 0;
if (HAL_LTDC_ConfigLayer(&hltdc, &pLayerCfg, 0) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN LTDC_Init 2 */
__HAL_LTDC_ENABLE(&hltdc);
__HAL_LTDC_LAYER_ENABLE(&hltdc,1);
/* USER CODE END LTDC_Init 2 */
}
/**
* @brief SDMMC2 Initialization Function
* @param None
* @retval None
*/
static void MX_SDMMC2_SD_Init(void)
{
/* USER CODE BEGIN SDMMC2_Init 0 */
/* USER CODE END SDMMC2_Init 0 */
/* USER CODE BEGIN SDMMC2_Init 1 */
/* USER CODE END SDMMC2_Init 1 */
hsd2.Instance = SDMMC2;
hsd2.Init.ClockEdge = SDMMC_CLOCK_EDGE_RISING;
hsd2.Init.ClockPowerSave = SDMMC_CLOCK_POWER_SAVE_DISABLE;
hsd2.Init.BusWide = SDMMC_BUS_WIDE_1B;
hsd2.Init.HardwareFlowControl = SDMMC_HARDWARE_FLOW_CONTROL_DISABLE;
hsd2.Init.ClockDiv = 0;
if (HAL_SD_Init(&hsd2) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN SDMMC2_Init 2 */
/* USER CODE END SDMMC2_Init 2 */
}
/**
* @brief UART5 Initialization Function
* @param None
* @retval None
*/
static void MX_UART5_Init(void)
{
/* USER CODE BEGIN UART5_Init 0 */
/* USER CODE END UART5_Init 0 */
/* USER CODE BEGIN UART5_Init 1 */
/* USER CODE END UART5_Init 1 */
huart5.Instance = UART5;
huart5.Init.BaudRate = 115200;
huart5.Init.WordLength = UART_WORDLENGTH_8B;
huart5.Init.StopBits = UART_STOPBITS_1;
huart5.Init.Parity = UART_PARITY_NONE;
huart5.Init.Mode = UART_MODE_TX_RX;
huart5.Init.HwFlowCtl = UART_HWCONTROL_NONE;
huart5.Init.OverSampling = UART_OVERSAMPLING_16;
huart5.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
huart5.Init.ClockPrescaler = UART_PRESCALER_DIV1;
huart5.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
if (HAL_UART_Init(&huart5) != HAL_OK)
{
Error_Handler();
}
if (HAL_UARTEx_SetTxFifoThreshold(&huart5, UART_TXFIFO_THRESHOLD_1_8) != HAL_OK)
{
Error_Handler();
}
if (HAL_UARTEx_SetRxFifoThreshold(&huart5, UART_RXFIFO_THRESHOLD_1_8) != HAL_OK)
{
Error_Handler();
}
if (HAL_UARTEx_DisableFifoMode(&huart5) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN UART5_Init 2 */
/* USER CODE END UART5_Init 2 */
}
/**
* @brief USART10 Initialization Function
* @param None
* @retval None
*/
static void MX_USART10_UART_Init(void)
{
/* USER CODE BEGIN USART10_Init 0 */
/* USER CODE END USART10_Init 0 */
/* USER CODE BEGIN USART10_Init 1 */
/* USER CODE END USART10_Init 1 */
huart10.Instance = USART10;
huart10.Init.BaudRate = 115200;
huart10.Init.WordLength = UART_WORDLENGTH_8B;
huart10.Init.StopBits = UART_STOPBITS_1;
huart10.Init.Parity = UART_PARITY_NONE;
huart10.Init.Mode = UART_MODE_TX_RX;
huart10.Init.HwFlowCtl = UART_HWCONTROL_NONE;
huart10.Init.OverSampling = UART_OVERSAMPLING_16;
huart10.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
huart10.Init.ClockPrescaler = UART_PRESCALER_DIV1;
huart10.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
if (HAL_UART_Init(&huart10) != HAL_OK)
{
Error_Handler();
}
if (HAL_UARTEx_SetTxFifoThreshold(&huart10, UART_TXFIFO_THRESHOLD_1_8) != HAL_OK)
{
Error_Handler();
}
if (HAL_UARTEx_SetRxFifoThreshold(&huart10, UART_RXFIFO_THRESHOLD_1_8) != HAL_OK)
{
Error_Handler();
}
if (HAL_UARTEx_DisableFifoMode(&huart10) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN USART10_Init 2 */
/* USER CODE END USART10_Init 2 */
}
/**
* @brief USB_OTG_HS Initialization Function
* @param None
* @retval None
*/
static void MX_USB_OTG_HS_PCD_Init(void)
{
/* USER CODE BEGIN USB_OTG_HS_Init 0 */
/* USER CODE END USB_OTG_HS_Init 0 */
/* USER CODE BEGIN USB_OTG_HS_Init 1 */
/* USER CODE END USB_OTG_HS_Init 1 */
hpcd_USB_OTG_HS.Instance = USB_OTG_HS;
hpcd_USB_OTG_HS.Init.dev_endpoints = 9;
hpcd_USB_OTG_HS.Init.speed = PCD_SPEED_FULL;
hpcd_USB_OTG_HS.Init.dma_enable = DISABLE;
hpcd_USB_OTG_HS.Init.phy_itface = USB_OTG_EMBEDDED_PHY;
hpcd_USB_OTG_HS.Init.Sof_enable = DISABLE;
hpcd_USB_OTG_HS.Init.low_power_enable = DISABLE;
hpcd_USB_OTG_HS.Init.lpm_enable = DISABLE;
hpcd_USB_OTG_HS.Init.vbus_sensing_enable = ENABLE;
hpcd_USB_OTG_HS.Init.use_dedicated_ep1 = DISABLE;
hpcd_USB_OTG_HS.Init.use_external_vbus = DISABLE;
if (HAL_PCD_Init(&hpcd_USB_OTG_HS) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN USB_OTG_HS_Init 2 */
/* USER CODE END USB_OTG_HS_Init 2 */
}
/* FMC initialization function */
static void MX_FMC_Init(void)
{
/* USER CODE BEGIN FMC_Init 0 */
/* USER CODE END FMC_Init 0 */
FMC_SDRAM_TimingTypeDef SdramTiming = {0};
/* USER CODE BEGIN FMC_Init 1 */
/* USER CODE END FMC_Init 1 */
/** Perform the SDRAM1 memory initialization sequence
*/
hsdram1.Instance = FMC_SDRAM_DEVICE;
/* hsdram1.Init */
hsdram1.Init.SDBank = FMC_SDRAM_BANK1;
hsdram1.Init.ColumnBitsNumber = FMC_SDRAM_COLUMN_BITS_NUM_9;
hsdram1.Init.RowBitsNumber = FMC_SDRAM_ROW_BITS_NUM_13;
hsdram1.Init.MemoryDataWidth = FMC_SDRAM_MEM_BUS_WIDTH_16;
hsdram1.Init.InternalBankNumber = FMC_SDRAM_INTERN_BANKS_NUM_4;
hsdram1.Init.CASLatency = FMC_SDRAM_CAS_LATENCY_3;
hsdram1.Init.WriteProtection = FMC_SDRAM_WRITE_PROTECTION_DISABLE;
hsdram1.Init.SDClockPeriod = FMC_SDRAM_CLOCK_PERIOD_2;
hsdram1.Init.ReadBurst = FMC_SDRAM_RBURST_DISABLE;
hsdram1.Init.ReadPipeDelay = FMC_SDRAM_RPIPE_DELAY_1;
/* SdramTiming */
SdramTiming.LoadToActiveDelay = 2;
SdramTiming.ExitSelfRefreshDelay = 5;
SdramTiming.SelfRefreshTime = 3;
SdramTiming.RowCycleDelay = 4;
SdramTiming.WriteRecoveryTime = 3;
SdramTiming.RPDelay = 3;
SdramTiming.RCDDelay = 2;
if (HAL_SDRAM_Init(&hsdram1, &SdramTiming) != HAL_OK)
{
Error_Handler( );
}
/* USER CODE BEGIN FMC_Init 2 */
FMC_SDRAM_CommandTypeDef command;
HAL_StatusTypeDef status;
command.CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1;
command.CommandMode = FMC_SDRAM_CMD_CLK_ENABLE;
command.AutoRefreshNumber = 1;
command.ModeRegisterDefinition = 0;
status = HAL_SDRAM_SendCommand(&hsdram1, &command, 1000);
HAL_Delay(1);
command.CommandMode = FMC_SDRAM_CMD_PALL;
command.AutoRefreshNumber = 8;
command.ModeRegisterDefinition = 0;
status = HAL_SDRAM_SendCommand(&hsdram1, &command, 1000);
command.CommandMode = FMC_SDRAM_CMD_LOAD_MODE;
command.AutoRefreshNumber = 1;
command.ModeRegisterDefinition = 0x130;
status = HAL_SDRAM_SendCommand(&hsdram1, &command, 1000);
command.CommandMode = FMC_SDRAM_CMD_AUTOREFRESH_MODE;
command.AutoRefreshNumber = 8;
command.ModeRegisterDefinition = 0;
status = HAL_SDRAM_SendCommand(&hsdram1, &command, 1000);
status = HAL_SDRAM_ProgramRefreshRate(&hsdram1, 0x0595);
/* USER CODE END FMC_Init 2 */
}
/**
* @brief GPIO Initialization Function
* @param None
* @retval None
*/
static void MX_GPIO_Init(void)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
/* GPIO Ports Clock Enable */
__HAL_RCC_GPIOE_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOF_CLK_ENABLE();
__HAL_RCC_GPIOH_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
__HAL_RCC_GPIOG_CLK_ENABLE();
__HAL_RCC_GPIOD_CLK_ENABLE();
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOF, STATUS_LED_1_Pin|STATUS_LED_2_Pin, GPIO_PIN_RESET);
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOC, Display_Reset_Pin|Display_Standby_Pin|Display_Left_Right_Pin|Display_Up_Down_Pin, GPIO_PIN_RESET);
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(Charger_Relay_GPIO_Port, Charger_Relay_Pin, GPIO_PIN_RESET);
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(Charger_Remote_Shutdown_GPIO_Port, Charger_Remote_Shutdown_Pin, GPIO_PIN_RESET);
/*Configure GPIO pins : STATUS_LED_1_Pin STATUS_LED_2_Pin */
GPIO_InitStruct.Pin = STATUS_LED_1_Pin|STATUS_LED_2_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);
/*Configure GPIO pins : Display_Reset_Pin Display_Standby_Pin Display_Left_Right_Pin Display_Up_Down_Pin */
GPIO_InitStruct.Pin = Display_Reset_Pin|Display_Standby_Pin|Display_Left_Right_Pin|Display_Up_Down_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);
/*Configure GPIO pins : Charger_CC_Status_Pin Charger_OT_Pin Charger_LIM_Pin Charger_DC_FAIL_Pin */
GPIO_InitStruct.Pin = Charger_CC_Status_Pin|Charger_OT_Pin|Charger_LIM_Pin|Charger_DC_FAIL_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOG, &GPIO_InitStruct);
/*Configure GPIO pin : Charger_Relay_Pin */
GPIO_InitStruct.Pin = Charger_Relay_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(Charger_Relay_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pin : Charger_AC_Fail_Pin */
GPIO_InitStruct.Pin = Charger_AC_Fail_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(Charger_AC_Fail_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pin : Charger_Remote_Shutdown_Pin */
GPIO_InitStruct.Pin = Charger_Remote_Shutdown_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(Charger_Remote_Shutdown_GPIO_Port, &GPIO_InitStruct);
}
/* USER CODE BEGIN 4 */
/** @brief run a Memory Check over the complete SDRAM Area
*
*/
uint32_t MemoryCheck(UART_HandleTypeDef *uart_console, SDRAM_HandleTypeDef *sram)
{
uint32_t totalerrors = 0;
uint32_t numberofsectors = 400;
uint32_t testadr = 0xC0000000;
//*testpointer = 1;
for(uint32_t startaddress = 0; startaddress < numberofsectors*RAM_TEST_BLOCKSIZE; startaddress += RAM_TEST_BLOCKSIZE)
{
for(uint32_t i = 0; i < RAM_TEST_BLOCKSIZE; i++)
{
testarray[i] = 0xFFFF00FF;
}
//*testadr = (uint32_t*) ;
HAL_StatusTypeDef status = HAL_SDRAM_Write_32b(sram, (uint32_t*)(testadr+startaddress), testarray, RAM_TEST_BLOCKSIZE);
//testadr = (uint32_t*) (startaddress + 0xC0000000);
for(uint32_t i = 0; i < RAM_TEST_BLOCKSIZE; i++)
{
testarray[i] = 0;
}
status = HAL_SDRAM_Read_32b(sram,(uint32_t*)(testadr+startaddress), testarray, RAM_TEST_BLOCKSIZE);
uint32_t errorcounter = 0;
for(uint32_t i = 0; i <RAM_TEST_BLOCKSIZE;i++)
{
if(testarray[i] != (i+3000))
{
errorcounter++;
}
}
totalerrors += errorcounter;
}
return totalerrors;
}
/* 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 */

70
Core/Src/slave_handler.c Normal file
View File

@ -0,0 +1,70 @@
/*
* slave_handler.c
*
* Created on: Jun 21, 2023
* Author: max
*/
#include "slave_handler.h"
#include "can.h"
#include "can-halal.h"
static uint8_t slave_id_to_index[128] = {0xFF};
void slave_handler_init()
{
memset(slave_id_to_index,0xFF,128);
}
SlaveHandle slaves[N_SLAVES];
static size_t get_slave_index(uint8_t);
void slaves_handle_status(const uint8_t *data) {
uint8_t slave_id = data[0] & 0x7F;
uint8_t idx = get_slave_index(slave_id);
int error = data[0] & 0x80;
if (error) {
if (slaves[idx].error.kind == SLAVE_ERR_NONE) {
slaves[idx].error.kind = SLAVE_ERR_UNKNOWN;
}
} else {
slaves[idx].error.kind = SLAVE_ERR_NONE;
}
slaves[idx].soc = data[1];
const uint8_t *ptr = &data[2];
slaves[idx].min_voltage = ftcan_unmarshal_unsigned(&ptr, 2);
slaves[idx].max_voltage = ftcan_unmarshal_unsigned(&ptr, 2);
slaves[idx].max_temp = ftcan_unmarshal_unsigned(&ptr, 2);
slaves[idx].last_message = HAL_GetTick();
}
float slaves_get_maximum_voltage()
{
float maxvoltage = 0;
for(uint8_t i = 0; i < N_SLAVES; i++)
{
if(maxvoltage < slaves[i].max_voltage)
maxvoltage = slaves[i].max_voltage;
}
return ((float)maxvoltage)/10000;
}
static size_t get_slave_index(uint8_t slave_id) {
// Slave IDs are 7-bit, so we can use a 128-element array to map them to
// indices. 0xFF is used to mark unseen slave IDs, since the highest index we
// could need is N_SLAVES - 1 (i.e. 5).
static size_t next_slave_index = 0;
if (slave_id_to_index[slave_id] == 0xFF) {
if (next_slave_index >= N_SLAVES) {
// We've seen more than N_SLAVES slave IDs, this shouldn't happen.
Error_Handler();
}
slave_id_to_index[slave_id] = next_slave_index;
slaves[next_slave_index].id = slave_id;
next_slave_index++;
}
return slave_id_to_index[slave_id];
}

View File

@ -0,0 +1,976 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32h7xx_hal_msp.c
* @brief This file provides code for the MSP Initialization
* and de-Initialization codes.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2022 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* 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 */
/**
* Initializes the Global MSP.
*/
void HAL_MspInit(void)
{
/* USER CODE BEGIN MspInit 0 */
/* USER CODE END MspInit 0 */
__HAL_RCC_SYSCFG_CLK_ENABLE();
/* System interrupt init*/
/* USER CODE BEGIN MspInit 1 */
/* USER CODE END MspInit 1 */
}
/**
* @brief FDCAN MSP Initialization
* This function configures the hardware resources used in this example
* @param hfdcan: FDCAN handle pointer
* @retval None
*/
void HAL_FDCAN_MspInit(FDCAN_HandleTypeDef* hfdcan)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
if(hfdcan->Instance==FDCAN1)
{
/* USER CODE BEGIN FDCAN1_MspInit 0 */
/* USER CODE END FDCAN1_MspInit 0 */
/** Initializes the peripherals clock
*/
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_FDCAN;
PeriphClkInitStruct.FdcanClockSelection = RCC_FDCANCLKSOURCE_PLL;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
{
Error_Handler();
}
/* Peripheral clock enable */
__HAL_RCC_FDCAN_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/**FDCAN1 GPIO Configuration
PB8 ------> FDCAN1_RX
PB9 ------> FDCAN1_TX
*/
GPIO_InitStruct.Pin = GPIO_PIN_8|GPIO_PIN_9;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF9_FDCAN1;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* FDCAN1 interrupt Init */
HAL_NVIC_SetPriority(FDCAN1_IT0_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(FDCAN1_IT0_IRQn);
HAL_NVIC_SetPriority(FDCAN1_IT1_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(FDCAN1_IT1_IRQn);
HAL_NVIC_SetPriority(FDCAN_CAL_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(FDCAN_CAL_IRQn);
/* USER CODE BEGIN FDCAN1_MspInit 1 */
/* USER CODE END FDCAN1_MspInit 1 */
}
}
/**
* @brief FDCAN MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hfdcan: FDCAN handle pointer
* @retval None
*/
void HAL_FDCAN_MspDeInit(FDCAN_HandleTypeDef* hfdcan)
{
if(hfdcan->Instance==FDCAN1)
{
/* USER CODE BEGIN FDCAN1_MspDeInit 0 */
/* USER CODE END FDCAN1_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_FDCAN_CLK_DISABLE();
/**FDCAN1 GPIO Configuration
PB8 ------> FDCAN1_RX
PB9 ------> FDCAN1_TX
*/
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_8|GPIO_PIN_9);
/* FDCAN1 interrupt DeInit */
HAL_NVIC_DisableIRQ(FDCAN1_IT0_IRQn);
HAL_NVIC_DisableIRQ(FDCAN1_IT1_IRQn);
HAL_NVIC_DisableIRQ(FDCAN_CAL_IRQn);
/* USER CODE BEGIN FDCAN1_MspDeInit 1 */
/* USER CODE END FDCAN1_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};
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
if(hi2c->Instance==I2C4)
{
/* USER CODE BEGIN I2C4_MspInit 0 */
/* USER CODE END I2C4_MspInit 0 */
/** Initializes the peripherals clock
*/
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_I2C4;
PeriphClkInitStruct.I2c4ClockSelection = RCC_I2C4CLKSOURCE_D3PCLK1;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
{
Error_Handler();
}
__HAL_RCC_GPIOB_CLK_ENABLE();
/**I2C4 GPIO Configuration
PB6 ------> I2C4_SCL
PB7 ------> I2C4_SDA
*/
GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF6_I2C4;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* Peripheral clock enable */
__HAL_RCC_I2C4_CLK_ENABLE();
/* USER CODE BEGIN I2C4_MspInit 1 */
/* USER CODE END I2C4_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==I2C4)
{
/* USER CODE BEGIN I2C4_MspDeInit 0 */
/* USER CODE END I2C4_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_I2C4_CLK_DISABLE();
/**I2C4 GPIO Configuration
PB6 ------> I2C4_SCL
PB7 ------> I2C4_SDA
*/
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_6);
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_7);
/* USER CODE BEGIN I2C4_MspDeInit 1 */
/* USER CODE END I2C4_MspDeInit 1 */
}
}
/**
* @brief LTDC MSP Initialization
* This function configures the hardware resources used in this example
* @param hltdc: LTDC handle pointer
* @retval None
*/
void HAL_LTDC_MspInit(LTDC_HandleTypeDef* hltdc)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
if(hltdc->Instance==LTDC)
{
/* USER CODE BEGIN LTDC_MspInit 0 */
/* USER CODE END LTDC_MspInit 0 */
/** Initializes the peripherals clock
*/
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_LTDC;
PeriphClkInitStruct.PLL3.PLL3M = 1;
PeriphClkInitStruct.PLL3.PLL3N = 12;
PeriphClkInitStruct.PLL3.PLL3P = 2;
PeriphClkInitStruct.PLL3.PLL3Q = 3;
PeriphClkInitStruct.PLL3.PLL3R = 3;
PeriphClkInitStruct.PLL3.PLL3RGE = RCC_PLL3VCIRANGE_3;
PeriphClkInitStruct.PLL3.PLL3VCOSEL = RCC_PLL3VCOWIDE;
PeriphClkInitStruct.PLL3.PLL3FRACN = 0.0;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
{
Error_Handler();
}
/* Peripheral clock enable */
__HAL_RCC_LTDC_CLK_ENABLE();
__HAL_RCC_GPIOF_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
__HAL_RCC_GPIOG_CLK_ENABLE();
__HAL_RCC_GPIOD_CLK_ENABLE();
/**LTDC GPIO Configuration
PF10 ------> LTDC_DE
PC0 ------> LTDC_R5
PA1 ------> LTDC_R2
PA3 ------> LTDC_B5
PA4 ------> LTDC_VSYNC
PA5 ------> LTDC_R4
PA6 ------> LTDC_G2
PC4 ------> LTDC_R7
PB0 ------> LTDC_R3
PB1 ------> LTDC_R6
PB10 ------> LTDC_G4
PB11 ------> LTDC_G5
PB15 ------> LTDC_G7
PG7 ------> LTDC_CLK
PC6 ------> LTDC_HSYNC
PC7 ------> LTDC_G6
PC9 ------> LTDC_G3
PA8 ------> LTDC_B3
PA10 ------> LTDC_B4
PA15 ------> LTDC_B6
PD2 ------> LTDC_B7
PD6 ------> LTDC_B2
*/
GPIO_InitStruct.Pin = GPIO_PIN_10;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF14_LTDC;
HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_4|GPIO_PIN_6|GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF14_LTDC;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_1|GPIO_PIN_3|GPIO_PIN_4|GPIO_PIN_5
|GPIO_PIN_6|GPIO_PIN_15;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF14_LTDC;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF9_LTDC;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_10|GPIO_PIN_11|GPIO_PIN_15;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF14_LTDC;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF14_LTDC;
HAL_GPIO_Init(GPIOG, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_9;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF10_LTDC;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_8;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF13_LTDC;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_10;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF12_LTDC;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_2;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF9_LTDC;
HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_6;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF14_LTDC;
HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
/* LTDC interrupt Init */
HAL_NVIC_SetPriority(LTDC_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(LTDC_IRQn);
HAL_NVIC_SetPriority(LTDC_ER_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(LTDC_ER_IRQn);
/* USER CODE BEGIN LTDC_MspInit 1 */
/* USER CODE END LTDC_MspInit 1 */
}
}
/**
* @brief LTDC MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hltdc: LTDC handle pointer
* @retval None
*/
void HAL_LTDC_MspDeInit(LTDC_HandleTypeDef* hltdc)
{
if(hltdc->Instance==LTDC)
{
/* USER CODE BEGIN LTDC_MspDeInit 0 */
/* USER CODE END LTDC_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_LTDC_CLK_DISABLE();
/**LTDC GPIO Configuration
PF10 ------> LTDC_DE
PC0 ------> LTDC_R5
PA1 ------> LTDC_R2
PA3 ------> LTDC_B5
PA4 ------> LTDC_VSYNC
PA5 ------> LTDC_R4
PA6 ------> LTDC_G2
PC4 ------> LTDC_R7
PB0 ------> LTDC_R3
PB1 ------> LTDC_R6
PB10 ------> LTDC_G4
PB11 ------> LTDC_G5
PB15 ------> LTDC_G7
PG7 ------> LTDC_CLK
PC6 ------> LTDC_HSYNC
PC7 ------> LTDC_G6
PC9 ------> LTDC_G3
PA8 ------> LTDC_B3
PA10 ------> LTDC_B4
PA15 ------> LTDC_B6
PD2 ------> LTDC_B7
PD6 ------> LTDC_B2
*/
HAL_GPIO_DeInit(GPIOF, GPIO_PIN_10);
HAL_GPIO_DeInit(GPIOC, GPIO_PIN_0|GPIO_PIN_4|GPIO_PIN_6|GPIO_PIN_7
|GPIO_PIN_9);
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_1|GPIO_PIN_3|GPIO_PIN_4|GPIO_PIN_5
|GPIO_PIN_6|GPIO_PIN_8|GPIO_PIN_10|GPIO_PIN_15);
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_10|GPIO_PIN_11
|GPIO_PIN_15);
HAL_GPIO_DeInit(GPIOG, GPIO_PIN_7);
HAL_GPIO_DeInit(GPIOD, GPIO_PIN_2|GPIO_PIN_6);
/* LTDC interrupt DeInit */
HAL_NVIC_DisableIRQ(LTDC_IRQn);
HAL_NVIC_DisableIRQ(LTDC_ER_IRQn);
/* USER CODE BEGIN LTDC_MspDeInit 1 */
/* USER CODE END LTDC_MspDeInit 1 */
}
}
/**
* @brief SD MSP Initialization
* This function configures the hardware resources used in this example
* @param hsd: SD handle pointer
* @retval None
*/
void HAL_SD_MspInit(SD_HandleTypeDef* hsd)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hsd->Instance==SDMMC2)
{
/* USER CODE BEGIN SDMMC2_MspInit 0 */
/* USER CODE END SDMMC2_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_SDMMC2_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
__HAL_RCC_GPIOD_CLK_ENABLE();
/**SDMMC2 GPIO Configuration
PC1 ------> SDMMC2_CK
PB14 ------> SDMMC2_D0
PD7 ------> SDMMC2_CMD
*/
GPIO_InitStruct.Pin = GPIO_PIN_1;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF9_SDMMC2;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_14;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF9_SDMMC2;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF11_SDMMC2;
HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
/* USER CODE BEGIN SDMMC2_MspInit 1 */
/* USER CODE END SDMMC2_MspInit 1 */
}
}
/**
* @brief SD MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hsd: SD handle pointer
* @retval None
*/
void HAL_SD_MspDeInit(SD_HandleTypeDef* hsd)
{
if(hsd->Instance==SDMMC2)
{
/* USER CODE BEGIN SDMMC2_MspDeInit 0 */
/* USER CODE END SDMMC2_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_SDMMC2_CLK_DISABLE();
/**SDMMC2 GPIO Configuration
PC1 ------> SDMMC2_CK
PB14 ------> SDMMC2_D0
PD7 ------> SDMMC2_CMD
*/
HAL_GPIO_DeInit(GPIOC, GPIO_PIN_1);
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_14);
HAL_GPIO_DeInit(GPIOD, GPIO_PIN_7);
/* USER CODE BEGIN SDMMC2_MspDeInit 1 */
/* USER CODE END SDMMC2_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};
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
if(huart->Instance==UART5)
{
/* USER CODE BEGIN UART5_MspInit 0 */
/* USER CODE END UART5_MspInit 0 */
/** Initializes the peripherals clock
*/
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_UART5;
PeriphClkInitStruct.Usart234578ClockSelection = RCC_USART234578CLKSOURCE_D2PCLK1;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
{
Error_Handler();
}
/* Peripheral clock enable */
__HAL_RCC_UART5_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/**UART5 GPIO Configuration
PB12 ------> UART5_RX
PB13 ------> UART5_TX
*/
GPIO_InitStruct.Pin = GPIO_PIN_12|GPIO_PIN_13;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF14_UART5;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* USER CODE BEGIN UART5_MspInit 1 */
/* USER CODE END UART5_MspInit 1 */
}
else if(huart->Instance==USART10)
{
/* USER CODE BEGIN USART10_MspInit 0 */
/* USER CODE END USART10_MspInit 0 */
/** Initializes the peripherals clock
*/
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART10;
PeriphClkInitStruct.Usart16ClockSelection = RCC_USART16910CLKSOURCE_D2PCLK2;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
{
Error_Handler();
}
/* Peripheral clock enable */
__HAL_RCC_USART10_CLK_ENABLE();
__HAL_RCC_GPIOE_CLK_ENABLE();
/**USART10 GPIO Configuration
PE2 ------> USART10_RX
PE3 ------> USART10_TX
*/
GPIO_InitStruct.Pin = GPIO_PIN_2|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_AF11_USART10;
HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
/* USER CODE BEGIN USART10_MspInit 1 */
/* USER CODE END USART10_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==UART5)
{
/* USER CODE BEGIN UART5_MspDeInit 0 */
/* USER CODE END UART5_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_UART5_CLK_DISABLE();
/**UART5 GPIO Configuration
PB12 ------> UART5_RX
PB13 ------> UART5_TX
*/
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_12|GPIO_PIN_13);
/* USER CODE BEGIN UART5_MspDeInit 1 */
/* USER CODE END UART5_MspDeInit 1 */
}
else if(huart->Instance==USART10)
{
/* USER CODE BEGIN USART10_MspDeInit 0 */
/* USER CODE END USART10_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_USART10_CLK_DISABLE();
/**USART10 GPIO Configuration
PE2 ------> USART10_RX
PE3 ------> USART10_TX
*/
HAL_GPIO_DeInit(GPIOE, GPIO_PIN_2|GPIO_PIN_3);
/* USER CODE BEGIN USART10_MspDeInit 1 */
/* USER CODE END USART10_MspDeInit 1 */
}
}
/**
* @brief PCD MSP Initialization
* This function configures the hardware resources used in this example
* @param hpcd: PCD handle pointer
* @retval None
*/
void HAL_PCD_MspInit(PCD_HandleTypeDef* hpcd)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
if(hpcd->Instance==USB_OTG_HS)
{
/* USER CODE BEGIN USB_OTG_HS_MspInit 0 */
/* USER CODE END USB_OTG_HS_MspInit 0 */
/** Initializes the peripherals clock
*/
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USB;
PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_HSI48;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
{
Error_Handler();
}
/** Enable USB Voltage detector
*/
HAL_PWREx_EnableUSBVoltageDetector();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**USB_OTG_HS GPIO Configuration
PA9 ------> USB_OTG_HS_VBUS
PA11 ------> USB_OTG_HS_DM
PA12 ------> USB_OTG_HS_DP
*/
GPIO_InitStruct.Pin = GPIO_PIN_9;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_12;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* Peripheral clock enable */
__HAL_RCC_USB_OTG_HS_CLK_ENABLE();
/* USER CODE BEGIN USB_OTG_HS_MspInit 1 */
/* USER CODE END USB_OTG_HS_MspInit 1 */
}
}
/**
* @brief PCD MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hpcd: PCD handle pointer
* @retval None
*/
void HAL_PCD_MspDeInit(PCD_HandleTypeDef* hpcd)
{
if(hpcd->Instance==USB_OTG_HS)
{
/* USER CODE BEGIN USB_OTG_HS_MspDeInit 0 */
/* USER CODE END USB_OTG_HS_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_USB_OTG_HS_CLK_DISABLE();
/**USB_OTG_HS GPIO Configuration
PA9 ------> USB_OTG_HS_VBUS
PA11 ------> USB_OTG_HS_DM
PA12 ------> USB_OTG_HS_DP
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_9|GPIO_PIN_11|GPIO_PIN_12);
/* USER CODE BEGIN USB_OTG_HS_MspDeInit 1 */
/* USER CODE END USB_OTG_HS_MspDeInit 1 */
}
}
static uint32_t FMC_Initialized = 0;
static void HAL_FMC_MspInit(void){
/* USER CODE BEGIN FMC_MspInit 0 */
/* USER CODE END FMC_MspInit 0 */
GPIO_InitTypeDef GPIO_InitStruct ={0};
if (FMC_Initialized) {
return;
}
FMC_Initialized = 1;
/* Peripheral clock enable */
__HAL_RCC_FMC_CLK_ENABLE();
/** FMC GPIO Configuration
PF0 ------> FMC_A0
PF1 ------> FMC_A1
PF2 ------> FMC_A2
PF3 ------> FMC_A3
PF4 ------> FMC_A4
PF5 ------> FMC_A5
PC2_C ------> FMC_SDNE0
PC3_C ------> FMC_SDCKE0
PA7 ------> FMC_SDNWE
PF11 ------> FMC_SDNRAS
PF12 ------> FMC_A6
PF13 ------> FMC_A7
PF14 ------> FMC_A8
PF15 ------> FMC_A9
PG0 ------> FMC_A10
PG1 ------> FMC_A11
PE7 ------> FMC_D4
PE8 ------> FMC_D5
PE9 ------> FMC_D6
PE10 ------> FMC_D7
PE11 ------> FMC_D8
PE12 ------> FMC_D9
PE13 ------> FMC_D10
PE14 ------> FMC_D11
PE15 ------> FMC_D12
PD8 ------> FMC_D13
PD9 ------> FMC_D14
PD10 ------> FMC_D15
PD14 ------> FMC_D0
PD15 ------> FMC_D1
PG2 ------> FMC_A12
PG4 ------> FMC_BA0
PG5 ------> FMC_BA1
PG8 ------> FMC_SDCLK
PD0 ------> FMC_D2
PD1 ------> FMC_D3
PG15 ------> FMC_SDNCAS
PE0 ------> FMC_NBL0
PE1 ------> FMC_NBL1
*/
GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_3
|GPIO_PIN_4|GPIO_PIN_5|GPIO_PIN_11|GPIO_PIN_12
|GPIO_PIN_13|GPIO_PIN_14|GPIO_PIN_15;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF12_FMC;
HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_2|GPIO_PIN_3;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF12_FMC;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF12_FMC;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_4
|GPIO_PIN_5|GPIO_PIN_8|GPIO_PIN_15;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF12_FMC;
HAL_GPIO_Init(GPIOG, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_7|GPIO_PIN_8|GPIO_PIN_9|GPIO_PIN_10
|GPIO_PIN_11|GPIO_PIN_12|GPIO_PIN_13|GPIO_PIN_14
|GPIO_PIN_15|GPIO_PIN_0|GPIO_PIN_1;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF12_FMC;
HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_8|GPIO_PIN_9|GPIO_PIN_10|GPIO_PIN_14
|GPIO_PIN_15|GPIO_PIN_0|GPIO_PIN_1;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF12_FMC;
HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
/* Peripheral interrupt init */
HAL_NVIC_SetPriority(FMC_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(FMC_IRQn);
/* USER CODE BEGIN FMC_MspInit 1 */
/* USER CODE END FMC_MspInit 1 */
}
void HAL_SDRAM_MspInit(SDRAM_HandleTypeDef* hsdram){
/* USER CODE BEGIN SDRAM_MspInit 0 */
/* USER CODE END SDRAM_MspInit 0 */
HAL_FMC_MspInit();
/* USER CODE BEGIN SDRAM_MspInit 1 */
/* USER CODE END SDRAM_MspInit 1 */
}
static uint32_t FMC_DeInitialized = 0;
static void HAL_FMC_MspDeInit(void){
/* USER CODE BEGIN FMC_MspDeInit 0 */
/* USER CODE END FMC_MspDeInit 0 */
if (FMC_DeInitialized) {
return;
}
FMC_DeInitialized = 1;
/* Peripheral clock enable */
__HAL_RCC_FMC_CLK_DISABLE();
/** FMC GPIO Configuration
PF0 ------> FMC_A0
PF1 ------> FMC_A1
PF2 ------> FMC_A2
PF3 ------> FMC_A3
PF4 ------> FMC_A4
PF5 ------> FMC_A5
PC2_C ------> FMC_SDNE0
PC3_C ------> FMC_SDCKE0
PA7 ------> FMC_SDNWE
PF11 ------> FMC_SDNRAS
PF12 ------> FMC_A6
PF13 ------> FMC_A7
PF14 ------> FMC_A8
PF15 ------> FMC_A9
PG0 ------> FMC_A10
PG1 ------> FMC_A11
PE7 ------> FMC_D4
PE8 ------> FMC_D5
PE9 ------> FMC_D6
PE10 ------> FMC_D7
PE11 ------> FMC_D8
PE12 ------> FMC_D9
PE13 ------> FMC_D10
PE14 ------> FMC_D11
PE15 ------> FMC_D12
PD8 ------> FMC_D13
PD9 ------> FMC_D14
PD10 ------> FMC_D15
PD14 ------> FMC_D0
PD15 ------> FMC_D1
PG2 ------> FMC_A12
PG4 ------> FMC_BA0
PG5 ------> FMC_BA1
PG8 ------> FMC_SDCLK
PD0 ------> FMC_D2
PD1 ------> FMC_D3
PG15 ------> FMC_SDNCAS
PE0 ------> FMC_NBL0
PE1 ------> FMC_NBL1
*/
HAL_GPIO_DeInit(GPIOF, GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_3
|GPIO_PIN_4|GPIO_PIN_5|GPIO_PIN_11|GPIO_PIN_12
|GPIO_PIN_13|GPIO_PIN_14|GPIO_PIN_15);
HAL_GPIO_DeInit(GPIOC, GPIO_PIN_2|GPIO_PIN_3);
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_7);
HAL_GPIO_DeInit(GPIOG, GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_4
|GPIO_PIN_5|GPIO_PIN_8|GPIO_PIN_15);
HAL_GPIO_DeInit(GPIOE, GPIO_PIN_7|GPIO_PIN_8|GPIO_PIN_9|GPIO_PIN_10
|GPIO_PIN_11|GPIO_PIN_12|GPIO_PIN_13|GPIO_PIN_14
|GPIO_PIN_15|GPIO_PIN_0|GPIO_PIN_1);
HAL_GPIO_DeInit(GPIOD, GPIO_PIN_8|GPIO_PIN_9|GPIO_PIN_10|GPIO_PIN_14
|GPIO_PIN_15|GPIO_PIN_0|GPIO_PIN_1);
/* Peripheral interrupt DeInit */
HAL_NVIC_DisableIRQ(FMC_IRQn);
/* USER CODE BEGIN FMC_MspDeInit 1 */
/* USER CODE END FMC_MspDeInit 1 */
}
void HAL_SDRAM_MspDeInit(SDRAM_HandleTypeDef* hsdram){
/* USER CODE BEGIN SDRAM_MspDeInit 0 */
/* USER CODE END SDRAM_MspDeInit 0 */
HAL_FMC_MspDeInit();
/* USER CODE BEGIN SDRAM_MspDeInit 1 */
/* USER CODE END SDRAM_MspDeInit 1 */
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

290
Core/Src/stm32h7xx_it.c Normal file
View File

@ -0,0 +1,290 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32h7xx_it.c
* @brief Interrupt Service Routines.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2022 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "stm32h7xx_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 FDCAN_HandleTypeDef hfdcan1;
extern SDRAM_HandleTypeDef hsdram1;
extern LTDC_HandleTypeDef hltdc;
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/******************************************************************************/
/* Cortex 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 */
/* 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 */
}
/******************************************************************************/
/* STM32H7xx 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_stm32h7xx.s). */
/******************************************************************************/
/**
* @brief This function handles FDCAN1 interrupt 0.
*/
void FDCAN1_IT0_IRQHandler(void)
{
/* USER CODE BEGIN FDCAN1_IT0_IRQn 0 */
/* USER CODE END FDCAN1_IT0_IRQn 0 */
HAL_FDCAN_IRQHandler(&hfdcan1);
/* USER CODE BEGIN FDCAN1_IT0_IRQn 1 */
/* USER CODE END FDCAN1_IT0_IRQn 1 */
}
/**
* @brief This function handles FDCAN1 interrupt 1.
*/
void FDCAN1_IT1_IRQHandler(void)
{
/* USER CODE BEGIN FDCAN1_IT1_IRQn 0 */
/* USER CODE END FDCAN1_IT1_IRQn 0 */
HAL_FDCAN_IRQHandler(&hfdcan1);
/* USER CODE BEGIN FDCAN1_IT1_IRQn 1 */
/* USER CODE END FDCAN1_IT1_IRQn 1 */
}
/**
* @brief This function handles FMC global interrupt.
*/
void FMC_IRQHandler(void)
{
/* USER CODE BEGIN FMC_IRQn 0 */
/* USER CODE END FMC_IRQn 0 */
HAL_SDRAM_IRQHandler(&hsdram1);
/* USER CODE BEGIN FMC_IRQn 1 */
/* USER CODE END FMC_IRQn 1 */
}
/**
* @brief This function handles FDCAN calibration unit interrupt.
*/
void FDCAN_CAL_IRQHandler(void)
{
/* USER CODE BEGIN FDCAN_CAL_IRQn 0 */
/* USER CODE END FDCAN_CAL_IRQn 0 */
HAL_FDCAN_IRQHandler(&hfdcan1);
/* USER CODE BEGIN FDCAN_CAL_IRQn 1 */
/* USER CODE END FDCAN_CAL_IRQn 1 */
}
/**
* @brief This function handles LTDC global interrupt.
*/
void LTDC_IRQHandler(void)
{
/* USER CODE BEGIN LTDC_IRQn 0 */
/* USER CODE END LTDC_IRQn 0 */
HAL_LTDC_IRQHandler(&hltdc);
/* USER CODE BEGIN LTDC_IRQn 1 */
/* USER CODE END LTDC_IRQn 1 */
}
/**
* @brief This function handles LTDC Error global Interrupt.
*/
void LTDC_ER_IRQHandler(void)
{
/* USER CODE BEGIN LTDC_ER_IRQn 0 */
/* USER CODE END LTDC_ER_IRQn 0 */
HAL_LTDC_IRQHandler(&hltdc);
/* USER CODE BEGIN LTDC_ER_IRQn 1 */
/* USER CODE END LTDC_ER_IRQn 1 */
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

156
Core/Src/syscalls.c Normal file
View File

@ -0,0 +1,156 @@
/**
******************************************************************************
* @file syscalls.c
* @author Auto-generated by STM32CubeIDE
* @brief STM32CubeIDE Minimal System calls file
*
* For more information about which c-functions
* need which of these lowlevel functions
* please consult the Newlib libc-manual
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Includes */
#include <sys/stat.h>
#include <stdlib.h>
#include <errno.h>
#include <stdio.h>
#include <signal.h>
#include <time.h>
#include <sys/time.h>
#include <sys/times.h>
/* Variables */
extern int __io_putchar(int ch) __attribute__((weak));
extern int __io_getchar(void) __attribute__((weak));
char *__env[1] = { 0 };
char **environ = __env;
/* Functions */
void initialise_monitor_handles()
{
}
int _getpid(void)
{
return 1;
}
int _kill(int pid, int sig)
{
errno = EINVAL;
return -1;
}
void _exit (int status)
{
_kill(status, -1);
while (1) {} /* Make sure we hang here */
}
__attribute__((weak)) int _read(int file, char *ptr, int len)
{
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
*ptr++ = __io_getchar();
}
return len;
}
__attribute__((weak)) int _write(int file, char *ptr, int len)
{
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
__io_putchar(*ptr++);
}
return len;
}
int _close(int file)
{
return -1;
}
int _fstat(int file, struct stat *st)
{
st->st_mode = S_IFCHR;
return 0;
}
int _isatty(int file)
{
return 1;
}
int _lseek(int file, int ptr, int dir)
{
return 0;
}
int _open(char *path, int flags, ...)
{
/* Pretend like we always fail */
return -1;
}
int _wait(int *status)
{
errno = ECHILD;
return -1;
}
int _unlink(char *name)
{
errno = ENOENT;
return -1;
}
int _times(struct tms *buf)
{
return -1;
}
int _stat(char *file, struct stat *st)
{
st->st_mode = S_IFCHR;
return 0;
}
int _link(char *old, char *new)
{
errno = EMLINK;
return -1;
}
int _fork(void)
{
errno = EAGAIN;
return -1;
}
int _execve(char *name, char **argv, char **env)
{
errno = ENOMEM;
return -1;
}

80
Core/Src/sysmem.c Normal file
View File

@ -0,0 +1,80 @@
/**
******************************************************************************
* @file sysmem.c
* @author Generated by STM32CubeIDE
* @brief STM32CubeIDE System Memory calls file
*
* For more information about which C functions
* need which of these lowlevel functions
* please consult the newlib libc manual
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Includes */
#include <errno.h>
#include <stdint.h>
/**
* Pointer to the current high watermark of the heap usage
*/
static uint8_t *__sbrk_heap_end = NULL;
/**
* @brief _sbrk() allocates memory to the newlib heap and is used by malloc
* and others from the C library
*
* @verbatim
* ############################################################################
* # .data # .bss # newlib heap # MSP stack #
* # # # # Reserved by _Min_Stack_Size #
* ############################################################################
* ^-- RAM start ^-- _end _estack, RAM end --^
* @endverbatim
*
* This implementation starts allocating at the '_end' linker symbol
* The '_Min_Stack_Size' linker symbol reserves a memory for the MSP stack
* The implementation considers '_estack' linker symbol to be RAM end
* NOTE: If the MSP stack, at any point during execution, grows larger than the
* reserved size, please increase the '_Min_Stack_Size'.
*
* @param incr Memory size
* @return Pointer to allocated memory
*/
void *_sbrk(ptrdiff_t incr)
{
extern uint8_t _end; /* Symbol defined in the linker script */
extern uint8_t _estack; /* Symbol defined in the linker script */
extern uint32_t _Min_Stack_Size; /* Symbol defined in the linker script */
const uint32_t stack_limit = (uint32_t)&_estack - (uint32_t)&_Min_Stack_Size;
const uint8_t *max_heap = (uint8_t *)stack_limit;
uint8_t *prev_heap_end;
/* Initialize heap end at first call */
if (NULL == __sbrk_heap_end)
{
__sbrk_heap_end = &_end;
}
/* Protect heap from growing into the reserved MSP stack */
if (__sbrk_heap_end + incr > max_heap)
{
errno = ENOMEM;
return (void *)-1;
}
prev_heap_end = __sbrk_heap_end;
__sbrk_heap_end += incr;
return (void *)prev_heap_end;
}

451
Core/Src/system_stm32h7xx.c Normal file
View File

@ -0,0 +1,451 @@
/**
******************************************************************************
* @file system_stm32h7xx.c
* @author MCD Application Team
* @brief CMSIS Cortex-Mx Device Peripheral Access Layer System Source File.
*
* 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_stm32h7xx.s" file.
*
* - SystemCoreClock variable: Contains the core clock, 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.
*
*
******************************************************************************
* @attention
*
* Copyright (c) 2017 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 stm32h7xx_system
* @{
*/
/** @addtogroup STM32H7xx_System_Private_Includes
* @{
*/
#include "stm32h7xx.h"
#include <math.h>
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (CSI_VALUE)
#define CSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* CSI_VALUE */
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)64000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @}
*/
/** @addtogroup STM32H7xx_System_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @addtogroup STM32H7xx_System_Private_Defines
* @{
*/
/************************* Miscellaneous Configuration ************************/
/*!< Uncomment the following line if you need to use initialized data in D2 domain SRAM (AHB SRAM) */
/* #define DATA_IN_D2_SRAM */
/* 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 BANK1 or AXI 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)
#if defined(DUAL_CORE) && defined(CORE_CM4)
/*!< Uncomment the following line if you need to relocate your vector Table
in D2 AXI SRAM else user remap will be done in FLASH BANK2. */
/* #define VECT_TAB_SRAM */
#if defined(VECT_TAB_SRAM)
#define VECT_TAB_BASE_ADDRESS D2_AXISRAM_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_BANK2_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 */
#else
/*!< Uncomment the following line if you need to relocate your vector Table
in D1 AXI SRAM else user remap will be done in FLASH BANK1. */
/* #define VECT_TAB_SRAM */
#if defined(VECT_TAB_SRAM)
#define VECT_TAB_BASE_ADDRESS D1_AXISRAM_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_BANK1_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 /* DUAL_CORE && CORE_CM4 */
#endif /* USER_VECT_TAB_ADDRESS */
/******************************************************************************/
/**
* @}
*/
/** @addtogroup STM32H7xx_System_Private_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32H7xx_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; then there
is no need to call the 2 first functions listed above, since SystemCoreClock
variable is updated automatically.
*/
uint32_t SystemCoreClock = 64000000;
uint32_t SystemD2Clock = 64000000;
const uint8_t D1CorePrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
/**
* @}
*/
/** @addtogroup STM32H7xx_System_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32H7xx_System_Private_Functions
* @{
*/
/**
* @brief Setup the microcontroller system
* Initialize the FPU setting and vector table location
* configuration.
* @param None
* @retval None
*/
void SystemInit (void)
{
#if defined (DATA_IN_D2_SRAM)
__IO uint32_t tmpreg;
#endif /* DATA_IN_D2_SRAM */
/* FPU settings ------------------------------------------------------------*/
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
SCB->CPACR |= ((3UL << (10*2))|(3UL << (11*2))); /* set CP10 and CP11 Full Access */
#endif
/* Reset the RCC clock configuration to the default reset state ------------*/
/* Increasing the CPU frequency */
if(FLASH_LATENCY_DEFAULT > (READ_BIT((FLASH->ACR), FLASH_ACR_LATENCY)))
{
/* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */
MODIFY_REG(FLASH->ACR, FLASH_ACR_LATENCY, (uint32_t)(FLASH_LATENCY_DEFAULT));
}
/* Set HSION bit */
RCC->CR |= RCC_CR_HSION;
/* Reset CFGR register */
RCC->CFGR = 0x00000000;
/* Reset HSEON, HSECSSON, CSION, HSI48ON, CSIKERON, PLL1ON, PLL2ON and PLL3ON bits */
RCC->CR &= 0xEAF6ED7FU;
/* Decreasing the number of wait states because of lower CPU frequency */
if(FLASH_LATENCY_DEFAULT < (READ_BIT((FLASH->ACR), FLASH_ACR_LATENCY)))
{
/* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */
MODIFY_REG(FLASH->ACR, FLASH_ACR_LATENCY, (uint32_t)(FLASH_LATENCY_DEFAULT));
}
#if defined(D3_SRAM_BASE)
/* Reset D1CFGR register */
RCC->D1CFGR = 0x00000000;
/* Reset D2CFGR register */
RCC->D2CFGR = 0x00000000;
/* Reset D3CFGR register */
RCC->D3CFGR = 0x00000000;
#else
/* Reset CDCFGR1 register */
RCC->CDCFGR1 = 0x00000000;
/* Reset CDCFGR2 register */
RCC->CDCFGR2 = 0x00000000;
/* Reset SRDCFGR register */
RCC->SRDCFGR = 0x00000000;
#endif
/* Reset PLLCKSELR register */
RCC->PLLCKSELR = 0x02020200;
/* Reset PLLCFGR register */
RCC->PLLCFGR = 0x01FF0000;
/* Reset PLL1DIVR register */
RCC->PLL1DIVR = 0x01010280;
/* Reset PLL1FRACR register */
RCC->PLL1FRACR = 0x00000000;
/* Reset PLL2DIVR register */
RCC->PLL2DIVR = 0x01010280;
/* Reset PLL2FRACR register */
RCC->PLL2FRACR = 0x00000000;
/* Reset PLL3DIVR register */
RCC->PLL3DIVR = 0x01010280;
/* Reset PLL3FRACR register */
RCC->PLL3FRACR = 0x00000000;
/* Reset HSEBYP bit */
RCC->CR &= 0xFFFBFFFFU;
/* Disable all interrupts */
RCC->CIER = 0x00000000;
#if (STM32H7_DEV_ID == 0x450UL)
/* dual core CM7 or single core line */
if((DBGMCU->IDCODE & 0xFFFF0000U) < 0x20000000U)
{
/* if stm32h7 revY*/
/* Change the switch matrix read issuing capability to 1 for the AXI SRAM target (Target 7) */
*((__IO uint32_t*)0x51008108) = 0x000000001U;
}
#endif
#if defined (DATA_IN_D2_SRAM)
/* in case of initialized data in D2 SRAM (AHB SRAM) , enable the D2 SRAM clock (AHB SRAM clock) */
#if defined(RCC_AHB2ENR_D2SRAM3EN)
RCC->AHB2ENR |= (RCC_AHB2ENR_D2SRAM1EN | RCC_AHB2ENR_D2SRAM2EN | RCC_AHB2ENR_D2SRAM3EN);
#elif defined(RCC_AHB2ENR_D2SRAM2EN)
RCC->AHB2ENR |= (RCC_AHB2ENR_D2SRAM1EN | RCC_AHB2ENR_D2SRAM2EN);
#else
RCC->AHB2ENR |= (RCC_AHB2ENR_AHBSRAM1EN | RCC_AHB2ENR_AHBSRAM2EN);
#endif /* RCC_AHB2ENR_D2SRAM3EN */
tmpreg = RCC->AHB2ENR;
(void) tmpreg;
#endif /* DATA_IN_D2_SRAM */
#if defined(DUAL_CORE) && defined(CORE_CM4)
/* Configure the Vector Table location add offset address for cortex-M4 ------------------*/
#if defined(USER_VECT_TAB_ADDRESS)
SCB->VTOR = VECT_TAB_BASE_ADDRESS | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal D2 AXI-RAM or in Internal FLASH */
#endif /* USER_VECT_TAB_ADDRESS */
#else
/*
* Disable the FMC bank1 (enabled after reset).
* This, prevents CPU speculation access on this bank which blocks the use of FMC during
* 24us. During this time the others FMC master (such as LTDC) cannot use it!
*/
FMC_Bank1_R->BTCR[0] = 0x000030D2;
/* 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 D1 AXI-RAM or in Internal FLASH */
#endif /* USER_VECT_TAB_ADDRESS */
#endif /*DUAL_CORE && CORE_CM4*/
}
/**
* @brief Update SystemCoreClock variable according to Clock Register Values.
* The SystemCoreClock variable contains the core clock , it can
* be used by the user application to setup the SysTick timer or configure
* other parameters.
*
* @note Each time the core clock 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 CSI, SystemCoreClock will contain the CSI_VALUE(*)
* - 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 CSI_VALUE(*),
* HSI_VALUE(**) or HSE_VALUE(***) multiplied/divided by the PLL factors.
*
* (*) CSI_VALUE is a constant defined in stm32h7xx_hal.h file (default value
* 4 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
* (**) HSI_VALUE is a constant defined in stm32h7xx_hal.h file (default value
* 64 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* (***)HSE_VALUE is a constant defined in stm32h7xx_hal.h file (default value
* 25 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 pllp, pllsource, pllm, pllfracen, hsivalue, tmp;
uint32_t common_system_clock;
float_t fracn1, pllvco;
/* Get SYSCLK source -------------------------------------------------------*/
switch (RCC->CFGR & RCC_CFGR_SWS)
{
case RCC_CFGR_SWS_HSI: /* HSI used as system clock source */
common_system_clock = (uint32_t) (HSI_VALUE >> ((RCC->CR & RCC_CR_HSIDIV)>> 3));
break;
case RCC_CFGR_SWS_CSI: /* CSI used as system clock source */
common_system_clock = CSI_VALUE;
break;
case RCC_CFGR_SWS_HSE: /* HSE used as system clock source */
common_system_clock = HSE_VALUE;
break;
case RCC_CFGR_SWS_PLL1: /* PLL1 used as system clock source */
/* PLL_VCO = (HSE_VALUE or HSI_VALUE or CSI_VALUE/ PLLM) * PLLN
SYSCLK = PLL_VCO / PLLR
*/
pllsource = (RCC->PLLCKSELR & RCC_PLLCKSELR_PLLSRC);
pllm = ((RCC->PLLCKSELR & RCC_PLLCKSELR_DIVM1)>> 4) ;
pllfracen = ((RCC->PLLCFGR & RCC_PLLCFGR_PLL1FRACEN)>>RCC_PLLCFGR_PLL1FRACEN_Pos);
fracn1 = (float_t)(uint32_t)(pllfracen* ((RCC->PLL1FRACR & RCC_PLL1FRACR_FRACN1)>> 3));
if (pllm != 0U)
{
switch (pllsource)
{
case RCC_PLLCKSELR_PLLSRC_HSI: /* HSI used as PLL clock source */
hsivalue = (HSI_VALUE >> ((RCC->CR & RCC_CR_HSIDIV)>> 3)) ;
pllvco = ( (float_t)hsivalue / (float_t)pllm) * ((float_t)(uint32_t)(RCC->PLL1DIVR & RCC_PLL1DIVR_N1) + (fracn1/(float_t)0x2000) +(float_t)1 );
break;
case RCC_PLLCKSELR_PLLSRC_CSI: /* CSI used as PLL clock source */
pllvco = ((float_t)CSI_VALUE / (float_t)pllm) * ((float_t)(uint32_t)(RCC->PLL1DIVR & RCC_PLL1DIVR_N1) + (fracn1/(float_t)0x2000) +(float_t)1 );
break;
case RCC_PLLCKSELR_PLLSRC_HSE: /* HSE used as PLL clock source */
pllvco = ((float_t)HSE_VALUE / (float_t)pllm) * ((float_t)(uint32_t)(RCC->PLL1DIVR & RCC_PLL1DIVR_N1) + (fracn1/(float_t)0x2000) +(float_t)1 );
break;
default:
hsivalue = (HSI_VALUE >> ((RCC->CR & RCC_CR_HSIDIV)>> 3)) ;
pllvco = ((float_t)hsivalue / (float_t)pllm) * ((float_t)(uint32_t)(RCC->PLL1DIVR & RCC_PLL1DIVR_N1) + (fracn1/(float_t)0x2000) +(float_t)1 );
break;
}
pllp = (((RCC->PLL1DIVR & RCC_PLL1DIVR_P1) >>9) + 1U ) ;
common_system_clock = (uint32_t)(float_t)(pllvco/(float_t)pllp);
}
else
{
common_system_clock = 0U;
}
break;
default:
common_system_clock = (uint32_t) (HSI_VALUE >> ((RCC->CR & RCC_CR_HSIDIV)>> 3));
break;
}
/* Compute SystemClock frequency --------------------------------------------------*/
#if defined (RCC_D1CFGR_D1CPRE)
tmp = D1CorePrescTable[(RCC->D1CFGR & RCC_D1CFGR_D1CPRE)>> RCC_D1CFGR_D1CPRE_Pos];
/* common_system_clock frequency : CM7 CPU frequency */
common_system_clock >>= tmp;
/* SystemD2Clock frequency : CM4 CPU, AXI and AHBs Clock frequency */
SystemD2Clock = (common_system_clock >> ((D1CorePrescTable[(RCC->D1CFGR & RCC_D1CFGR_HPRE)>> RCC_D1CFGR_HPRE_Pos]) & 0x1FU));
#else
tmp = D1CorePrescTable[(RCC->CDCFGR1 & RCC_CDCFGR1_CDCPRE)>> RCC_CDCFGR1_CDCPRE_Pos];
/* common_system_clock frequency : CM7 CPU frequency */
common_system_clock >>= tmp;
/* SystemD2Clock frequency : AXI and AHBs Clock frequency */
SystemD2Clock = (common_system_clock >> ((D1CorePrescTable[(RCC->CDCFGR1 & RCC_CDCFGR1_HPRE)>> RCC_CDCFGR1_HPRE_Pos]) & 0x1FU));
#endif
#if defined(DUAL_CORE) && defined(CORE_CM4)
SystemCoreClock = SystemD2Clock;
#else
SystemCoreClock = common_system_clock;
#endif /* DUAL_CORE && CORE_CM4 */
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/