discard previous trial, tried display with internal frame buffer

This commit is contained in:
2025-03-31 17:48:00 +02:00
parent c30b708f92
commit 7e4ce4a1cd
56 changed files with 6904 additions and 4686 deletions

View File

@ -1,205 +0,0 @@
/*
* 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

View File

@ -1,273 +0,0 @@
#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);
}

View File

@ -1,57 +0,0 @@
/*
* 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"
#include "charger_control.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;
}*/
switch (id) {
case CAN_ID_AMS_STATUS: {
int sdc_closed = data[0] >> 7;
if (sdc_closed == 0) {
charger_control_disable_remote();
}
break;
}
case CAN_ID_AMS_IN: {
int active = data[0] & 0x01;
if (active) {
charger_control_enable_remote();
}
}
}
}

View File

@ -1,69 +0,0 @@
/*
* 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);
}
}
}

View File

@ -1,168 +0,0 @@
/*
* 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);
}

View File

@ -6,27 +6,21 @@
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2022 STMicroelectronics.
* All rights reserved.</center></h2>
* Copyright (c) 2025 STMicroelectronics.
* All rights reserved.
*
* 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
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "app_touchgfx.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 */
@ -37,6 +31,7 @@
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
@ -64,7 +59,7 @@ PCD_HandleTypeDef hpcd_USB_OTG_HS;
SDRAM_HandleTypeDef hsdram1;
/* USER CODE BEGIN PV */
uint16_t framebuffer[160*120];
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
@ -81,13 +76,12 @@ static void MX_UART5_Init(void);
static void MX_LTDC_Init(void);
static void MX_CRC_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 */
/**
@ -131,41 +125,24 @@ int main(void)
MX_UART5_Init();
MX_LTDC_Init();
MX_CRC_Init();
MX_TouchGFX_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);
HAL_LTDC_SetAddress(&hltdc, (uint32_t)framebuffer, LTDC_LAYER_1);
uint8_t r = 0xff, g = 0x00, b = 0x00; // Solid red
uint16_t col = ((r>>3)<<11) | ((g>>2)<<5) | (b>>3); // Convert colors to RGB565
// Put colors into the framebuffer
for(int i = 0; i < 160*120; i++)
{
framebuffer[i] = col;
}
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
uint32_t lasttick = HAL_GetTick();
while (1)
{
/* USER CODE END WHILE */
MX_TouchGFX_Process();
/* 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 */
}
@ -415,12 +392,12 @@ static void MX_LTDC_Init(void)
hltdc.Init.PCPolarity = LTDC_PCPOLARITY_IPC;
hltdc.Init.HorizontalSync = 19;
hltdc.Init.VerticalSync = 2;
hltdc.Init.AccumulatedHBP = 159;
hltdc.Init.AccumulatedHBP = 69;
hltdc.Init.AccumulatedVBP = 22;
hltdc.Init.AccumulatedActiveW = 1183;
hltdc.Init.AccumulatedActiveH = 622;
hltdc.Init.TotalWidth = 1343;
hltdc.Init.TotalHeigh = 634;
hltdc.Init.AccumulatedActiveW = 549;
hltdc.Init.AccumulatedActiveH = 294;
hltdc.Init.TotalWidth = 599;
hltdc.Init.TotalHeigh = 306;
hltdc.Init.Backcolor.Blue = 0;
hltdc.Init.Backcolor.Green = 0;
hltdc.Init.Backcolor.Red = 0;
@ -429,10 +406,10 @@ static void MX_LTDC_Init(void)
Error_Handler();
}
pLayerCfg.WindowX0 = 0;
pLayerCfg.WindowX1 = 1024;
pLayerCfg.WindowX1 = 480;
pLayerCfg.WindowY0 = 0;
pLayerCfg.WindowY1 = 600;
pLayerCfg.PixelFormat = LTDC_PIXEL_FORMAT_RGB888;
pLayerCfg.WindowY1 = 272;
pLayerCfg.PixelFormat = LTDC_PIXEL_FORMAT_RGB565;
pLayerCfg.Alpha = 1;
pLayerCfg.Alpha0 = 0;
pLayerCfg.BlendingFactor1 = LTDC_BLENDING_FACTOR1_CA;
@ -448,8 +425,7 @@ static void MX_LTDC_Init(void)
Error_Handler();
}
/* USER CODE BEGIN LTDC_Init 2 */
__HAL_LTDC_ENABLE(&hltdc);
__HAL_LTDC_LAYER_ENABLE(&hltdc,1);
/* USER CODE END LTDC_Init 2 */
}
@ -660,32 +636,7 @@ static void MX_FMC_Init(void)
}
/* 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 */
}
@ -768,49 +719,6 @@ static void MX_GPIO_Init(void)
/* 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 */
/**

View File

@ -1,70 +0,0 @@
/*
* 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

@ -7,13 +7,12 @@
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2022 STMicroelectronics.
* All rights reserved.</center></h2>
* Copyright (c) 2025 STMicroelectronics.
* All rights reserved.
*
* 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
* 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.
*
******************************************************************************
*/
@ -332,7 +331,6 @@ void HAL_LTDC_MspInit(LTDC_HandleTypeDef* hltdc)
/**LTDC GPIO Configuration
PF10 ------> LTDC_DE
PC0 ------> LTDC_R5
PA1 ------> LTDC_R2
PA3 ------> LTDC_B5
PA4 ------> LTDC_VSYNC
PA5 ------> LTDC_R4
@ -351,7 +349,6 @@ void HAL_LTDC_MspInit(LTDC_HandleTypeDef* hltdc)
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;
@ -367,8 +364,8 @@ void HAL_LTDC_MspInit(LTDC_HandleTypeDef* hltdc)
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.Pin = 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;
@ -424,18 +421,9 @@ void HAL_LTDC_MspInit(LTDC_HandleTypeDef* hltdc)
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 */
@ -463,7 +451,6 @@ void HAL_LTDC_MspDeInit(LTDC_HandleTypeDef* hltdc)
/**LTDC GPIO Configuration
PF10 ------> LTDC_DE
PC0 ------> LTDC_R5
PA1 ------> LTDC_R2
PA3 ------> LTDC_B5
PA4 ------> LTDC_VSYNC
PA5 ------> LTDC_R4
@ -482,26 +469,24 @@ void HAL_LTDC_MspDeInit(LTDC_HandleTypeDef* hltdc)
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(GPIOA, 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);
HAL_GPIO_DeInit(GPIOD, GPIO_PIN_2);
/* 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 */

View File

@ -6,13 +6,12 @@
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2022 STMicroelectronics.
* All rights reserved.</center></h2>
* Copyright (c) 2025 STMicroelectronics.
* All rights reserved.
*
* 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
* 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.
*
******************************************************************************
*/
@ -75,7 +74,7 @@ void NMI_Handler(void)
/* USER CODE END NonMaskableInt_IRQn 0 */
/* USER CODE BEGIN NonMaskableInt_IRQn 1 */
while (1)
while (1)
{
}
/* USER CODE END NonMaskableInt_IRQn 1 */
@ -267,24 +266,10 @@ void LTDC_IRQHandler(void)
/* USER CODE END LTDC_IRQn 0 */
HAL_LTDC_IRQHandler(&hltdc);
/* USER CODE BEGIN LTDC_IRQn 1 */
HAL_LTDC_ProgramLineEvent(&hltdc,0);
/* 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 */

View File

@ -1,8 +1,8 @@
/**
******************************************************************************
* @file syscalls.c
* @author Auto-generated by STM32CubeIDE
* @brief STM32CubeIDE Minimal System calls file
* @author Auto-generated by STM32CubeMX
* @brief Minimal System calls file
*
* For more information about which c-functions
* need which of these lowlevel functions
@ -10,13 +10,12 @@
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
* Copyright (c) 2020-2024 STMicroelectronics.
* All rights reserved.
*
* 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
* 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.
*
******************************************************************************
*/
@ -48,109 +47,130 @@ void initialise_monitor_handles()
int _getpid(void)
{
return 1;
return 1;
}
int _kill(int pid, int sig)
{
errno = EINVAL;
return -1;
(void)pid;
(void)sig;
errno = EINVAL;
return -1;
}
void _exit (int status)
{
_kill(status, -1);
while (1) {} /* Make sure we hang here */
_kill(status, -1);
while (1) {} /* Make sure we hang here */
}
__attribute__((weak)) int _read(int file, char *ptr, int len)
{
int DataIdx;
(void)file;
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
*ptr++ = __io_getchar();
}
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
*ptr++ = __io_getchar();
}
return len;
return len;
}
__attribute__((weak)) int _write(int file, char *ptr, int len)
{
int DataIdx;
(void)file;
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
__io_putchar(*ptr++);
}
return len;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
__io_putchar(*ptr++);
}
return len;
}
int _close(int file)
{
return -1;
(void)file;
return -1;
}
int _fstat(int file, struct stat *st)
{
st->st_mode = S_IFCHR;
return 0;
(void)file;
st->st_mode = S_IFCHR;
return 0;
}
int _isatty(int file)
{
return 1;
(void)file;
return 1;
}
int _lseek(int file, int ptr, int dir)
{
return 0;
(void)file;
(void)ptr;
(void)dir;
return 0;
}
int _open(char *path, int flags, ...)
{
/* Pretend like we always fail */
return -1;
(void)path;
(void)flags;
/* Pretend like we always fail */
return -1;
}
int _wait(int *status)
{
errno = ECHILD;
return -1;
(void)status;
errno = ECHILD;
return -1;
}
int _unlink(char *name)
{
errno = ENOENT;
return -1;
(void)name;
errno = ENOENT;
return -1;
}
int _times(struct tms *buf)
{
return -1;
(void)buf;
return -1;
}
int _stat(char *file, struct stat *st)
{
st->st_mode = S_IFCHR;
return 0;
(void)file;
st->st_mode = S_IFCHR;
return 0;
}
int _link(char *old, char *new)
{
errno = EMLINK;
return -1;
(void)old;
(void)new;
errno = EMLINK;
return -1;
}
int _fork(void)
{
errno = EAGAIN;
return -1;
errno = EAGAIN;
return -1;
}
int _execve(char *name, char **argv, char **env)
{
errno = ENOMEM;
return -1;
(void)name;
(void)argv;
(void)env;
errno = ENOMEM;
return -1;
}

View File

@ -1,8 +1,8 @@
/**
******************************************************************************
* @file sysmem.c
* @author Generated by STM32CubeIDE
* @brief STM32CubeIDE System Memory calls file
* @author Generated by STM32CubeMX
* @brief System Memory calls file
*
* For more information about which C functions
* need which of these lowlevel functions
@ -10,13 +10,12 @@
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
* Copyright (c) 2024 STMicroelectronics.
* All rights reserved.
*
* 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
* 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.
*
******************************************************************************
*/

File diff suppressed because it is too large Load Diff