Compare commits
39 Commits
0.0.1
...
refactor/V
| Author | SHA1 | Date | |
|---|---|---|---|
| 8d02489b16 | |||
| 452246951b | |||
| eb5733da97 | |||
| 766d5e9ca8 | |||
| 9c489c1a25 | |||
| d0544576a3 | |||
| 66e04c6e06 | |||
| 9b49028c20 | |||
| 13c6a71af6 | |||
| c7d6ba78d5 | |||
| 804c4c8c69 | |||
| a91fdc9311 | |||
| fd3757b6a1 | |||
| 2b12ea9602 | |||
| e892a21f97 | |||
| 1a1e4bbee4 | |||
| c3322ed571 | |||
| bd8779b5aa | |||
| 04c5eb047e | |||
| 1d7ad7dc31 | |||
| a9d11ea891 | |||
| 92c8624fe4 | |||
| a58079c3c0 | |||
| 25fb6d0a1e | |||
| e995e1bd01 | |||
| 3869b31b03 | |||
| 467d7c4de9 | |||
| 2d903dcf11 | |||
| 77a774e7dd | |||
| 4431f12c8f | |||
| e8518fc9d4 | |||
| 6218223d41 | |||
| 471ec34ba0 | |||
| e7fe3162f2 | |||
| 72d8e9d2d6 | |||
| fe432acef3 | |||
| 6782048b51 | |||
| c8d0fd1d87 | |||
| 623ec1576a |
@@ -8,12 +8,13 @@ jobs:
|
||||
steps:
|
||||
|
||||
- name: Install dependencies
|
||||
run: apt-get update && apt-get install -y gcc-arm-none-eabi binutils-arm-none-eabi ninja-build cmake protobuf-compiler python3 python3-grpcio python3-protobuf python3-pkg-resources
|
||||
run: apt-get update && apt-get install -y gcc-arm-none-eabi binutils-arm-none-eabi ninja-build cmake protobuf-compiler python3 python3-grpcio python3-protobuf python3-pkg-resources python3-requests
|
||||
# run: pip install setuptools
|
||||
- name: Check out repository code
|
||||
uses: actions/checkout@v4
|
||||
with:
|
||||
submodules: true
|
||||
fetch-depth: 0
|
||||
|
||||
- name: Create Build directory
|
||||
run: mkdir build
|
||||
@@ -31,3 +32,8 @@ jobs:
|
||||
path: |
|
||||
build/*.hex
|
||||
build/*.bin
|
||||
|
||||
- name: Upload Firmware
|
||||
env:
|
||||
SERVER_KEY: ${{ secrets.SERVER_KEY }}
|
||||
run: python3 tools/upload_firmware.py $SERVER_KEY
|
||||
27
.vscode/launch.json
vendored
27
.vscode/launch.json
vendored
@@ -44,6 +44,33 @@
|
||||
//"armToolchainPath": "c:\\ST\\STM32CubeIDE_1.7.0\\STM32CubeIDE\\plugins\\com.st.stm32cube.ide.mcu.externaltools.gnu-tools-for-stm32.9-2020-q2-update.win32_2.0.0.202105311346\\tools\\bin",
|
||||
//"stm32cubeprogrammer": "c:\\Program Files\\STMicroelectronics\\STM32Cube\\STM32CubeProgrammer\\bin",
|
||||
|
||||
/* If you use external loader, add additional arguments */
|
||||
//"serverArgs": ["--extload", "path/to/ext/loader.stldr"],
|
||||
},
|
||||
{
|
||||
"name": "Attach Microcontroller - ST-Link",
|
||||
"cwd": "${workspaceFolder}",
|
||||
"type": "cortex-debug",
|
||||
"executable": "${command:cmake.launchTargetPath}", //or fixed file path: build/stm32h735g-dk-led.elf
|
||||
"request": "attach", //Use "attach" to connect to target w/o elf download
|
||||
"servertype": "stlink",
|
||||
"device": "STM32H723VGT", //MCU used, ex. "STM32H735IG"
|
||||
"interface": "swd",
|
||||
"serialNumber": "002800223232511939353236", //Set ST-Link ID if you use multiple at the same time
|
||||
"runToEntryPoint": "main",
|
||||
"svdFile": "STM32H723.svd", //Path to SVD file to see registers
|
||||
"v1": false,
|
||||
"showDevDebugOutput": "both",
|
||||
"liveWatch": {
|
||||
"enabled": true,
|
||||
"samplesPerSecond": 4
|
||||
}
|
||||
/* Will get automatically detected if STM32CubeIDE is installed to default directory
|
||||
or it can be manually provided if necessary.. */
|
||||
//"serverpath": "c:\\ST\\STM32CubeIDE_1.7.0\\STM32CubeIDE\\plugins\\com.st.stm32cube.ide.mcu.externaltools.stlink-gdb-server.win32_2.0.100.202109301221\\tools\\bin\\ST-LINK_gdbserver.exe",
|
||||
//"armToolchainPath": "c:\\ST\\STM32CubeIDE_1.7.0\\STM32CubeIDE\\plugins\\com.st.stm32cube.ide.mcu.externaltools.gnu-tools-for-stm32.9-2020-q2-update.win32_2.0.0.202105311346\\tools\\bin",
|
||||
//"stm32cubeprogrammer": "c:\\Program Files\\STMicroelectronics\\STM32Cube\\STM32CubeProgrammer\\bin",
|
||||
|
||||
/* If you use external loader, add additional arguments */
|
||||
//"serverArgs": ["--extload", "path/to/ext/loader.stldr"],
|
||||
}
|
||||
|
||||
5
.vscode/settings.json
vendored
Normal file
5
.vscode/settings.json
vendored
Normal file
@@ -0,0 +1,5 @@
|
||||
{
|
||||
"files.associations": {
|
||||
"bsp_adc.h": "c"
|
||||
}
|
||||
}
|
||||
92
Application/BSP/BSP_ADC.c
Normal file
92
Application/BSP/BSP_ADC.c
Normal file
@@ -0,0 +1,92 @@
|
||||
#include "main.h"
|
||||
#include "BSP_ADC.h"
|
||||
#include "adc.h"
|
||||
#include "stdbool.h"
|
||||
|
||||
|
||||
#define TOTAL_ADC_CHANNELS 4
|
||||
#define ADC_HISTORY_SIZE 4
|
||||
#define ADC_BUFFER_SIZE (TOTAL_ADC_CHANNELS * ADC_HISTORY_SIZE)
|
||||
#define ADC_CONVERTED_DATA_BUFFER_SIZE ((uint32_t) ADC_BUFFER_SIZE) /* Size of array aADCxConvertedData[] */
|
||||
ALIGN_32BYTES (static uint16_t aADCxConvertedData[ADC_CONVERTED_DATA_BUFFER_SIZE]);
|
||||
|
||||
#define ADC_CHANNEL_DIMMER 1
|
||||
#define ADC_CHANNEL_BUS 3
|
||||
|
||||
static bool adcIsInitialized = false;
|
||||
|
||||
//start the ADC conversion
|
||||
void BSP_ADC_Start()
|
||||
{
|
||||
|
||||
|
||||
if (HAL_ADCEx_Calibration_Start(&hadc1, ADC_CALIB_OFFSET_LINEARITY, ADC_SINGLE_ENDED) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
|
||||
if (HAL_ADC_Start_DMA(&hadc1,
|
||||
(uint32_t *)aADCxConvertedData,
|
||||
ADC_CONVERTED_DATA_BUFFER_SIZE
|
||||
) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
adcIsInitialized = true;
|
||||
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Conversion complete callback in non-blocking mode
|
||||
* @param hadc: ADC handle
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef* hadc)
|
||||
{
|
||||
/* Invalidate Data Cache to get the updated content of the SRAM on the first half of the ADC converted data buffer: 32 bytes */
|
||||
//SCB_InvalidateDCache_by_Addr((uint32_t *) &aADCxConvertedData[0], ADC_CONVERTED_DATA_BUFFER_SIZE);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Conversion DMA half-transfer callback in non-blocking mode
|
||||
* @param hadc: ADC handle
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc)
|
||||
{
|
||||
/* Invalidate Data Cache to get the updated content of the SRAM on the second half of the ADC converted data buffer: 32 bytes */
|
||||
//SCB_InvalidateDCache_by_Addr((uint32_t *) &aADCxConvertedData[ADC_CONVERTED_DATA_BUFFER_SIZE/2], ADC_CONVERTED_DATA_BUFFER_SIZE);
|
||||
}
|
||||
|
||||
|
||||
|
||||
float BSP_ADC_ReadValue( uint32_t channel, float factor) {
|
||||
if (!adcIsInitialized) {
|
||||
return 0;
|
||||
}
|
||||
// average the last 4 values of the dimmer ADC
|
||||
uint32_t sum = 0;
|
||||
for (int i = 0; i < ADC_HISTORY_SIZE; i++) {
|
||||
sum += aADCxConvertedData[channel + i * TOTAL_ADC_CHANNELS];
|
||||
}
|
||||
|
||||
|
||||
//convert raw ADC value to voltage
|
||||
float voltage = (float)sum / (float)ADC_HISTORY_SIZE / factor; // gemessan an sample pcb
|
||||
|
||||
return voltage;
|
||||
|
||||
}
|
||||
|
||||
float BSP_ADC_ReadDimmerValue() {
|
||||
return BSP_ADC_ReadValue(ADC_CHANNEL_DIMMER, 4319.619048);
|
||||
|
||||
}
|
||||
|
||||
|
||||
float BSP_ADC_ReadBusValue() {
|
||||
return BSP_ADC_ReadValue(ADC_CHANNEL_BUS, 4046.87186);
|
||||
}
|
||||
10
Application/BSP/BSP_ADC.h
Normal file
10
Application/BSP/BSP_ADC.h
Normal file
@@ -0,0 +1,10 @@
|
||||
|
||||
|
||||
void BSP_ADC_Start();
|
||||
|
||||
|
||||
float BSP_ADC_ReadDimmerValue();
|
||||
|
||||
|
||||
|
||||
float BSP_ADC_ReadBusValue();
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "ee24.h"
|
||||
#include "i2c.h"
|
||||
#include "cmsis_os2.h"
|
||||
#include "gpio.h"
|
||||
#include "BSP_GPIO.h"
|
||||
|
||||
#define BSP_EE24_I2C &hi2c2
|
||||
#define BSP_EE24_ADDRESS EE24_ADDRESS_DEFAULT
|
||||
@@ -71,7 +71,7 @@ bool BSP_EE24_Init(void) {
|
||||
ee24_lock = osMutexNew(NULL);
|
||||
|
||||
// wc control high disables write
|
||||
HAL_GPIO_WritePin(EEPROM_WC_GPIO_Port, EEPROM_WC_Pin, GPIO_PIN_SET);
|
||||
BSP_GPIO_EE24WriteProtectOn();
|
||||
|
||||
// Read the Partition Table header from the EEPROM
|
||||
BSP_EE24_TableHeader header = {0};
|
||||
@@ -121,9 +121,9 @@ bool BSP_EE24_Read(uint32_t Address, uint8_t *Data, size_t Len) {
|
||||
*/
|
||||
bool BSP_EE24_Write(uint32_t Address, uint8_t *Data, size_t Len) {
|
||||
osMutexAcquire(ee24_lock,BSP_EE24_MUTEXT_TIMEOUT);
|
||||
HAL_GPIO_WritePin(EEPROM_WC_GPIO_Port, EEPROM_WC_Pin, GPIO_PIN_RESET); // low enables write;
|
||||
BSP_GPIO_EE24WriteProtectOff();
|
||||
bool status = EE24_Write(&hee24,Address,Data,Len,BSP_EE24_TIMEOUT);
|
||||
HAL_GPIO_WritePin(EEPROM_WC_GPIO_Port, EEPROM_WC_Pin, GPIO_PIN_SET); // high disables write;
|
||||
BSP_GPIO_EE24WriteProtectOn();
|
||||
osMutexRelease(ee24_lock);
|
||||
return status;
|
||||
}
|
||||
|
||||
86
Application/BSP/BSP_GPIO.c
Normal file
86
Application/BSP/BSP_GPIO.c
Normal file
@@ -0,0 +1,86 @@
|
||||
#include "BSP_GPIO.h"
|
||||
#include "main.h"
|
||||
#include "gpio.h"
|
||||
|
||||
|
||||
/**
|
||||
* @brief Checks if the K15 pin is set.
|
||||
* @return true if the K15 pin is set, false otherwise.
|
||||
*/
|
||||
bool BSP_GPIO_K15isSet() {
|
||||
return HAL_GPIO_ReadPin(K15_Detect_GPIO_Port, K15_Detect_Pin) == GPIO_PIN_SET;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Turns on the CLS power.
|
||||
*/
|
||||
void BSP_GPIO_ClsOn() {
|
||||
HAL_GPIO_WritePin(CLS_POWER_GPIO_Port, CLS_POWER_Pin, GPIO_PIN_SET);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Turns off the CLS power.
|
||||
*/
|
||||
void BSP_GPIO_ClsOff() {
|
||||
HAL_GPIO_WritePin(CLS_POWER_GPIO_Port, CLS_POWER_Pin, GPIO_PIN_RESET);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Turns on the peripheral power.
|
||||
*/
|
||||
void BSP_GPIO_PeriperalsOn() {
|
||||
HAL_GPIO_WritePin(Periph_Power_GPIO_Port,Periph_Power_Pin,GPIO_PIN_RESET);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Turns off the peripheral power.
|
||||
*/
|
||||
void BSP_GPIO_PeriperalsOff() {
|
||||
HAL_GPIO_WritePin(Periph_Power_GPIO_Port,Periph_Power_Pin,GPIO_PIN_SET);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Turns on the radio.
|
||||
*
|
||||
* This function sets the GPIO pin to high, turning on the radio.
|
||||
*/
|
||||
void BSP_GPIO_RadioOn() {
|
||||
HAL_GPIO_WritePin(K15_OUT_GPIO_Port, K15_OUT_Pin, GPIO_PIN_SET);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Turns off the radio.
|
||||
*
|
||||
* This function sets the GPIO pin to low, turning off the radio.
|
||||
*/
|
||||
void BSP_GPIO_RadioOff() {
|
||||
HAL_GPIO_WritePin(K15_OUT_GPIO_Port, K15_OUT_Pin, GPIO_PIN_RESET);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Turns on the write protection for the EEPROM.
|
||||
*
|
||||
* This function sets the write protect pin of the EEPROM to high,
|
||||
* enabling write protection for the EEPROM.
|
||||
*/
|
||||
void BSP_GPIO_EE24WriteProtectOn() {
|
||||
HAL_GPIO_WritePin(EEPROM_WC_GPIO_Port, EEPROM_WC_Pin, GPIO_PIN_SET);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Turns off the write protection for the EEPROM.
|
||||
*
|
||||
* This function sets the write protect pin of the EEPROM to low,
|
||||
* disabling write protection for the EEPROM.
|
||||
*/
|
||||
void BSP_GPIO_EE24WriteProtectOff() {
|
||||
HAL_GPIO_WritePin(EEPROM_WC_GPIO_Port, EEPROM_WC_Pin, GPIO_PIN_RESET);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Checks if the headlight is on.
|
||||
* @return true if the headlight is on, false otherwise.
|
||||
*/
|
||||
bool BSP_GPIO_HeadLightIsSet() {
|
||||
return HAL_GPIO_ReadPin(Headlight_Detect_GPIO_Port, Headlight_Detect_Pin) == GPIO_PIN_SET;
|
||||
}
|
||||
@@ -1,3 +1,32 @@
|
||||
// GPIOs access functions
|
||||
// External Interrupts
|
||||
// Shordhand functions to read improtant pins
|
||||
|
||||
|
||||
#include "stdint.h"
|
||||
#include "stdbool.h"
|
||||
|
||||
// Check K15 input
|
||||
bool BSP_GPIO_K15isSet();
|
||||
|
||||
// Set On / Off for CLS_Relay
|
||||
void BSP_GPIO_ClsOn();
|
||||
void BSP_GPIO_ClsOff();
|
||||
|
||||
|
||||
// Set On / Off for peripheral
|
||||
void BSP_GPIO_PeriperalsOn();
|
||||
void BSP_GPIO_PeriperalsOff();
|
||||
|
||||
// Set On / Off for 12V Radio Power
|
||||
void BSP_GPIO_RadioOn();
|
||||
void BSP_GPIO_RadioOff();
|
||||
|
||||
|
||||
void BSP_GPIO_EE24WriteProtectOn();
|
||||
void BSP_GPIO_EE24WriteProtectOff();
|
||||
|
||||
|
||||
// Check if the headlight is on
|
||||
bool BSP_GPIO_HeadLightIsSet();
|
||||
|
||||
|
||||
@@ -3,17 +3,159 @@
|
||||
#include "BSP_POWER.h"
|
||||
#include "lptim.h"
|
||||
#include "ulog.h"
|
||||
|
||||
#include "rtc.h"
|
||||
#include "fdcan.h"
|
||||
#include "i2c.h"
|
||||
#include "sdmmc.h"
|
||||
#include "cmsis_os2.h"
|
||||
#include "BSP_GPIO.h"
|
||||
#include "BSP_ADC.h"
|
||||
#include "BSP_SDLogger.h"
|
||||
#define LPTIM_CLK 500 // Hz
|
||||
#define SLEEP_TIME 10 // seconds to wait
|
||||
#define SLEEP_TICK_TIME 1 // seconds to wait
|
||||
#define STAY_AWAKE_TIME 60 // seconds to stay awake without K15
|
||||
|
||||
|
||||
bool CanDataTask_CarCanActive();
|
||||
|
||||
|
||||
// Start the sleep counter check
|
||||
void BSP_POWER_Init() {
|
||||
uint16_t counter = LPTIM_CLK * SLEEP_TIME;
|
||||
uint16_t counter = LPTIM_CLK * SLEEP_TICK_TIME;
|
||||
HAL_LPTIM_Counter_Start_IT(&hlptim4, counter);
|
||||
}
|
||||
|
||||
|
||||
void HAL_LPTIM_AutoReloadMatchCallback(LPTIM_HandleTypeDef *hlptim) {
|
||||
// This should be called as soon as possible after wakeup
|
||||
void BSP_POWER_WakeUp() {
|
||||
|
||||
/* Check if the system has resumed from StandBy mode */
|
||||
if(__HAL_PWR_GET_FLAG(PWR_FLAG_SB) != RESET)
|
||||
{
|
||||
/* Clear Standby flag */
|
||||
__HAL_PWR_CLEAR_FLAG(PWR_FLAG_SB);
|
||||
}
|
||||
|
||||
|
||||
if (__HAL_RTC_WAKEUPTIMER_GET_FLAG(&hrtc, RTC_FLAG_WUTF) != 0U)
|
||||
{
|
||||
__HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(&hrtc, RTC_FLAG_WUTF);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
/* The Following Wakeup sequence is highly recommended prior to each Standby mode entry
|
||||
mainly when using more than one wakeup source this is to not miss any wakeup event.
|
||||
- Disable all used wakeup sources,
|
||||
- Clear all related wakeup flags,
|
||||
- Re-enable all used wakeup sources,
|
||||
- Enter the Standby mode.
|
||||
*/
|
||||
void BSP_POWER_EnterStandby() {
|
||||
|
||||
// if there is still communication on the CAN bus, we should not go to standby
|
||||
// intstead we should reset the system, because the CAN bus would wake us up again
|
||||
if (CanDataTask_CarCanActive()) {
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
// stop the sytem interrupts
|
||||
__disable_irq();
|
||||
|
||||
// We need to disable all Periperals to minimize parasitic currents
|
||||
HAL_I2C_DeInit(&hi2c1);
|
||||
HAL_I2C_MspDeInit(&hi2c1);
|
||||
HAL_I2C_DeInit(&hi2c2);
|
||||
HAL_I2C_MspDeInit(&hi2c2);
|
||||
HAL_FDCAN_DeInit(&hfdcan1);
|
||||
HAL_FDCAN_MspDeInit(&hfdcan1);
|
||||
HAL_FDCAN_DeInit(&hfdcan2);
|
||||
HAL_FDCAN_MspDeInit(&hfdcan2);
|
||||
HAL_SD_MspDeInit(&hsd1);
|
||||
|
||||
// These Pins interfere with the WAKEUP PINS
|
||||
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_1| GPIO_PIN_3);
|
||||
|
||||
// cut the power for the Slaves and unused peripherals
|
||||
BSP_GPIO_ClsOff();
|
||||
BSP_GPIO_PeriperalsOff();
|
||||
BSP_GPIO_RadioOff();
|
||||
|
||||
|
||||
|
||||
// Here now the showdown
|
||||
PWREx_WakeupPinTypeDef sPinParams;
|
||||
|
||||
/* Disable used wakeup source: PWR_WAKEUP_PIN1 */
|
||||
HAL_PWR_DisableWakeUpPin(PWR_WAKEUP_PIN1);
|
||||
HAL_PWR_DisableWakeUpPin(PWR_WAKEUP_PIN2);
|
||||
HAL_RTCEx_DeactivateWakeUpTimer(&hrtc);
|
||||
|
||||
HAL_PWREx_ClearPendingEvent();
|
||||
/* Clear all related wakeup flags */
|
||||
HAL_PWREx_ClearWakeupFlag(PWR_WAKEUP_FLAG_ALL);
|
||||
HAL_PWREx_ClearWakeupFlag(PWR_WAKEUP_PIN1);
|
||||
HAL_PWREx_ClearWakeupFlag(PWR_WAKEUP_PIN2);
|
||||
|
||||
/* Clear all related wakeup flags */
|
||||
__HAL_PWR_CLEAR_FLAG(PWR_FLAG_WU);
|
||||
|
||||
|
||||
//HAL_RTCEx_SetWakeUpTimer_IT(&hrtc, 0xFFFF, RTC_WAKEUPCLOCK_RTCCLK_DIV16);
|
||||
HAL_PWREx_ClearWakeupFlag(PWR_WAKEUP_PIN1);
|
||||
|
||||
sPinParams.WakeUpPin = PWR_WAKEUP_PIN1;
|
||||
sPinParams.PinPolarity = PWR_PIN_POLARITY_HIGH;
|
||||
sPinParams.PinPull = PWR_PIN_PULL_DOWN;
|
||||
HAL_PWREx_EnableWakeUpPin(&sPinParams);
|
||||
|
||||
sPinParams.WakeUpPin = PWR_WAKEUP_PIN2;
|
||||
sPinParams.PinPolarity = PWR_PIN_POLARITY_HIGH;
|
||||
sPinParams.PinPull = PWR_PIN_PULL_DOWN;
|
||||
HAL_PWREx_EnableWakeUpPin(&sPinParams);
|
||||
|
||||
|
||||
/* Enter the Standby mode */
|
||||
HAL_PWR_EnterSTANDBYMode();
|
||||
|
||||
while (1)
|
||||
{
|
||||
// if we are here, something went wrong
|
||||
NVIC_SystemReset();
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
uint32_t sec_without_k15 = 0;
|
||||
|
||||
void HAL_LPTIM_AutoReloadMatchCallback(LPTIM_HandleTypeDef *hlptim) {
|
||||
|
||||
if(hlptim == &hlptim4) {
|
||||
// 1s timer check if K15 is set
|
||||
if (!BSP_GPIO_K15isSet()) {
|
||||
sec_without_k15++;
|
||||
} else {
|
||||
sec_without_k15 = 0;
|
||||
}
|
||||
|
||||
if (sec_without_k15 > STAY_AWAKE_TIME) {
|
||||
BSP_POWER_EnterStandby();
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
void BSP_POWER_FullPowerMode() {
|
||||
|
||||
BSP_GPIO_ClsOn();
|
||||
BSP_GPIO_PeriperalsOn();
|
||||
BSP_GPIO_RadioOn();
|
||||
BSP_ADC_Start();
|
||||
osDelay(10);
|
||||
StartPowerTasks();
|
||||
|
||||
}
|
||||
|
||||
@@ -7,3 +7,10 @@
|
||||
void BSP_POWER_Init();
|
||||
|
||||
|
||||
void BSP_POWER_WakeUp();
|
||||
|
||||
|
||||
void BSP_POWER_EnterStandby();
|
||||
|
||||
|
||||
void BSP_POWER_FullPowerMode();
|
||||
110
Application/BSP/BSP_SDLogger.c
Normal file
110
Application/BSP/BSP_SDLogger.c
Normal file
@@ -0,0 +1,110 @@
|
||||
#include "BSP_SDLogger.h"
|
||||
#include "fatfs.h"
|
||||
#include "ulog.h"
|
||||
#include "stdio.h"
|
||||
#include "string.h"
|
||||
|
||||
uint8_t block_buffer[512] = {0};
|
||||
size_t block_buffer_index = 0;
|
||||
char file_name[20];
|
||||
|
||||
char ulog_buffer[ULOG_MAX_MESSAGE_LENGTH] = {0};
|
||||
|
||||
void BSP_SDLogger_ULOG(ulog_level_t level, char *msg) {
|
||||
uint32_t send_length = snprintf(ulog_buffer, ULOG_MAX_MESSAGE_LENGTH, "[%s] %s\n", ulog_level_name(level), msg);
|
||||
BSP_SDLogger_Write(ulog_buffer, send_length);
|
||||
}
|
||||
|
||||
#include "cmsis_os2.h"
|
||||
|
||||
// Define the mutex
|
||||
osMutexId_t logger_mutex;
|
||||
|
||||
// init the logger buffer and the file
|
||||
// filename is generated based on the log number
|
||||
void BSP_SDLogger_Init(int log_number) {
|
||||
|
||||
// create the file name
|
||||
sprintf(file_name, "log_%d.txt", log_number);
|
||||
|
||||
// open the file
|
||||
FIL file;
|
||||
FRESULT res = f_open(&file, file_name, FA_CREATE_ALWAYS | FA_WRITE);
|
||||
if (res != FR_OK) {
|
||||
ULOG_ERROR("Failed to open file %s", file_name);
|
||||
}
|
||||
|
||||
//ULOG_SUBSCRIBE(BSP_SDLogger_ULOG, ULOG_DEBUG_LEVEL);
|
||||
|
||||
// close the file
|
||||
f_close(&file);
|
||||
|
||||
// Create the mutex
|
||||
logger_mutex = osMutexNew(NULL);
|
||||
}
|
||||
|
||||
// this fuctions assumes you have the mutex
|
||||
void BSP_SDLogger_Flush_private() {
|
||||
// open the file
|
||||
FIL file;
|
||||
FRESULT res = f_open(&file, file_name, FA_OPEN_APPEND | FA_WRITE );
|
||||
if (res != FR_OK) {
|
||||
ULOG_ERROR("Failed to open file %s", file_name);
|
||||
}
|
||||
|
||||
// write the buffer to the file
|
||||
UINT bytes_written;
|
||||
res = f_write(&file, block_buffer, block_buffer_index, &bytes_written);
|
||||
if (res != FR_OK) {
|
||||
ULOG_ERROR("Failed to write to file %s", file_name);
|
||||
}
|
||||
|
||||
// close the file
|
||||
f_close(&file);
|
||||
|
||||
// reset the buffer index
|
||||
block_buffer_index = 0;
|
||||
|
||||
}
|
||||
|
||||
|
||||
void BSP_SDLogger_Flush() {
|
||||
// Acquire the mutex
|
||||
osMutexAcquire(logger_mutex, osWaitForever);
|
||||
|
||||
// flush the buffer
|
||||
BSP_SDLogger_Flush_private();
|
||||
|
||||
// Release the mutex
|
||||
osMutexRelease(logger_mutex);
|
||||
}
|
||||
|
||||
// write data to the logger
|
||||
// data is only written to the buffer!
|
||||
// once the buffer is full, the data is written to the file
|
||||
void BSP_SDLogger_Write(char *data, size_t length) {
|
||||
// Acquire the mutex
|
||||
osMutexAcquire(logger_mutex, osWaitForever);
|
||||
|
||||
size_t buffer_size = sizeof(block_buffer);
|
||||
size_t remaining_size = buffer_size - block_buffer_index;
|
||||
|
||||
// if the data is larger than the remaining space in the buffer
|
||||
if (length > remaining_size) {
|
||||
// write the remaining space to the buffer
|
||||
memcpy(&block_buffer[block_buffer_index], data, remaining_size);
|
||||
block_buffer_index += remaining_size;
|
||||
// write the buffer to the file
|
||||
BSP_SDLogger_Flush_private();
|
||||
// write the remaining data to the buffer
|
||||
memcpy(&block_buffer[block_buffer_index], &data[remaining_size], length - remaining_size);
|
||||
block_buffer_index = length - remaining_size;
|
||||
} else {
|
||||
// write the data to the buffer
|
||||
memcpy(&block_buffer[block_buffer_index], data, length);
|
||||
block_buffer_index += length;
|
||||
}
|
||||
|
||||
// Release the mutex
|
||||
osMutexRelease(logger_mutex);
|
||||
}
|
||||
@@ -2,3 +2,13 @@
|
||||
// buffernd logger collect logs until some amount of data is collected.
|
||||
// needs to be flushed before shutdown
|
||||
// used with ULOG
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stddef.h>
|
||||
|
||||
void BSP_SDLogger_Init(int log_number);
|
||||
|
||||
|
||||
void BSP_SDLogger_Write(char *data, size_t length);
|
||||
|
||||
void BSP_SDLogger_Flush();
|
||||
@@ -3,6 +3,9 @@ add_library(BSP STATIC
|
||||
BSP_EE24.c
|
||||
BSP_INA.c
|
||||
BSP_POWER.c
|
||||
BSP_GPIO.c
|
||||
BSP_ADC.c
|
||||
BSP_SDLogger.c
|
||||
)
|
||||
|
||||
target_include_directories(BSP PUBLIC ./)
|
||||
|
||||
Submodule Application/CLS updated: 5535393c23...4744762b4c
@@ -1,4 +1,5 @@
|
||||
#include "CLS_BSP.h"
|
||||
#include "CLSAddress.h"
|
||||
|
||||
|
||||
#ifdef CLS_BSP_FDCAN
|
||||
@@ -25,4 +26,51 @@ HAL_StatusTypeDef CLS_BSP_CAN_SetUniversalFilter(const CLS_BSP_CAN_UniversalFilt
|
||||
#endif
|
||||
|
||||
|
||||
uint8_t CLS_BSP_DLC_ToBytes(uint32_t dlc) {
|
||||
|
||||
switch (dlc) {
|
||||
case CLS_BSP_DLC_BYTES_1:
|
||||
return 1;
|
||||
case CLS_BSP_DLC_BYTES_2:
|
||||
return 2;
|
||||
case CLS_BSP_DLC_BYTES_3:
|
||||
return 3;
|
||||
case CLS_BSP_DLC_BYTES_4:
|
||||
return 4;
|
||||
case CLS_BSP_DLC_BYTES_5:
|
||||
return 5;
|
||||
case CLS_BSP_DLC_BYTES_6:
|
||||
return 6;
|
||||
case CLS_BSP_DLC_BYTES_7:
|
||||
return 7;
|
||||
case CLS_BSP_DLC_BYTES_8:
|
||||
return 8;
|
||||
default:
|
||||
return 0;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
CLS_Type_t CLS_BSP_GetDeviceType(void) {
|
||||
return cls_device_Type_MASTER;
|
||||
}
|
||||
|
||||
|
||||
void CLS_BSP_SetDeviceType(CLS_Type_t type) {
|
||||
}
|
||||
|
||||
CLS_Position_t CLS_BSP_GetPosition(void) {
|
||||
CLS_Position_t position;
|
||||
position.p0 = cls_device_Position_FRONT;
|
||||
position.p1 = cls_device_Position_CENTER;
|
||||
return position;
|
||||
}
|
||||
|
||||
void CLS_BSP_SetPosition(CLS_Position_t position) {
|
||||
}
|
||||
|
||||
|
||||
|
||||
#include "BSP_GPIO.h"
|
||||
|
||||
|
||||
@@ -1,10 +1,10 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#define CLS_BSP_FDCAN
|
||||
|
||||
#ifdef CLS_BSP_FDCAN
|
||||
|
||||
#include "fdcan.h"
|
||||
#include "CLS.h"
|
||||
|
||||
typedef FDCAN_TxHeaderTypeDef CLS_BSP_TxHeaderType;
|
||||
|
||||
@@ -30,6 +30,9 @@ typedef FDCAN_TxHeaderTypeDef CLS_BSP_TxHeaderType;
|
||||
#define CLS_BSP_DLC_BYTES_7 FDCAN_DLC_BYTES_7
|
||||
#define CLS_BSP_DLC_BYTES_8 FDCAN_DLC_BYTES_8
|
||||
|
||||
// function to convert DLC to bytes
|
||||
uint8_t CLS_BSP_DLC_ToBytes(uint32_t dlc);
|
||||
|
||||
#define CLS_CAN_FILTER_DISABLE FDCAN_FILTER_DISABLE
|
||||
#define CLS_CAN_FILTER_TO_RXFIFO0 FDCAN_FILTER_TO_RXFIFO0
|
||||
#define CLS_CAN_FILTER_TO_RXFIFO1 FDCAN_FILTER_TO_RXFIFO1
|
||||
@@ -51,3 +54,9 @@ typedef struct {
|
||||
HAL_StatusTypeDef CLS_BSP_CAN_AddMessageToSend(CLS_BSP_TxHeaderType * header, uint8_t * data);
|
||||
|
||||
HAL_StatusTypeDef CLS_BSP_CAN_SetUniversalFilter(const CLS_BSP_CAN_UniversalFilter * filter);
|
||||
|
||||
CLS_Type_t CLS_BSP_GetDeviceType(void);
|
||||
void CLS_BSP_SetDeviceType(CLS_Type_t type);
|
||||
|
||||
CLS_Position_t CLS_BSP_GetPosition(void);
|
||||
void CLS_BSP_SetPosition(CLS_Position_t position);
|
||||
|
||||
@@ -11,4 +11,5 @@ target_sources(${PROJECT_NAME}
|
||||
${CMAKE_CURRENT_LIST_DIR}/CLS_BSP.h
|
||||
)
|
||||
|
||||
target_include_directories(${PROJECT_NAME} INTERFACE ${CMAKE_CURRENT_LIST_DIR})
|
||||
target_include_directories(${PROJECT_NAME} PUBLIC ${CMAKE_CURRENT_LIST_DIR})
|
||||
target_link_libraries(${PROJECT_NAME} PRIVATE CLS BSP Vehicle)
|
||||
@@ -1,4 +1,6 @@
|
||||
add_subdirectory(Tasks)
|
||||
add_subdirectory(CLS_BSP)
|
||||
add_subdirectory(CLS)
|
||||
add_subdirectory(CLS_BSP)
|
||||
add_subdirectory(BSP)
|
||||
add_subdirectory(ram_loader)
|
||||
add_subdirectory(Vehicle)
|
||||
@@ -11,13 +11,15 @@ target_sources(${PROJECT_NAME}
|
||||
${CMAKE_CURRENT_LIST_DIR}/FirmwareHandler.c
|
||||
${CMAKE_CURRENT_LIST_DIR}/FirmwareUpdate.c
|
||||
${CMAKE_CURRENT_LIST_DIR}/LightTask.c
|
||||
${CMAKE_CURRENT_LIST_DIR}/LightState.c
|
||||
INTERFACE
|
||||
${CMAKE_CURRENT_LIST_DIR}/UsbDataHandler.h
|
||||
${CMAKE_CURRENT_LIST_DIR}/CanDataTask.h
|
||||
${CMAKE_CURRENT_LIST_DIR}/FirmwareUpdate.h
|
||||
${CMAKE_CURRENT_LIST_DIR}/LightTask.h
|
||||
${CMAKE_CURRENT_LIST_DIR}/LightState.h
|
||||
)
|
||||
|
||||
target_include_directories(${PROJECT_NAME} INTERFACE ${CMAKE_CURRENT_LIST_DIR})
|
||||
target_link_libraries(${PROJECT_NAME} PUBLIC PROTOS CLS)
|
||||
target_link_libraries(${PROJECT_NAME} PRIVATE CLS_BSP BSP)
|
||||
target_link_libraries(${PROJECT_NAME} PRIVATE Revision CLS_BSP BSP ulog Vehicle ram_loader)
|
||||
@@ -7,7 +7,11 @@
|
||||
#include "firmware.pb.h"
|
||||
#include "cls_device.pb.h"
|
||||
#include "usb.pb.h"
|
||||
|
||||
#include "version_info.h"
|
||||
#include "ulog.h"
|
||||
#include "BSP_POWER.h"
|
||||
#include "BSP_GPIO.h"
|
||||
#include "Vehicle.h"
|
||||
// Define thread flags
|
||||
#define FLAG_FDCAN_RX_FIFO0 (1<<0)
|
||||
#define FLAG_FDCAN_RX_FIFO1 (1<<1)
|
||||
@@ -28,6 +32,22 @@ const osThreadAttr_t CanDataTask_attr = {
|
||||
.priority = osPriorityNormal,
|
||||
};
|
||||
|
||||
// Memory for the task
|
||||
StaticTask_t CarCanTask_cb;
|
||||
uint32_t CarCanTask_stk[512];
|
||||
// Attributes for the task
|
||||
osThreadId_t CarCanTask_id;
|
||||
const osThreadAttr_t CarCanTask_attr = {
|
||||
.name = "CarCanTask",
|
||||
.attr_bits = 0U,
|
||||
.cb_mem = &CarCanTask_cb,
|
||||
.cb_size = sizeof(CarCanTask_cb),
|
||||
.stack_mem = CarCanTask_stk,
|
||||
.stack_size = sizeof(CarCanTask_stk),
|
||||
.priority = osPriorityNormal,
|
||||
};
|
||||
|
||||
static uint64_t last_car_message_time = 0;
|
||||
|
||||
uint32_t dlcDecode(uint32_t dlcCode) {
|
||||
switch(dlcCode) {
|
||||
@@ -53,14 +73,14 @@ uint32_t dlcDecode(uint32_t dlcCode) {
|
||||
|
||||
|
||||
void CanDataTask_func(void *argument);
|
||||
void CarCanTask_func(void *argument);
|
||||
|
||||
void CanDataTask_start() {
|
||||
// Task functionality here
|
||||
CanDataTask_id = osThreadNew(CanDataTask_func, NULL, &CanDataTask_attr);
|
||||
CarCanTask_id = osThreadNew(CarCanTask_func, NULL, &CarCanTask_attr);
|
||||
}
|
||||
|
||||
static FDCAN_RxHeaderTypeDef RxHeader;
|
||||
static uint8_t RxData[8];
|
||||
|
||||
// Function for the task
|
||||
void CanDataTask_func(void *argument) {
|
||||
@@ -87,7 +107,8 @@ void CanDataTask_func(void *argument) {
|
||||
CanData_regDataMsg(GENERATE_CLS_ADDRESS(CLS_CODE_STATUS, i, CLS_CH_STA_HEATBEAT));
|
||||
}
|
||||
|
||||
|
||||
FDCAN_RxHeaderTypeDef RxHeader;
|
||||
uint8_t RxData[8];
|
||||
|
||||
for(;;) {
|
||||
// wait for interrupt event on any fifo
|
||||
@@ -111,14 +132,178 @@ void CanDataTask_func(void *argument) {
|
||||
}
|
||||
|
||||
|
||||
// convert byte to 2 hex characters
|
||||
void byteToHex(uint8_t byte, char * hex) {
|
||||
const char hexLookup[] = "0123456789ABCDEF";
|
||||
hex[0] = hexLookup[byte >> 4];
|
||||
hex[1] = hexLookup[byte & 0x0F];
|
||||
}
|
||||
|
||||
|
||||
static FDCAN_RxHeaderTypeDef RxHeader = {0};
|
||||
static uint8_t RxData[8] = {0};
|
||||
|
||||
void CarCanTask_func(void *argument) {
|
||||
|
||||
// for testing accept all messages from the car can bus
|
||||
// put unkown messages in fifo 0
|
||||
if (HAL_FDCAN_ConfigGlobalFilter(&hfdcan2, FDCAN_ACCEPT_IN_RX_FIFO0, FDCAN_ACCEPT_IN_RX_FIFO0, FDCAN_REJECT_REMOTE, FDCAN_REJECT_REMOTE) != HAL_OK) {
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
|
||||
Vehicle_Setup_CAN();
|
||||
|
||||
|
||||
/* Start the FDCAN module */
|
||||
if (HAL_FDCAN_Start(&hfdcan2) != HAL_OK){
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
if(HAL_FDCAN_ActivateNotification(&hfdcan2,FDCAN_IT_RX_FIFO0_NEW_MESSAGE | FDCAN_IT_RX_FIFO1_NEW_MESSAGE, 0) != HAL_OK) {
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
|
||||
|
||||
for(;;) {
|
||||
// wait for interrupt event on any fifo
|
||||
osThreadFlagsWait(FLAG_FDCAN_RX_FIFO0 | FLAG_FDCAN_RX_FIFO1, osFlagsWaitAny, osWaitForever);
|
||||
// check the fifos for data and handle it if nessessay
|
||||
while (HAL_FDCAN_GetRxFifoFillLevel(&hfdcan2, FDCAN_RX_FIFO0) > 0 ) {
|
||||
if (HAL_FDCAN_GetRxMessage(&hfdcan2, FDCAN_RX_FIFO0, &RxHeader, RxData) != HAL_OK) {
|
||||
Error_Handler();
|
||||
} else {
|
||||
|
||||
// do something with the can data
|
||||
//last_car_message_time = osKernelGetTickCount();
|
||||
char msg[17] = {0};
|
||||
|
||||
switch (RxHeader.DataLength)
|
||||
{
|
||||
case FDCAN_DLC_BYTES_1:
|
||||
byteToHex(RxData[0], &msg[0]);
|
||||
break;
|
||||
case FDCAN_DLC_BYTES_2:
|
||||
byteToHex(RxData[0], &msg[0]);
|
||||
byteToHex(RxData[1], &msg[2]);
|
||||
break;
|
||||
case FDCAN_DLC_BYTES_3:
|
||||
byteToHex(RxData[0], &msg[0]);
|
||||
byteToHex(RxData[1], &msg[2]);
|
||||
byteToHex(RxData[2], &msg[4]);
|
||||
break;
|
||||
case FDCAN_DLC_BYTES_4:
|
||||
byteToHex(RxData[0], &msg[0]);
|
||||
byteToHex(RxData[1], &msg[2]);
|
||||
byteToHex(RxData[2], &msg[4]);
|
||||
byteToHex(RxData[3], &msg[6]);
|
||||
break;
|
||||
case FDCAN_DLC_BYTES_5:
|
||||
byteToHex(RxData[0], &msg[0]);
|
||||
byteToHex(RxData[1], &msg[2]);
|
||||
byteToHex(RxData[2], &msg[4]);
|
||||
byteToHex(RxData[3], &msg[6]);
|
||||
byteToHex(RxData[4], &msg[8]);
|
||||
break;
|
||||
case FDCAN_DLC_BYTES_6:
|
||||
byteToHex(RxData[0], &msg[0]);
|
||||
byteToHex(RxData[1], &msg[2]);
|
||||
byteToHex(RxData[2], &msg[4]);
|
||||
byteToHex(RxData[3], &msg[6]);
|
||||
byteToHex(RxData[4], &msg[8]);
|
||||
byteToHex(RxData[5], &msg[10]);
|
||||
break;
|
||||
case FDCAN_DLC_BYTES_7:
|
||||
byteToHex(RxData[0], &msg[0]);
|
||||
byteToHex(RxData[1], &msg[2]);
|
||||
byteToHex(RxData[2], &msg[4]);
|
||||
byteToHex(RxData[3], &msg[6]);
|
||||
byteToHex(RxData[4], &msg[8]);
|
||||
byteToHex(RxData[5], &msg[10]);
|
||||
byteToHex(RxData[6], &msg[12]);
|
||||
break;
|
||||
case FDCAN_DLC_BYTES_8:
|
||||
byteToHex(RxData[0], &msg[0]);
|
||||
byteToHex(RxData[1], &msg[2]);
|
||||
byteToHex(RxData[2], &msg[4]);
|
||||
byteToHex(RxData[3], &msg[6]);
|
||||
byteToHex(RxData[4], &msg[8]);
|
||||
byteToHex(RxData[5], &msg[10]);
|
||||
byteToHex(RxData[6], &msg[12]);
|
||||
byteToHex(RxData[7], &msg[14]);
|
||||
break;
|
||||
|
||||
case FDCAN_DLC_BYTES_0:
|
||||
default:
|
||||
/* nothing to do */
|
||||
break;
|
||||
}
|
||||
|
||||
//ULOG_DEBUG("Car MSG: %x, %d %s", RxHeader.Identifier,CLS_BSP_DLC_ToBytes(RxHeader.DataLength) , msg);
|
||||
|
||||
}
|
||||
}
|
||||
while (HAL_FDCAN_GetRxFifoFillLevel(&hfdcan2, FDCAN_RX_FIFO1) > 0 ) {
|
||||
if (HAL_FDCAN_GetRxMessage(&hfdcan2, FDCAN_RX_FIFO1, &RxHeader, RxData) != HAL_OK) {
|
||||
Error_Handler();
|
||||
} else {
|
||||
|
||||
Vehicle_Receive_CAN(RxHeader, RxData);
|
||||
|
||||
//ULOG_DEBUG("Used Car MSG: %x, %d %s", RxHeader.Identifier, CLS_BSP_DLC_ToBytes(RxHeader.DataLength), msg );
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Check if a car can message has been received
|
||||
*
|
||||
* @return true if a car can message has been received
|
||||
* @return false if no car can message has been received
|
||||
*/
|
||||
|
||||
|
||||
bool CanDataTask_CarCanActive() {
|
||||
if (last_car_message_time == 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return osKernelGetTickCount() - last_car_message_time < 1000;
|
||||
}
|
||||
|
||||
|
||||
|
||||
void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef *hfdcan, uint32_t RxFifo0ITs) {
|
||||
// Notify the thread
|
||||
if(hfdcan == &hfdcan1) {
|
||||
osThreadFlagsSet(CanDataTask_id, FLAG_FDCAN_RX_FIFO0);
|
||||
}
|
||||
|
||||
if(hfdcan == &hfdcan2) {
|
||||
last_car_message_time = osKernelGetTickCount();
|
||||
|
||||
while (HAL_FDCAN_GetRxFifoFillLevel(&hfdcan2, FDCAN_RX_FIFO0) > 0 ) {
|
||||
FDCAN_RxHeaderTypeDef RxHeader;
|
||||
uint8_t RxData[8];
|
||||
HAL_FDCAN_GetRxMessage(&hfdcan2, FDCAN_RX_FIFO0, &RxHeader, RxData);
|
||||
//ignore the message for now
|
||||
}
|
||||
//osThreadFlagsSet(CarCanTask_id, FLAG_FDCAN_RX_FIFO0);
|
||||
}
|
||||
}
|
||||
|
||||
void HAL_FDCAN_RxFifo1Callback(FDCAN_HandleTypeDef *hfdcan, uint32_t RxFifo1ITs) {
|
||||
// Notify the thread
|
||||
if(hfdcan == &hfdcan1) {
|
||||
osThreadFlagsSet(CanDataTask_id, FLAG_FDCAN_RX_FIFO1);
|
||||
}
|
||||
|
||||
if(hfdcan == &hfdcan2) {
|
||||
last_car_message_time = osKernelGetTickCount();
|
||||
osThreadFlagsSet(CarCanTask_id, FLAG_FDCAN_RX_FIFO1);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -133,27 +318,63 @@ extern uint8_t gCLS_DEVICE_ADDRESS;
|
||||
void DataClbk_cls_device_RequestList(void* msg, uint32_t length) {
|
||||
memset(&list,0,sizeof(list));
|
||||
// add yourself
|
||||
|
||||
CLS_Position_t position = CLS_BSP_GetPosition();
|
||||
CLS_Type_t type = CLS_BSP_GetDeviceType();
|
||||
|
||||
list.devices[list.devices_count].available = true;
|
||||
list.devices[list.devices_count].canid = GENERATE_CLS_ADDRESS(CLS_CODE_STATUS, gCLS_DEVICE_ADDRESS, CLS_CH_STA_HEATBEAT);
|
||||
list.devices[list.devices_count].device = gCLS_DEVICE_ADDRESS;
|
||||
list.devices[list.devices_count].counter = (osKernelGetTickCount()/500)%256;
|
||||
list.devices[list.devices_count].type = (uint32_t) type; // enum to uint
|
||||
list.devices[list.devices_count].position[0] = position.p0;
|
||||
list.devices[list.devices_count].position[1] = position.p1;
|
||||
list.devices[list.devices_count].position_count = 2;
|
||||
list.devices[list.devices_count].fw_version[0] = VERSION_INFO.count;
|
||||
list.devices[list.devices_count].fw_version[1] = VERSION_INFO.patch;
|
||||
list.devices[list.devices_count].fw_version[2] = VERSION_INFO.minor;
|
||||
list.devices[list.devices_count].fw_version[3] = VERSION_INFO.major;
|
||||
|
||||
list.devices_count++;
|
||||
|
||||
for (size_t i = 0; i < 16; i++)
|
||||
{
|
||||
uint16_t canid = (GENERATE_CLS_ADDRESS(CLS_CODE_STATUS, i, CLS_CH_STA_HEATBEAT));
|
||||
const CanDataMessage * msg =CanData_getDataMessage(canid);
|
||||
|
||||
if(msg) {
|
||||
if(msg->data_length > 0) {
|
||||
|
||||
CLS_HeatbeatData_t data = {0};
|
||||
memcpy(&data, msg->data, msg->data_length);
|
||||
|
||||
list.devices[list.devices_count].available = true;
|
||||
list.devices[list.devices_count].canid = canid;
|
||||
list.devices[list.devices_count].device = i;
|
||||
list.devices[list.devices_count].counter = msg->data[0];
|
||||
list.devices[list.devices_count].counter = data.counter;
|
||||
list.devices[list.devices_count].type = (uint32_t) data.type; // enum to uint
|
||||
list.devices[list.devices_count].position[0] = data.position.p0;
|
||||
list.devices[list.devices_count].position[1] = data.position.p1;
|
||||
list.devices[list.devices_count].position_count = 2;
|
||||
list.devices[list.devices_count].fw_version[0] = data.firmware_version.count;
|
||||
list.devices[list.devices_count].fw_version[1] = data.firmware_version.patch;
|
||||
list.devices[list.devices_count].fw_version[2] = data.firmware_version.minor;
|
||||
list.devices[list.devices_count].fw_version[3] = data.firmware_version.major;
|
||||
list.devices_count++;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
USBDataResonse(&list, cls_device_ResponseList_fields, cls_usb_PackageType_RESPONSE_DEVICE_LIST);
|
||||
|
||||
}
|
||||
|
||||
cls_device_UpdateDeviceSettings msg_cls_device_UpdateDeviceSettings;
|
||||
void DataClbk_cls_device_UpdateDeviceSettings(void* msg, uint32_t length)
|
||||
{
|
||||
DATA_CLBK_SETUP(cls_device_UpdateDeviceSettings);
|
||||
cls_device_UpdateDeviceSettings * msgs = &msg_cls_device_UpdateDeviceSettings;
|
||||
if(msgs->position_count >= 2) {
|
||||
CLS_Position_t pos;
|
||||
pos.p0 = msgs->position[0];
|
||||
pos.p1 = msgs->position[1];
|
||||
CLS_SendEventChangeTypePostion(msgs->device, msgs->type, pos);
|
||||
}
|
||||
}
|
||||
@@ -1,3 +1,14 @@
|
||||
#pragma once
|
||||
|
||||
#include "stdbool.h"
|
||||
|
||||
void CanDataTask_start();
|
||||
|
||||
|
||||
bool CanDataTask_gotCarCanMessage();
|
||||
|
||||
bool CanDataTask_CarCanActive();
|
||||
|
||||
uint8_t CanDataTask_CarCanBrightness();
|
||||
float CanDataTask_CarCanSpeed();
|
||||
int CanDataTask_CarCanDirectionIsForward();
|
||||
@@ -10,6 +10,9 @@
|
||||
#include "crc.h"
|
||||
#include "FirmwareUpdate.h"
|
||||
#include "stdbool.h"
|
||||
#include "CLS.h"
|
||||
#include "stdbool.h"
|
||||
#include "ram_loader.h"
|
||||
|
||||
// static memory only for decoding messages
|
||||
static cls_firmware_Start msg_cls_firmware_Start;
|
||||
@@ -58,19 +61,15 @@ void DataSend_FirmwareFileCheck(uint32_t crc, uint32_t device_id, bool ready_for
|
||||
#define CHUNK_SIZE 256 // Change this to the size of chunks you want to read
|
||||
static uint8_t crc_buffer[CHUNK_SIZE];
|
||||
|
||||
void DataClbk_cls_firmware_Start(void *msg, uint32_t length) {
|
||||
DATA_CLBK_SETUP(cls_firmware_Start);
|
||||
fwStartTime = osKernelGetSysTimerCount();
|
||||
fwPackageCounter = 0;
|
||||
|
||||
void fw_Start_Slave( cls_firmware_Start * msg) {
|
||||
|
||||
uint32_t crc = 0;
|
||||
UINT totalRead = 0;
|
||||
UINT bytesRead = 0;
|
||||
|
||||
if(FileOpen) {
|
||||
f_close(&FwFile);
|
||||
}
|
||||
// Check if file already exists
|
||||
if(f_open(&FwFile, msg_cls_firmware_Start.name, FA_READ) == FR_OK) {
|
||||
if(f_open(&FwFile, msg->name, FA_READ) == FR_OK) {
|
||||
|
||||
__HAL_CRC_DR_RESET(&hcrc);
|
||||
do {
|
||||
@@ -80,16 +79,38 @@ void DataClbk_cls_firmware_Start(void *msg, uint32_t length) {
|
||||
} while(bytesRead == CHUNK_SIZE);
|
||||
f_close(&FwFile);
|
||||
|
||||
if(crc == msg_cls_firmware_Start.crc_fw) {
|
||||
if(crc == msg->crc_fw) {
|
||||
// CRC matches, no need for transfer
|
||||
DataSend_FirmwareFileCheck(crc, msg_cls_firmware_Start.device_id, false, totalRead, msg_cls_firmware_Start.name);
|
||||
DataSend_FirmwareFileCheck(crc, msg->device_id, false, totalRead, msg->name);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
fresult_open = f_open(&FwFile, msg_cls_firmware_Start.name, FA_CREATE_ALWAYS | FA_WRITE);
|
||||
fresult_open = f_open(&FwFile, msg->name, FA_CREATE_ALWAYS | FA_WRITE);
|
||||
FileOpen=true;
|
||||
DataSend_FirmwareFileCheck(crc, msg_cls_firmware_Start.device_id, fresult_open==FR_OK, totalRead, msg_cls_firmware_Start.name);
|
||||
DataSend_FirmwareFileCheck(crc, msg->device_id, fresult_open==FR_OK, totalRead, msg->name);
|
||||
}
|
||||
|
||||
void fw_Start_Master( cls_firmware_Start * msg) {
|
||||
fresult_open = f_open(&FwFile, "firm.bin", FA_CREATE_ALWAYS | FA_WRITE);
|
||||
FileOpen=true;
|
||||
DataSend_FirmwareFileCheck(0, msg->device_id, fresult_open==FR_OK, 0, msg->name);
|
||||
}
|
||||
|
||||
void DataClbk_cls_firmware_Start(void *msg, uint32_t length) {
|
||||
DATA_CLBK_SETUP(cls_firmware_Start);
|
||||
fwStartTime = osKernelGetSysTimerCount();
|
||||
fwPackageCounter = 0;
|
||||
|
||||
if(FileOpen) {
|
||||
f_close(&FwFile);
|
||||
}
|
||||
|
||||
if(msg_cls_firmware_Start.device_id == gCLS_DEVICE_ADDRESS) {
|
||||
fw_Start_Master(&msg_cls_firmware_Start);
|
||||
} else {
|
||||
fw_Start_Slave(&msg_cls_firmware_Start);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -133,10 +154,14 @@ void DataClbk_cls_firmware_Done(void *msg, uint32_t length) {
|
||||
fresult_open = 0xFF;
|
||||
FileOpen=false;
|
||||
|
||||
if(msg_cls_firmware_Done.device_id == gCLS_DEVICE_ADDRESS) {
|
||||
RamLoader_LoadApplication();
|
||||
} else {
|
||||
|
||||
FirmwareUpdateArgs args;
|
||||
args.device = msg_cls_firmware_Done.device_id;
|
||||
memcpy(args.name, msg_cls_firmware_Start.name, sizeof(args.name));
|
||||
|
||||
FirmwareUpdateTask_start(args);
|
||||
|
||||
}
|
||||
}
|
||||
@@ -160,7 +160,6 @@ void FirmwareUpdateTask_start(FirmwareUpdateArgs args) {
|
||||
}
|
||||
}
|
||||
|
||||
UsbDataPacket buffer;
|
||||
void CLSFirmwareUpdateTask_func(void *argument) {
|
||||
FirmwareUpdateArgs args;
|
||||
osStatus_t status;
|
||||
|
||||
64
Application/Tasks/LightState.c
Normal file
64
Application/Tasks/LightState.c
Normal file
@@ -0,0 +1,64 @@
|
||||
#include "cmsis_os2.h"
|
||||
#include "LightState.h"
|
||||
#include "BSP_GPIO.h"
|
||||
#include "BSP_ADC.h"
|
||||
#include "LightTask.h"
|
||||
#include "ulog.h"
|
||||
#include "stdbool.h"
|
||||
#include "Vehicle.h"
|
||||
|
||||
// Create the task with a specific priority and stack size
|
||||
osThreadAttr_t task_attr = {
|
||||
.name = "LightStateTask",
|
||||
.priority = osPriorityNormal,
|
||||
.stack_size = 2048
|
||||
};
|
||||
|
||||
// Function prototype for the task function
|
||||
void LightStateTask(void *argument);
|
||||
|
||||
// Function to start the LightStateTask
|
||||
void LightStateTask_start(void)
|
||||
{
|
||||
osThreadNew(LightStateTask, NULL, &task_attr);
|
||||
}
|
||||
|
||||
|
||||
|
||||
// Function to determine the next state of the light
|
||||
// return 1 as default state
|
||||
// return 2 if the engine is running
|
||||
// return 3 if the headlight and engine is running
|
||||
static int determineNextState()
|
||||
{
|
||||
if (Vehicle_isHeadlightOn() && Vehicle_isEngineRunning()) {
|
||||
return 2;
|
||||
} else if (Vehicle_isEngineRunning()) {
|
||||
return 1;
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Task function
|
||||
void LightStateTask(void *argument)
|
||||
{
|
||||
|
||||
// default state
|
||||
int current_state = 0;
|
||||
// Infinite loop to keep the task running
|
||||
while (1)
|
||||
{
|
||||
// only change the state if the current state is different from the next state
|
||||
int next_state = determineNextState();
|
||||
if (current_state != next_state) {
|
||||
LightTask_setTheme(next_state);
|
||||
ULOG_INFO("Light state changed to %d", next_state);
|
||||
current_state = next_state;
|
||||
}
|
||||
|
||||
// Delay the task for a certain amount of time (in milliseconds)
|
||||
osDelay(50);
|
||||
}
|
||||
}
|
||||
7
Application/Tasks/LightState.h
Normal file
7
Application/Tasks/LightState.h
Normal file
@@ -0,0 +1,7 @@
|
||||
#ifndef LIGHT_STATE_H
|
||||
#define LIGHT_STATE_H
|
||||
|
||||
// Function to start the LightStateTask
|
||||
void LightStateTask_start();
|
||||
|
||||
#endif // LIGHT_STATE_H
|
||||
@@ -7,6 +7,13 @@
|
||||
#include "CLSAddress.h"
|
||||
#include "BSP_EE24.h"
|
||||
#include "LightTask.h"
|
||||
#include "CanDataHandler.h"
|
||||
#include "BSP_GPIO.h"
|
||||
|
||||
#include "CanDataTask.h"
|
||||
#include "Vehicle.h"
|
||||
#include "BSP_ADC.h"
|
||||
#define DIMM_DEADZONE_VOLTAGE 0.7
|
||||
|
||||
// Memory for the task
|
||||
StaticTask_t LightTask_cb;
|
||||
@@ -27,11 +34,23 @@ static cls_light_GlobalBrightness msg_cls_light_GlobalBrightness;
|
||||
static cls_light_GlobalTheme msg_cls_light_GlobalTheme;
|
||||
static cls_light_ThemeSettings msg_cls_light_ThemeSettings;
|
||||
static cls_light_SaveThemeSettings msg_cls_light_SaveThemeSettings;
|
||||
static cls_light_RequestThemeSetting msg_cls_light_RequestThemeSetting;
|
||||
|
||||
static volatile struct LightSettings_s {
|
||||
typedef struct LightSettings_s {
|
||||
volatile uint8_t brightness;
|
||||
volatile uint8_t theme;
|
||||
} lightSettings;
|
||||
} LightSettings_t;
|
||||
|
||||
static volatile LightSettings_t lightSettings = {0};
|
||||
static volatile LightSettings_t lightSettings_dimmed = {0};
|
||||
|
||||
void LightTask_setBrightness(uint8_t brightness) {
|
||||
lightSettings.brightness = brightness;
|
||||
}
|
||||
|
||||
void LightTask_setTheme(uint8_t theme) {
|
||||
lightSettings.theme = theme;
|
||||
}
|
||||
|
||||
// these are used to save these settings some tome after they change
|
||||
static const uint32_t settingSaveTimeout = 10*1000;
|
||||
@@ -47,8 +66,6 @@ void LightTask_start() {
|
||||
|
||||
|
||||
void LightTask_func(void *argument) {
|
||||
osDelay(10);
|
||||
|
||||
BSP_EE24_PartRead(BSP_EE24_PART_GLOBAL_LIGHT, (uint8_t*) &lightSettings, sizeof(lightSettings));
|
||||
uint16_t msg_global_light = GENERATE_CLS_ADDRESS(CLS_CODE_MESSAGE, GLOBAL_CAST_CLS_ADDRESS, CLS_CH_MSG_LIGHT);
|
||||
CLS_BSP_TxHeaderType can_header = CREATE_BSP_CAN_HEADER(msg_global_light, CLS_BSP_DLC_BYTES_2);
|
||||
@@ -58,7 +75,45 @@ void LightTask_func(void *argument) {
|
||||
{
|
||||
tick += 50;
|
||||
osDelayUntil(tick);
|
||||
CLS_BSP_CAN_AddMessageToSend(&can_header,(uint8_t*)&lightSettings);
|
||||
|
||||
|
||||
// calculate the brightness to send
|
||||
uint8_t brightness = lightSettings.brightness;
|
||||
// Read ADC battery voltage and dimmer voltage
|
||||
|
||||
|
||||
|
||||
uint8_t dimm = 255;
|
||||
|
||||
// currenlty not working
|
||||
// only dimm if the headlight is on
|
||||
//if (Vehicle_isHeadlightOn()) {
|
||||
|
||||
// new version over CAN
|
||||
//dimm = Vehicle_Brightness();
|
||||
|
||||
// old version over ADC
|
||||
// calculate the dimmfactor based on the battery voltage and the dimmer voltage
|
||||
// the dimmfactor shoudl be 0 if the dimmer voltage is 4V.
|
||||
// the dimmfactor should be 1 if the dimmer voltage is the same as the battery voltage
|
||||
// float v_bus = BSP_ADC_ReadBusValue() - DIMM_DEADZONE_VOLTAGE;
|
||||
// float v_dimm = BSP_ADC_ReadDimmerValue();
|
||||
//if (v_dimm >= v_bus) {
|
||||
// dimmfactor = 1.0;
|
||||
//} else if (v_dimm <= 4.0) {
|
||||
// dimmfactor = 0.0;
|
||||
//} else {
|
||||
// dimmfactor = (v_dimm - 4.0) / (v_bus - 4.0);
|
||||
//}
|
||||
|
||||
//}
|
||||
|
||||
uint8_t adjustedBrightness = (brightness * dimm)/ 255;
|
||||
lightSettings_dimmed.brightness = adjustedBrightness;
|
||||
lightSettings_dimmed.theme = lightSettings.theme;
|
||||
|
||||
|
||||
CLS_BSP_CAN_AddMessageToSend(&can_header,(uint8_t*)&lightSettings_dimmed);
|
||||
|
||||
if( settingChangeTime !=0 && tick > settingChangeTime + settingSaveTimeout) {
|
||||
BSP_EE24_PartWrite(BSP_EE24_PART_GLOBAL_LIGHT, (uint8_t*) &lightSettings, sizeof(lightSettings));
|
||||
@@ -106,3 +161,35 @@ void DataClbk_cls_light_SaveThemeSettings(void* msg, uint32_t length) {
|
||||
CLS_BSP_TxHeaderType can_header = CREATE_BSP_CAN_HEADER(msg_light_setting, CLS_BSP_DLC_BYTES_1);
|
||||
CLS_BSP_CAN_AddMessageToSend(&can_header, (uint8_t*)"X");
|
||||
}
|
||||
|
||||
static uint8_t request_theme;
|
||||
static RGB_Theme_t response_theme;
|
||||
static cls_light_ThemeSettings themesettings;
|
||||
void CanData_responseThemeSetting(CanDataId canid, uint8_t* data, uint8_t len) {
|
||||
if(len == 8) {
|
||||
memcpy(&response_theme, data, 8);
|
||||
|
||||
themesettings.animation = response_theme.animation;
|
||||
themesettings.brightness = response_theme.max_brighness;
|
||||
themesettings.deviceId = (canid >> 3) & 0x1F;
|
||||
themesettings.rgb = response_theme.color.r | (response_theme.color.g << 8) | (response_theme.color.b << 16);
|
||||
themesettings.theme = request_theme;
|
||||
USBDataResonse(&themesettings,cls_light_ThemeSettings_fields, cls_usb_PackageType_LIGHT_SETTING_THEME);
|
||||
}
|
||||
|
||||
CanData_removeEvent(canid);
|
||||
}
|
||||
|
||||
void DataClbk_cls_light_RequestThemeSetting(void* msg, uint32_t length) {
|
||||
DATA_CLBK_SETUP(cls_light_RequestThemeSetting);
|
||||
uint8_t device = msg_cls_light_RequestThemeSetting.deviceId;
|
||||
request_theme = (uint8_t)msg_cls_light_RequestThemeSetting.theme;
|
||||
uint16_t msg_light_setting = GENERATE_CLS_ADDRESS(CLS_CODE_CONFIG, device, 7);
|
||||
CLS_BSP_TxHeaderType can_header = CREATE_BSP_CAN_HEADER(msg_light_setting, CLS_BSP_DLC_BYTES_1);
|
||||
|
||||
|
||||
CanData_regEventMsg(msg_light_setting,CanData_responseThemeSetting);
|
||||
|
||||
|
||||
CLS_BSP_CAN_AddMessageToSend(&can_header, (uint8_t*)&request_theme);
|
||||
}
|
||||
@@ -35,12 +35,14 @@ typedef struct RGB
|
||||
*/
|
||||
typedef struct RGB_Theme
|
||||
{
|
||||
uint8_t max_brighness;
|
||||
uint16_t max_brighness;
|
||||
RGB_t color;
|
||||
uint8_t animation;
|
||||
uint8_t reseved;
|
||||
uint16_t reseved_16;
|
||||
} RGB_Theme_t;
|
||||
|
||||
|
||||
void LightTask_start();
|
||||
|
||||
|
||||
void LightTask_setTheme(uint8_t theme);
|
||||
@@ -55,10 +55,13 @@ union {
|
||||
cls_firmware_Done msg_cls_firmware_Done;
|
||||
cls_device_RequestList msg_cls_device_RequestList;
|
||||
cls_device_ResponseList msg_cls_device_ResponseList;
|
||||
cls_device_UpdateDeviceSettings msg_cls_device_UpdateDeviceSettings;
|
||||
cls_light_GlobalBrightness msg_cls_light_GlobalBrightness;
|
||||
cls_light_GlobalTheme msg_cls_light_GlobalTheme;
|
||||
cls_light_ThemeSettings msg_cls_light_ThemeSettings;
|
||||
cls_light_SaveThemeSettings msg_cls_light_SaveThemeSettings;
|
||||
cls_light_RequestThemeSetting msg_cls_light_RequestThemeSetting;
|
||||
cls_usb_JumpToBootloader msg_cls_usb_JumpToBootloader;
|
||||
|
||||
} mem_msg_decode;
|
||||
|
||||
@@ -111,10 +114,13 @@ message_handler_t message_handlers[] = {
|
||||
MESSAGE_HANDLER(cls_usb_PackageType_FIRMWAREPACKAGEACK, cls_firmware_PackageAck),
|
||||
MESSAGE_HANDLER(cls_usb_PackageType_REQUEST_DEVICE_LIST, cls_device_RequestList),
|
||||
MESSAGE_HANDLER(cls_usb_PackageType_RESPONSE_DEVICE_LIST, cls_device_ResponseList),
|
||||
MESSAGE_HANDLER(cls_usb_PackageType_UPDATE_DEVICE_SETTINGS, cls_device_UpdateDeviceSettings),
|
||||
MESSAGE_HANDLER(cls_usb_PackageType_LIGHT_GLOBAL_BRIGHT, cls_light_GlobalBrightness),
|
||||
MESSAGE_HANDLER(cls_usb_PackageType_LIGHT_GLOBAL_THEME, cls_light_GlobalTheme),
|
||||
MESSAGE_HANDLER(cls_usb_PackageType_LIGHT_SETTING_THEME, cls_light_ThemeSettings),
|
||||
MESSAGE_HANDLER(cls_usb_PackageType_LIGHT_SETTING_THEME_SAVE, cls_light_SaveThemeSettings),
|
||||
MESSAGE_HANDLER(cls_usb_PackageType_LIGHT_REQUEST_THEME, cls_light_RequestThemeSetting),
|
||||
MESSAGE_HANDLER(cls_usb_PackageType_JUMP_TO_BOOTLOADER, cls_usb_JumpToBootloader),
|
||||
};
|
||||
|
||||
|
||||
|
||||
@@ -122,6 +122,7 @@ void UsbDataHandler_Runner();
|
||||
*/
|
||||
int UsbDataHandler_RxCallback(uint8_t* Buf, uint32_t Len);
|
||||
|
||||
void DataClbk_cls_usb_JumpToBootloader(void* msg, uint32_t length);
|
||||
|
||||
void DataClbk_cls_firmware_Start(void* msg, uint32_t length);
|
||||
void DataClbk_cls_firmware_Package(void* msg, uint32_t length);
|
||||
@@ -129,10 +130,12 @@ void DataClbk_cls_firmware_PackageAck(void* msg, uint32_t length);
|
||||
void DataClbk_cls_firmware_Done(void* msg, uint32_t length);
|
||||
void DataClbk_cls_device_ResponseList(void* msg, uint32_t length);
|
||||
void DataClbk_cls_device_RequestList(void* msg, uint32_t length);
|
||||
void DataClbk_cls_device_UpdateDeviceSettings(void* msg, uint32_t length);
|
||||
void DataClbk_cls_light_GlobalBrightness(void* msg, uint32_t length);
|
||||
void DataClbk_cls_light_GlobalTheme(void* msg, uint32_t length);
|
||||
void DataClbk_cls_light_ThemeSettings(void* msg, uint32_t length);
|
||||
void DataClbk_cls_light_SaveThemeSettings(void* msg, uint32_t length);
|
||||
void DataClbk_cls_light_RequestThemeSetting(void* msg, uint32_t length);
|
||||
|
||||
#include "usb.pb.h"
|
||||
void USBDataResonse(void * msg, const pb_msgdesc_t *fields, cls_usb_PackageType typeid);
|
||||
|
||||
32
Application/Vehicle/CMakeLists.txt
Normal file
32
Application/Vehicle/CMakeLists.txt
Normal file
@@ -0,0 +1,32 @@
|
||||
# Set the minimum required CMake version
|
||||
cmake_minimum_required(VERSION 3.12)
|
||||
|
||||
# Set the project name
|
||||
project(Vehicle)
|
||||
|
||||
# Add the source files for the library
|
||||
set(SOURCES
|
||||
Vehicle.c
|
||||
Vehicle_can.c
|
||||
)
|
||||
|
||||
# Add the header files for the library
|
||||
set(HEADERS
|
||||
Vehicle.h
|
||||
)
|
||||
|
||||
# Create the library target
|
||||
add_library(Vehicle ${SOURCES} ${HEADERS})
|
||||
|
||||
# Set the include directories for the library
|
||||
target_include_directories(Vehicle PUBLIC ./)
|
||||
|
||||
# Set any additional compiler flags or options
|
||||
# target_compile_options(Vehicle PRIVATE ...)
|
||||
|
||||
# Set any additional linker flags or options
|
||||
# target_link_options(Vehicle PRIVATE ...)
|
||||
|
||||
# Specify any dependencies for the library
|
||||
target_link_libraries(Vehicle BSP CLS CLS_BSP)
|
||||
|
||||
82
Application/Vehicle/Vehicle.c
Normal file
82
Application/Vehicle/Vehicle.c
Normal file
@@ -0,0 +1,82 @@
|
||||
|
||||
#include "Vehicle.h"
|
||||
#include "BSP_GPIO.h"
|
||||
#include "stdbool.h"
|
||||
#include "BSP_ADC.h"
|
||||
|
||||
// Define the threshold voltage for engine running
|
||||
#define ENGINE_RUNNING_THRESHOLD 13.0 // 13.5V
|
||||
|
||||
// Define thresholds with hysteresis
|
||||
#define ENGINE_RUNNING_THRESHOLD_HIGH (ENGINE_RUNNING_THRESHOLD + 0.225)
|
||||
#define ENGINE_RUNNING_THRESHOLD_LOW (ENGINE_RUNNING_THRESHOLD - 0.225)
|
||||
|
||||
// Global variable to store the current engine state
|
||||
static bool engineRunning = false;
|
||||
|
||||
|
||||
void Vehicle_Init() {
|
||||
engineRunning = false;
|
||||
}
|
||||
|
||||
bool Vehicle_isHeadlightOn()
|
||||
{
|
||||
return BSP_GPIO_HeadLightIsSet();
|
||||
}
|
||||
|
||||
bool Vehicle_isEngineRunning() {
|
||||
|
||||
|
||||
float voltage = BSP_ADC_ReadBusValue();
|
||||
|
||||
if (engineRunning)
|
||||
{
|
||||
// If engine is currently running, use the lower threshold to turn it off
|
||||
if (voltage < ENGINE_RUNNING_THRESHOLD_LOW)
|
||||
{
|
||||
engineRunning = false;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// If engine is currently off, use the higher threshold to turn it on
|
||||
if (voltage > ENGINE_RUNNING_THRESHOLD_HIGH)
|
||||
{
|
||||
engineRunning = true;
|
||||
}
|
||||
|
||||
|
||||
|
||||
}
|
||||
return engineRunning;
|
||||
}
|
||||
|
||||
bool Vehicle_isK15On() {
|
||||
return BSP_GPIO_K15isSet();
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#include "CLS.h"
|
||||
#include "CLS_BSP.h"
|
||||
#include "CLSAddress.h"
|
||||
|
||||
static CLS_VehicleStatus_t status = {0};
|
||||
_Static_assert(sizeof(status) == 8, "CLS_HeatbeatData_t is not 8 bytes");
|
||||
|
||||
void CLS_VehicleHeatbeat(void *argument) {
|
||||
CLS_BSP_TxHeaderType cls_vehicle_header = CREATE_BSP_CAN_HEADER(GENERATE_CLS_ADDRESS(CLS_CODE_STATUS,0,CLS_CH_STA_VEHICLE), CLS_BSP_DLC_BYTES_8);
|
||||
|
||||
|
||||
status.k15 = Vehicle_isK15On();
|
||||
status.headlight = Vehicle_isHeadlightOn();
|
||||
status.engine = Vehicle_isEngineRunning();
|
||||
status.speed = (uint8_t)Vehicle_Speed();
|
||||
status.unlocked = Vehicle_UnlockedSignal();
|
||||
|
||||
CLS_BSP_CAN_AddMessageToSend(&cls_vehicle_header, (uint8_t*)&status);
|
||||
|
||||
}
|
||||
24
Application/Vehicle/Vehicle.h
Normal file
24
Application/Vehicle/Vehicle.h
Normal file
@@ -0,0 +1,24 @@
|
||||
|
||||
#include "fdcan.h"
|
||||
#include "stdint.h"
|
||||
#include "stdbool.h"
|
||||
|
||||
void Vehicle_Init();
|
||||
|
||||
bool Vehicle_isHeadlightOn();
|
||||
|
||||
bool Vehicle_isEngineRunning();
|
||||
|
||||
bool Vehicle_isK15On();
|
||||
|
||||
|
||||
void Vehicle_Setup_CAN();
|
||||
|
||||
void Vehicle_Receive_CAN( FDCAN_RxHeaderTypeDef header, uint8_t* data);
|
||||
|
||||
|
||||
bool Vehicle_gotUnlockMessage();
|
||||
uint8_t Vehicle_Brightness();
|
||||
float Vehicle_Speed();
|
||||
int Vehicle_DirectionIsForward();
|
||||
bool Vehicle_UnlockedSignal();
|
||||
146
Application/Vehicle/Vehicle_can.c
Normal file
146
Application/Vehicle/Vehicle_can.c
Normal file
@@ -0,0 +1,146 @@
|
||||
#include "Vehicle.h"
|
||||
#include "fdcan.h"
|
||||
#include "CLS.h"
|
||||
#include "CLS_BSP.h"
|
||||
#include "BSP_GPIO.h"
|
||||
#include "cmsis_os2.h"
|
||||
|
||||
static uint64_t last_unlock_message_time = UINT64_MAX;
|
||||
static uint8_t car_can_brightness = 255;
|
||||
static float car_can_speed = 0;
|
||||
static int car_can_direction = 0;
|
||||
|
||||
|
||||
void Vehicle_Setup_CAN() {
|
||||
|
||||
|
||||
FDCAN_FilterTypeDef sFilterConfig;
|
||||
sFilterConfig.IdType = FDCAN_STANDARD_ID;
|
||||
sFilterConfig.FilterIndex = 0;
|
||||
sFilterConfig.FilterType = CLS_BSP_CAN_FILTER_LIST;
|
||||
sFilterConfig.FilterConfig = FDCAN_FILTER_TO_RXFIFO1;
|
||||
sFilterConfig.FilterID1 = 0x391;
|
||||
sFilterConfig.FilterID2 = 0x395;
|
||||
HAL_FDCAN_ConfigFilter(&hfdcan2, &sFilterConfig);
|
||||
|
||||
sFilterConfig.FilterIndex = 1;
|
||||
sFilterConfig.FilterID1 = 0x351;
|
||||
sFilterConfig.FilterID2 = 0x635;
|
||||
HAL_FDCAN_ConfigFilter(&hfdcan2, &sFilterConfig);
|
||||
|
||||
}
|
||||
|
||||
|
||||
static void rx_unlock_key(uint8_t * RxData ) {
|
||||
if (RxData[1] == 0x04)
|
||||
{
|
||||
// car was unlocked
|
||||
last_unlock_message_time = osKernelGetTickCount();
|
||||
}
|
||||
else if (RxData[1] ==0x80)
|
||||
{
|
||||
// car was locked
|
||||
if (!BSP_GPIO_K15isSet()) {
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
static void rx_unlock_secure(uint8_t * RxData ) {
|
||||
if ((RxData[0] & 0x0F) == 0x01) {
|
||||
// car was unlocked
|
||||
last_unlock_message_time = osKernelGetTickCount();
|
||||
|
||||
} else if ((RxData[0] & 0x0F) == 0x02) {
|
||||
// car was locked
|
||||
if (!BSP_GPIO_K15isSet()) {
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
static void rx_speed(uint8_t * RxData) {
|
||||
// speed signal
|
||||
// AA BB XX YY 00 00 00 00
|
||||
// Speed (XX*(2^8)+(YY-1))/190
|
||||
// direction AA = 0x00 forward, 0x02 backward
|
||||
uint16_t speed = (RxData[2] << 8) + RxData[3];
|
||||
float speed_kmh = (speed - 1) / 190.0;
|
||||
car_can_speed = speed_kmh;
|
||||
car_can_direction = RxData[0];
|
||||
//ULOG_DEBUG("Speed: %f, Direction: %d", car_can_speed, car_can_direction);
|
||||
|
||||
}
|
||||
|
||||
static void rx_brightness(uint8_t* RxData) {
|
||||
// scale the brightness to 0 - 255 only using integer math
|
||||
car_can_brightness = ((uint32_t)RxData[0] * 255) / 100;
|
||||
//ULOG_DEBUG("Brightness: %d", car_can_brightness);
|
||||
}
|
||||
|
||||
void Vehicle_Receive_CAN( FDCAN_RxHeaderTypeDef RxHeader, uint8_t* RxData) {
|
||||
|
||||
if(RxHeader.Identifier == 0x391) {
|
||||
rx_unlock_key(RxData);
|
||||
}
|
||||
|
||||
if (RxHeader.Identifier == 0x395) {
|
||||
rx_unlock_secure(RxData);
|
||||
}
|
||||
|
||||
|
||||
if (RxHeader.Identifier == 0x351) {
|
||||
rx_speed(RxData);
|
||||
}
|
||||
|
||||
// brightness knob in 0 - 100
|
||||
if (RxHeader.Identifier == 0x635) {
|
||||
rx_brightness(RxData);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
bool Vehicle_gotUnlockMessage() {
|
||||
return last_unlock_message_time != UINT64_MAX;
|
||||
}
|
||||
|
||||
|
||||
|
||||
uint8_t Vehicle_Brightness() {
|
||||
return car_can_brightness;
|
||||
}
|
||||
|
||||
float Vehicle_Speed() {
|
||||
return car_can_speed;
|
||||
}
|
||||
|
||||
int Vehicle_DirectionIsForward() {
|
||||
return car_can_direction == 0;
|
||||
}
|
||||
|
||||
|
||||
static bool unlocked = false;
|
||||
|
||||
|
||||
bool Vehicle_UnlockedSignal() {
|
||||
|
||||
if (unlocked) {
|
||||
if(Vehicle_isK15On()) {
|
||||
unlocked = false;
|
||||
last_unlock_message_time = UINT64_MAX;
|
||||
}
|
||||
}
|
||||
|
||||
if (!unlocked) {
|
||||
if (Vehicle_gotUnlockMessage()) {
|
||||
unlocked = true;
|
||||
}
|
||||
}
|
||||
|
||||
return unlocked;
|
||||
}
|
||||
34
Application/ram_loader/CMakeLists.txt
Normal file
34
Application/ram_loader/CMakeLists.txt
Normal file
@@ -0,0 +1,34 @@
|
||||
# Set the minimum required CMake version
|
||||
cmake_minimum_required(VERSION 3.12)
|
||||
|
||||
# Set the project name
|
||||
project(ram_loader)
|
||||
|
||||
# Add the source files for the library
|
||||
set(SOURCES
|
||||
ram_loader.c
|
||||
)
|
||||
|
||||
# Add the header files for the library
|
||||
set(HEADERS
|
||||
ram_loader.h
|
||||
)
|
||||
|
||||
# Create the library target
|
||||
add_library(ram_loader ${SOURCES} ${HEADERS})
|
||||
|
||||
# Set the include directories for the library
|
||||
target_include_directories(ram_loader PUBLIC ./)
|
||||
|
||||
# Set any additional compiler flags or options
|
||||
# target_compile_options(${PROJECT_NAME} PRIVATE ...)
|
||||
|
||||
# Set any additional linker flags or options
|
||||
# target_link_options(${PROJECT_NAME} PRIVATE ...)
|
||||
|
||||
# Specify any dependencies for the library
|
||||
# target_link_libraries(${PROJECT_NAME} <dependency1> <dependency2> ...)
|
||||
|
||||
# Optionally, add an executable target for testing
|
||||
# add_executable(test_ram_loader test/test_ram_loader.cpp)
|
||||
# target_link_libraries(test_ram_loader ${PROJECT_NAME})
|
||||
110
Application/ram_loader/ram_loader.c
Normal file
110
Application/ram_loader/ram_loader.c
Normal file
@@ -0,0 +1,110 @@
|
||||
#include "fatfs.h"
|
||||
#include "string.h"
|
||||
|
||||
#define RAM_LOADER_BUFFER_SIZE 15*1024
|
||||
#define RAM_LOADER_ADDRESS 0x38000000
|
||||
#define APP_START_ADDRESS RAM_LOADER_ADDRESS
|
||||
uint8_t * ram_loader_buffer = (uint8_t *) RAM_LOADER_ADDRESS;
|
||||
|
||||
void _app_start(void)
|
||||
{
|
||||
__disable_irq();
|
||||
// Reset USB
|
||||
|
||||
//De-init all peripherals
|
||||
//HAL_ADC_DeInit(&hadc1);
|
||||
|
||||
// Disable Systick
|
||||
SysTick->CTRL = 0;
|
||||
SysTick->LOAD = 0;
|
||||
SysTick->VAL = 0;
|
||||
|
||||
// Reset clock to default
|
||||
HAL_RCC_DeInit();
|
||||
|
||||
// Clear all interrupt bits
|
||||
for (uint8_t i = 0; i < sizeof(NVIC->ICER) / sizeof(NVIC->ICER[0]); i++)
|
||||
{
|
||||
NVIC->ICER[i] = 0xFFFFFFFF;
|
||||
NVIC->ICPR[i] = 0xFFFFFFFF;
|
||||
}
|
||||
|
||||
__enable_irq();
|
||||
|
||||
|
||||
// set the vector table offset register
|
||||
SCB->VTOR = APP_START_ADDRESS;
|
||||
|
||||
// get the application stack pointer
|
||||
__set_MSP(((uint32_t *)APP_START_ADDRESS)[0]);
|
||||
|
||||
|
||||
// jump to the application
|
||||
((void (*)(void))((uint32_t *)APP_START_ADDRESS)[1])();
|
||||
|
||||
// the application should never return
|
||||
// ULOG_ERROR("Failed to start application");
|
||||
while (1) {}
|
||||
|
||||
}
|
||||
|
||||
static uint8_t buffer[512];
|
||||
|
||||
void RamLoader_LoadApplication()
|
||||
{
|
||||
|
||||
// check if the file "load.bin" exists
|
||||
FIL file;
|
||||
FRESULT res = f_open(&file, "load.bin", FA_READ);
|
||||
if (res != FR_OK) {
|
||||
// ULOG_ERROR("Failed to open file load.bin");
|
||||
return;
|
||||
}
|
||||
|
||||
UINT size = f_size(&file);
|
||||
// ensure the file is not larger than the buffer
|
||||
if (size > RAM_LOADER_BUFFER_SIZE ) {
|
||||
// ULOG_ERROR("File load.bin is too large");
|
||||
return;
|
||||
}
|
||||
|
||||
// read the file into the buffer
|
||||
UINT bytes_read;
|
||||
uint32_t remaining_bytes = size;
|
||||
uint8_t *destination_ptr = ram_loader_buffer;
|
||||
uint8_t *buffer_ptr = buffer;
|
||||
while (remaining_bytes > 0) {
|
||||
UINT read_size = remaining_bytes > 512 ? 512 : remaining_bytes;
|
||||
res = f_read(&file, buffer_ptr, read_size, &bytes_read);
|
||||
if (res != FR_OK) {
|
||||
// ULOG_ERROR("Failed to read file load.bin");
|
||||
return;
|
||||
}
|
||||
if (bytes_read != read_size) {
|
||||
// ULOG_ERROR("Failed to read file load.bin completely");
|
||||
return;
|
||||
}
|
||||
|
||||
memcpy(destination_ptr, buffer_ptr, read_size);
|
||||
remaining_bytes -= read_size;
|
||||
destination_ptr += read_size;
|
||||
}
|
||||
|
||||
// close the file
|
||||
f_close(&file);
|
||||
|
||||
|
||||
// check that the file to flash exists ("firm.bin")
|
||||
res = f_open(&file, "firm.bin", FA_READ);
|
||||
if (res != FR_OK) {
|
||||
// ULOG_ERROR("Failed to open file firm.bin");
|
||||
return;
|
||||
}
|
||||
//close the file
|
||||
f_close(&file);
|
||||
|
||||
|
||||
_app_start();
|
||||
|
||||
|
||||
}
|
||||
3
Application/ram_loader/ram_loader.h
Normal file
3
Application/ram_loader/ram_loader.h
Normal file
@@ -0,0 +1,3 @@
|
||||
#pragma once
|
||||
|
||||
void RamLoader_LoadApplication();
|
||||
@@ -1,24 +1,30 @@
|
||||
#MicroXplorer Configuration settings - do not modify
|
||||
ADC1.Channel-1\#ChannelRegularConversion=ADC_CHANNEL_9
|
||||
ADC1.Channel-2\#ChannelRegularConversion=ADC_CHANNEL_5
|
||||
ADC1.Channel-3\#ChannelRegularConversion=ADC_CHANNEL_5
|
||||
ADC1.Channel-1\#ChannelRegularConversion=ADC_CHANNEL_5
|
||||
ADC1.Channel-2\#ChannelRegularConversion=ADC_CHANNEL_8
|
||||
ADC1.Channel-3\#ChannelRegularConversion=ADC_CHANNEL_9
|
||||
ADC1.Channel-4\#ChannelRegularConversion=ADC_CHANNEL_19
|
||||
ADC1.ContinuousConvMode=ENABLE
|
||||
ADC1.ConversionDataManagement=ADC_CONVERSIONDATA_DMA_CIRCULAR
|
||||
ADC1.EOCSelection=ADC_EOC_SEQ_CONV
|
||||
ADC1.IPParameters=Rank-1\#ChannelRegularConversion,Channel-1\#ChannelRegularConversion,SamplingTime-1\#ChannelRegularConversion,OffsetNumber-1\#ChannelRegularConversion,OffsetSignedSaturation-1\#ChannelRegularConversion,NbrOfConversionFlag,master,ContinuousConvMode,EOCSelection,Rank-2\#ChannelRegularConversion,Channel-2\#ChannelRegularConversion,SamplingTime-2\#ChannelRegularConversion,OffsetNumber-2\#ChannelRegularConversion,OffsetSignedSaturation-2\#ChannelRegularConversion,Rank-3\#ChannelRegularConversion,Channel-3\#ChannelRegularConversion,SamplingTime-3\#ChannelRegularConversion,OffsetNumber-3\#ChannelRegularConversion,OffsetSignedSaturation-3\#ChannelRegularConversion,NbrOfConversion
|
||||
ADC1.NbrOfConversion=3
|
||||
ADC1.IPParameters=Rank-1\#ChannelRegularConversion,Channel-1\#ChannelRegularConversion,SamplingTime-1\#ChannelRegularConversion,OffsetNumber-1\#ChannelRegularConversion,OffsetSignedSaturation-1\#ChannelRegularConversion,NbrOfConversionFlag,master,ContinuousConvMode,EOCSelection,Rank-2\#ChannelRegularConversion,Channel-2\#ChannelRegularConversion,SamplingTime-2\#ChannelRegularConversion,OffsetNumber-2\#ChannelRegularConversion,OffsetSignedSaturation-2\#ChannelRegularConversion,Rank-3\#ChannelRegularConversion,Channel-3\#ChannelRegularConversion,SamplingTime-3\#ChannelRegularConversion,OffsetNumber-3\#ChannelRegularConversion,OffsetSignedSaturation-3\#ChannelRegularConversion,NbrOfConversion,Rank-4\#ChannelRegularConversion,Channel-4\#ChannelRegularConversion,SamplingTime-4\#ChannelRegularConversion,OffsetNumber-4\#ChannelRegularConversion,OffsetSignedSaturation-4\#ChannelRegularConversion,ConversionDataManagement
|
||||
ADC1.NbrOfConversion=4
|
||||
ADC1.NbrOfConversionFlag=1
|
||||
ADC1.OffsetNumber-1\#ChannelRegularConversion=ADC_OFFSET_NONE
|
||||
ADC1.OffsetNumber-2\#ChannelRegularConversion=ADC_OFFSET_NONE
|
||||
ADC1.OffsetNumber-3\#ChannelRegularConversion=ADC_OFFSET_NONE
|
||||
ADC1.OffsetNumber-4\#ChannelRegularConversion=ADC_OFFSET_NONE
|
||||
ADC1.OffsetSignedSaturation-1\#ChannelRegularConversion=DISABLE
|
||||
ADC1.OffsetSignedSaturation-2\#ChannelRegularConversion=DISABLE
|
||||
ADC1.OffsetSignedSaturation-3\#ChannelRegularConversion=DISABLE
|
||||
ADC1.OffsetSignedSaturation-4\#ChannelRegularConversion=DISABLE
|
||||
ADC1.Rank-1\#ChannelRegularConversion=1
|
||||
ADC1.Rank-2\#ChannelRegularConversion=2
|
||||
ADC1.Rank-3\#ChannelRegularConversion=3
|
||||
ADC1.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_1CYCLE_5
|
||||
ADC1.SamplingTime-2\#ChannelRegularConversion=ADC_SAMPLETIME_1CYCLE_5
|
||||
ADC1.SamplingTime-3\#ChannelRegularConversion=ADC_SAMPLETIME_1CYCLE_5
|
||||
ADC1.Rank-4\#ChannelRegularConversion=4
|
||||
ADC1.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_32CYCLES_5
|
||||
ADC1.SamplingTime-2\#ChannelRegularConversion=ADC_SAMPLETIME_32CYCLES_5
|
||||
ADC1.SamplingTime-3\#ChannelRegularConversion=ADC_SAMPLETIME_32CYCLES_5
|
||||
ADC1.SamplingTime-4\#ChannelRegularConversion=ADC_SAMPLETIME_32CYCLES_5
|
||||
ADC1.master=1
|
||||
CAD.formats=
|
||||
CAD.pinconfig=
|
||||
@@ -27,11 +33,30 @@ CORTEX_M7.CPU_DCache=Disabled
|
||||
CORTEX_M7.CPU_ICache=Enabled
|
||||
CORTEX_M7.IPParameters=default_mode_Activation,CPU_ICache,CPU_DCache
|
||||
CORTEX_M7.default_mode_Activation=1
|
||||
Dma.ADC1.4.Direction=DMA_PERIPH_TO_MEMORY
|
||||
Dma.ADC1.4.EventEnable=DISABLE
|
||||
Dma.ADC1.4.FIFOMode=DMA_FIFOMODE_DISABLE
|
||||
Dma.ADC1.4.Instance=DMA1_Stream4
|
||||
Dma.ADC1.4.MemDataAlignment=DMA_MDATAALIGN_HALFWORD
|
||||
Dma.ADC1.4.MemInc=DMA_MINC_ENABLE
|
||||
Dma.ADC1.4.Mode=DMA_CIRCULAR
|
||||
Dma.ADC1.4.PeriphDataAlignment=DMA_PDATAALIGN_HALFWORD
|
||||
Dma.ADC1.4.PeriphInc=DMA_PINC_DISABLE
|
||||
Dma.ADC1.4.Polarity=HAL_DMAMUX_REQ_GEN_RISING
|
||||
Dma.ADC1.4.Priority=DMA_PRIORITY_LOW
|
||||
Dma.ADC1.4.RequestNumber=1
|
||||
Dma.ADC1.4.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode,SignalID,Polarity,RequestNumber,SyncSignalID,SyncPolarity,SyncEnable,EventEnable,SyncRequestNumber
|
||||
Dma.ADC1.4.SignalID=NONE
|
||||
Dma.ADC1.4.SyncEnable=DISABLE
|
||||
Dma.ADC1.4.SyncPolarity=HAL_DMAMUX_SYNC_NO_EVENT
|
||||
Dma.ADC1.4.SyncRequestNumber=1
|
||||
Dma.ADC1.4.SyncSignalID=NONE
|
||||
Dma.Request0=USART1_RX
|
||||
Dma.Request1=USART1_TX
|
||||
Dma.Request2=USART3_RX
|
||||
Dma.Request3=USART3_TX
|
||||
Dma.RequestsNb=4
|
||||
Dma.Request4=ADC1
|
||||
Dma.RequestsNb=5
|
||||
Dma.USART1_RX.0.Direction=DMA_PERIPH_TO_MEMORY
|
||||
Dma.USART1_RX.0.EventEnable=DISABLE
|
||||
Dma.USART1_RX.0.FIFOMode=DMA_FIFOMODE_DISABLE
|
||||
@@ -195,7 +220,6 @@ Mcu.IP21=USART1
|
||||
Mcu.IP22=USART3
|
||||
Mcu.IP23=USB_DEVICE
|
||||
Mcu.IP24=USB_OTG_HS
|
||||
Mcu.IP25=VREFBUF
|
||||
Mcu.IP3=DEBUG
|
||||
Mcu.IP4=DMA
|
||||
Mcu.IP5=FATFS
|
||||
@@ -203,7 +227,7 @@ Mcu.IP6=FDCAN1
|
||||
Mcu.IP7=FDCAN2
|
||||
Mcu.IP8=FREERTOS
|
||||
Mcu.IP9=I2C1
|
||||
Mcu.IPNb=26
|
||||
Mcu.IPNb=25
|
||||
Mcu.Name=STM32H723VGTx
|
||||
Mcu.Package=LQFP100
|
||||
Mcu.Pin0=PE2
|
||||
@@ -267,22 +291,23 @@ Mcu.Pin60=VP_RTC_VS_RTC_WakeUp_intern
|
||||
Mcu.Pin61=VP_SYS_VS_tim1
|
||||
Mcu.Pin62=VP_TIM2_VS_ClockSourceINT
|
||||
Mcu.Pin63=VP_USB_DEVICE_VS_USB_DEVICE_CDC_HS
|
||||
Mcu.Pin64=VP_VREFBUF_V_VREFBUF
|
||||
Mcu.Pin7=PA2
|
||||
Mcu.Pin8=PA3
|
||||
Mcu.Pin9=PA5
|
||||
Mcu.PinsNb=65
|
||||
Mcu.PinsNb=64
|
||||
Mcu.ThirdParty0=STMicroelectronics.X-CUBE-EEPRMA1.4.2.0
|
||||
Mcu.ThirdPartyNb=1
|
||||
Mcu.UserConstants=
|
||||
Mcu.UserName=STM32H723VGTx
|
||||
MxCube.Version=6.9.2
|
||||
MxDb.Version=DB.6.0.92
|
||||
NVIC.ADC_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true
|
||||
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
|
||||
NVIC.DMA1_Stream0_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true
|
||||
NVIC.DMA1_Stream1_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true
|
||||
NVIC.DMA1_Stream2_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true
|
||||
NVIC.DMA1_Stream3_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true
|
||||
NVIC.DMA1_Stream4_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true
|
||||
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
|
||||
NVIC.EXTI3_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true
|
||||
NVIC.FDCAN1_IT0_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true
|
||||
@@ -515,7 +540,7 @@ ProjectManager.ToolChainLocation=
|
||||
ProjectManager.UAScriptAfterPath=
|
||||
ProjectManager.UAScriptBeforePath=
|
||||
ProjectManager.UnderRoot=true
|
||||
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-MX_I2C2_Init-I2C2-false-HAL-true,5-MX_LPUART1_UART_Init-LPUART1-false-HAL-true,6-MX_USART1_UART_Init-USART1-false-LL-true,7-MX_USART3_UART_Init-USART3-false-LL-true,8-MX_RTC_Init-RTC-false-HAL-true,9-MX_SDMMC1_SD_Init-SDMMC1-false-HAL-true,10-MX_FATFS_Init-FATFS-false-HAL-false,11-MX_ADC1_Init-ADC1-false-HAL-true,12-MX_FDCAN1_Init-FDCAN1-false-HAL-true,13-MX_USB_DEVICE_Init-USB_DEVICE-false-HAL-false,14-MX_FDCAN2_Init-FDCAN2-false-HAL-true,15-MX_I2C1_Init-I2C1-false-HAL-true,16-MX_CRC_Init-CRC-false-HAL-true,17-MX_RNG_Init-RNG-false-HAL-true,18-MX_TIM2_Init-TIM2-false-HAL-true,0-MX_CORTEX_M7_Init-CORTEX_M7-false-HAL-true,0-MX_VREFBUF_Init-VREFBUF-false-HAL-true,0-MX_PWR_Init-PWR-false-HAL-true
|
||||
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-MX_I2C2_Init-I2C2-false-HAL-true,5-MX_LPUART1_UART_Init-LPUART1-false-HAL-true,6-MX_USART1_UART_Init-USART1-false-LL-true,7-MX_USART3_UART_Init-USART3-false-LL-true,8-MX_RTC_Init-RTC-false-HAL-true,9-MX_SDMMC1_SD_Init-SDMMC1-false-HAL-true,10-MX_FATFS_Init-FATFS-false-HAL-false,11-MX_ADC1_Init-ADC1-false-HAL-true,12-MX_FDCAN1_Init-FDCAN1-false-HAL-true,13-MX_USB_DEVICE_Init-USB_DEVICE-false-HAL-false,14-MX_FDCAN2_Init-FDCAN2-false-HAL-true,15-MX_I2C1_Init-I2C1-false-HAL-true,16-MX_CRC_Init-CRC-false-HAL-true,17-MX_RNG_Init-RNG-false-HAL-true,18-MX_TIM2_Init-TIM2-false-HAL-true,19-MX_LPTIM4_Init-LPTIM4-false-HAL-true,0-MX_CORTEX_M7_Init-CORTEX_M7-false-HAL-true,0-MX_VREFBUF_Init-VREFBUF-false-HAL-true,0-MX_PWR_Init-PWR-false-HAL-true
|
||||
RCC.ADCFreq_Value=96000000
|
||||
RCC.AHB12Freq_Value=275000000
|
||||
RCC.AHB4Freq_Value=275000000
|
||||
@@ -677,7 +702,5 @@ VP_TIM2_VS_ClockSourceINT.Mode=Internal
|
||||
VP_TIM2_VS_ClockSourceINT.Signal=TIM2_VS_ClockSourceINT
|
||||
VP_USB_DEVICE_VS_USB_DEVICE_CDC_HS.Mode=CDC_HS
|
||||
VP_USB_DEVICE_VS_USB_DEVICE_CDC_HS.Signal=USB_DEVICE_VS_USB_DEVICE_CDC_HS
|
||||
VP_VREFBUF_V_VREFBUF.Mode=ExternalMode
|
||||
VP_VREFBUF_V_VREFBUF.Signal=VREFBUF_V_VREFBUF
|
||||
board=custom
|
||||
rtos.0.ip=FREERTOS
|
||||
|
||||
@@ -116,9 +116,6 @@ include_directories(
|
||||
)
|
||||
|
||||
|
||||
add_subdirectory("lib")
|
||||
add_subdirectory("Application")
|
||||
|
||||
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/lib/nanopb/extra)
|
||||
find_package(Nanopb REQUIRED)
|
||||
include_directories(${NANOPB_INCLUDE_DIRS})
|
||||
@@ -132,13 +129,18 @@ add_library(PROTOS ${PROTO_SRCS} ${PROTO_HDRS})
|
||||
target_include_directories(PROTOS PUBLIC ${NANOPB_INCLUDE_DIRS} ${PROJECT_BINARY_DIR})
|
||||
include_directories(${PROJECT_BINARY_DIR})
|
||||
|
||||
add_subdirectory("Revision")
|
||||
add_subdirectory("lib")
|
||||
add_subdirectory("Application")
|
||||
|
||||
|
||||
# Add linked libraries
|
||||
# target_link_libraries(${CMAKE_PROJECT_NAME} PUBLIC protobuf-nanopb-static)
|
||||
|
||||
add_executable(${CMAKE_PROJECT_NAME})
|
||||
target_sources(${CMAKE_PROJECT_NAME} PUBLIC ${sources_SRCS})
|
||||
|
||||
target_link_libraries(${CMAKE_PROJECT_NAME} PUBLIC Tasks CLS CLS_BSP BSP EE24 INA219 ulog)
|
||||
target_link_libraries(${CMAKE_PROJECT_NAME} PUBLIC Tasks CLS CLS_BSP BSP EE24 INA219 ulog ram_loader Vehicle)
|
||||
#target_link_libraries(${CMAKE_PROJECT_NAME} PUBLIC PROTOS)
|
||||
target_link_libraries(${CMAKE_PROJECT_NAME} PUBLIC uart_driver)
|
||||
#target_link_libraries(${CMAKE_PROJECT_NAME} PUBLIC lwrb)
|
||||
|
||||
@@ -107,7 +107,7 @@ void Error_Handler(void);
|
||||
#define CLS_POWER_GPIO_Port GPIOE
|
||||
|
||||
/* USER CODE BEGIN Private defines */
|
||||
|
||||
void StartPowerTasks(void);
|
||||
/* USER CODE END Private defines */
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
||||
@@ -58,6 +58,8 @@ void DMA1_Stream0_IRQHandler(void);
|
||||
void DMA1_Stream1_IRQHandler(void);
|
||||
void DMA1_Stream2_IRQHandler(void);
|
||||
void DMA1_Stream3_IRQHandler(void);
|
||||
void DMA1_Stream4_IRQHandler(void);
|
||||
void ADC_IRQHandler(void);
|
||||
void FDCAN1_IT0_IRQHandler(void);
|
||||
void FDCAN2_IT0_IRQHandler(void);
|
||||
void FDCAN1_IT1_IRQHandler(void);
|
||||
|
||||
@@ -25,6 +25,7 @@
|
||||
/* USER CODE END 0 */
|
||||
|
||||
ADC_HandleTypeDef hadc1;
|
||||
DMA_HandleTypeDef hdma_adc1;
|
||||
|
||||
/* ADC1 init function */
|
||||
void MX_ADC1_Init(void)
|
||||
@@ -44,17 +45,17 @@ void MX_ADC1_Init(void)
|
||||
/** Common config
|
||||
*/
|
||||
hadc1.Instance = ADC1;
|
||||
hadc1.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV1;
|
||||
hadc1.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV2;
|
||||
hadc1.Init.Resolution = ADC_RESOLUTION_16B;
|
||||
hadc1.Init.ScanConvMode = ADC_SCAN_ENABLE;
|
||||
hadc1.Init.EOCSelection = ADC_EOC_SEQ_CONV;
|
||||
hadc1.Init.LowPowerAutoWait = DISABLE;
|
||||
hadc1.Init.ContinuousConvMode = ENABLE;
|
||||
hadc1.Init.NbrOfConversion = 3;
|
||||
hadc1.Init.NbrOfConversion = 4;
|
||||
hadc1.Init.DiscontinuousConvMode = DISABLE;
|
||||
hadc1.Init.ExternalTrigConv = ADC_SOFTWARE_START;
|
||||
hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
|
||||
hadc1.Init.ConversionDataManagement = ADC_CONVERSIONDATA_DR;
|
||||
hadc1.Init.ConversionDataManagement = ADC_CONVERSIONDATA_DMA_CIRCULAR;
|
||||
hadc1.Init.Overrun = ADC_OVR_DATA_PRESERVED;
|
||||
hadc1.Init.LeftBitShift = ADC_LEFTBITSHIFT_NONE;
|
||||
hadc1.Init.OversamplingMode = DISABLE;
|
||||
@@ -73,9 +74,9 @@ void MX_ADC1_Init(void)
|
||||
|
||||
/** Configure Regular Channel
|
||||
*/
|
||||
sConfig.Channel = ADC_CHANNEL_9;
|
||||
sConfig.Channel = ADC_CHANNEL_5;
|
||||
sConfig.Rank = ADC_REGULAR_RANK_1;
|
||||
sConfig.SamplingTime = ADC_SAMPLETIME_1CYCLE_5;
|
||||
sConfig.SamplingTime = ADC_SAMPLETIME_810CYCLES_5;
|
||||
sConfig.SingleDiff = ADC_SINGLE_ENDED;
|
||||
sConfig.OffsetNumber = ADC_OFFSET_NONE;
|
||||
sConfig.Offset = 0;
|
||||
@@ -87,7 +88,7 @@ void MX_ADC1_Init(void)
|
||||
|
||||
/** Configure Regular Channel
|
||||
*/
|
||||
sConfig.Channel = ADC_CHANNEL_5;
|
||||
sConfig.Channel = ADC_CHANNEL_8;
|
||||
sConfig.Rank = ADC_REGULAR_RANK_2;
|
||||
if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK)
|
||||
{
|
||||
@@ -96,11 +97,21 @@ void MX_ADC1_Init(void)
|
||||
|
||||
/** Configure Regular Channel
|
||||
*/
|
||||
sConfig.Channel = ADC_CHANNEL_9;
|
||||
sConfig.Rank = ADC_REGULAR_RANK_3;
|
||||
if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
/** Configure Regular Channel
|
||||
*/
|
||||
sConfig.Channel = ADC_CHANNEL_19;
|
||||
sConfig.Rank = ADC_REGULAR_RANK_4;
|
||||
if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN ADC1_Init 2 */
|
||||
|
||||
/* USER CODE END ADC1_Init 2 */
|
||||
@@ -162,6 +173,28 @@ void HAL_ADC_MspInit(ADC_HandleTypeDef* adcHandle)
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
|
||||
|
||||
/* ADC1 DMA Init */
|
||||
/* ADC1 Init */
|
||||
hdma_adc1.Instance = DMA1_Stream4;
|
||||
hdma_adc1.Init.Request = DMA_REQUEST_ADC1;
|
||||
hdma_adc1.Init.Direction = DMA_PERIPH_TO_MEMORY;
|
||||
hdma_adc1.Init.PeriphInc = DMA_PINC_DISABLE;
|
||||
hdma_adc1.Init.MemInc = DMA_MINC_ENABLE;
|
||||
hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
|
||||
hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
|
||||
hdma_adc1.Init.Mode = DMA_CIRCULAR;
|
||||
hdma_adc1.Init.Priority = DMA_PRIORITY_LOW;
|
||||
hdma_adc1.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
|
||||
if (HAL_DMA_Init(&hdma_adc1) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
__HAL_LINKDMA(adcHandle,DMA_Handle,hdma_adc1);
|
||||
|
||||
/* ADC1 interrupt Init */
|
||||
HAL_NVIC_SetPriority(ADC_IRQn, 5, 0);
|
||||
HAL_NVIC_EnableIRQ(ADC_IRQn);
|
||||
/* USER CODE BEGIN ADC1_MspInit 1 */
|
||||
|
||||
/* USER CODE END ADC1_MspInit 1 */
|
||||
@@ -191,6 +224,11 @@ void HAL_ADC_MspDeInit(ADC_HandleTypeDef* adcHandle)
|
||||
|
||||
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_0|GPIO_PIN_1);
|
||||
|
||||
/* ADC1 DMA DeInit */
|
||||
HAL_DMA_DeInit(adcHandle->DMA_Handle);
|
||||
|
||||
/* ADC1 interrupt Deinit */
|
||||
HAL_NVIC_DisableIRQ(ADC_IRQn);
|
||||
/* USER CODE BEGIN ADC1_MspDeInit 1 */
|
||||
|
||||
/* USER CODE END ADC1_MspDeInit 1 */
|
||||
|
||||
@@ -55,6 +55,9 @@ void MX_DMA_Init(void)
|
||||
/* DMA1_Stream3_IRQn interrupt configuration */
|
||||
NVIC_SetPriority(DMA1_Stream3_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(),5, 0));
|
||||
NVIC_EnableIRQ(DMA1_Stream3_IRQn);
|
||||
/* DMA1_Stream4_IRQn interrupt configuration */
|
||||
HAL_NVIC_SetPriority(DMA1_Stream4_IRQn, 5, 0);
|
||||
HAL_NVIC_EnableIRQ(DMA1_Stream4_IRQn);
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -36,6 +36,11 @@
|
||||
#include "BSP_INA.h"
|
||||
#include "BSP_POWER.h"
|
||||
#include "LightTask.h"
|
||||
#include "LightState.h"
|
||||
#include "BSP_GPIO.h"
|
||||
#include "BSP_ADC.h"
|
||||
#include "BSP_SDLogger.h"
|
||||
#include "Vehicle.h"
|
||||
/* USER CODE END Includes */
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
@@ -65,12 +70,20 @@ const osThreadAttr_t defaultTask_attributes = {
|
||||
.priority = (osPriority_t) osPriorityNormal,
|
||||
};
|
||||
|
||||
osThreadId_t waitForStartConfirmHandle;
|
||||
const osThreadAttr_t waitForStartConfirm_attributes = {
|
||||
.name = "waitForStartConfirm",
|
||||
.stack_size = 512 * 4,
|
||||
.priority = (osPriority_t) osPriorityNormal,
|
||||
};
|
||||
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* USER CODE BEGIN FunctionPrototypes */
|
||||
|
||||
/* USER CODE END FunctionPrototypes */
|
||||
|
||||
void StartDefaultTask(void *argument);
|
||||
void WaitForStartConfirm_Task(void *argument);
|
||||
|
||||
extern void MX_USB_DEVICE_Init(void);
|
||||
void MX_FREERTOS_Init(void); /* (MISRA C 2004 rule 8.1) */
|
||||
@@ -99,7 +112,6 @@ return __HAL_TIM_GetCounter(&htim2);
|
||||
*/
|
||||
void MX_FREERTOS_Init(void) {
|
||||
/* USER CODE BEGIN Init */
|
||||
BSP_POWER_Init();
|
||||
/* USER CODE END Init */
|
||||
|
||||
/* USER CODE BEGIN RTOS_MUTEX */
|
||||
@@ -123,14 +135,13 @@ void MX_FREERTOS_Init(void) {
|
||||
defaultTaskHandle = osThreadNew(StartDefaultTask, NULL, &defaultTask_attributes);
|
||||
|
||||
/* USER CODE BEGIN RTOS_THREADS */
|
||||
|
||||
waitForStartConfirmHandle = osThreadNew(WaitForStartConfirm_Task, NULL, &waitForStartConfirm_attributes);
|
||||
|
||||
ULOG_INFO("Setup UsbDataHandler");
|
||||
UsbDataHandler_Start();
|
||||
ULOG_INFO("Setup CanDataTask");
|
||||
CanDataTask_start();
|
||||
ULOG_INFO("Setup CLS");
|
||||
CLS_Init();
|
||||
ULOG_INFO("Setup LightTask");
|
||||
LightTask_start();
|
||||
/* USER CODE END RTOS_THREADS */
|
||||
|
||||
/* USER CODE BEGIN RTOS_EVENTS */
|
||||
@@ -177,6 +188,8 @@ void StartDefaultTask(void *argument)
|
||||
ULOG_INFO(output);
|
||||
}
|
||||
|
||||
BSP_SDLogger_Init(counter);
|
||||
|
||||
char INA_LOG[72];
|
||||
|
||||
/* Infinite loop */
|
||||
@@ -193,6 +206,18 @@ void StartDefaultTask(void *argument)
|
||||
snprintf(INA_LOG, sizeof(INA_LOG),"Voltage[mV] %.2f Current[mA] %d P[W]: %.2f", voltage_V, current, power_W);
|
||||
ULOG_INFO(INA_LOG);
|
||||
|
||||
|
||||
|
||||
// Read the battery voltage
|
||||
float bus = BSP_ADC_ReadBusValue();
|
||||
float dimm = BSP_ADC_ReadDimmerValue();
|
||||
|
||||
// Print the battery voltage and dimmer value
|
||||
char output[64];
|
||||
snprintf(output,64,"Bus voltage: %.2fV, Dimmer voltage: %.2fV", bus, dimm);
|
||||
ULOG_INFO(output);
|
||||
|
||||
|
||||
}
|
||||
/* USER CODE END StartDefaultTask */
|
||||
}
|
||||
@@ -200,5 +225,56 @@ void StartDefaultTask(void *argument)
|
||||
/* Private application code --------------------------------------------------*/
|
||||
/* USER CODE BEGIN Application */
|
||||
|
||||
void WaitForStartConfirm_Task(void *argument) {
|
||||
|
||||
// wait for up to 1 s and check if either K15 is set or we got a Car CAN message
|
||||
// once one of these is true, we can start the power systems.
|
||||
// after waiting for 1s, the system should shutdown / go to standby mode
|
||||
uint32_t tick = osKernelGetTickCount();
|
||||
uint32_t delayTime = 50; // Set the initial delay time to 50ms
|
||||
uint32_t maxDelayTime = 1000; // Set the maximum delay time to 1000ms
|
||||
|
||||
while(1) {
|
||||
osDelayUntil(tick);
|
||||
tick += delayTime;
|
||||
if(BSP_GPIO_K15isSet() || Vehicle_gotUnlockMessage()) {
|
||||
BSP_POWER_FullPowerMode();
|
||||
ULOG_INFO("Power systems started");
|
||||
osThreadExit();
|
||||
|
||||
while (1)
|
||||
{
|
||||
osDelay(1000);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
if(tick > maxDelayTime) {
|
||||
while (1)
|
||||
{
|
||||
ULOG_INFO("System in standby mode");
|
||||
BSP_POWER_EnterStandby();
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
osThreadExit();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// this is called from BSP_POWER_FullPowerMode
|
||||
// this function should start tasks that depend on the power being on
|
||||
void StartPowerTasks(void) {
|
||||
|
||||
ULOG_INFO("Setup CLS");
|
||||
CLS_Init();
|
||||
ULOG_INFO("Setup LightTask");
|
||||
LightTask_start();
|
||||
LightStateTask_start();
|
||||
|
||||
|
||||
}
|
||||
|
||||
/* USER CODE END Application */
|
||||
|
||||
|
||||
@@ -38,6 +38,10 @@
|
||||
/* USER CODE BEGIN Includes */
|
||||
#include "ulog.h"
|
||||
#include "stdio.h"
|
||||
#include "BSP_POWER.h"
|
||||
#include "BSP_GPIO.h"
|
||||
#include "BSP_ADC.h"
|
||||
#include "ram_loader.h"
|
||||
/* USER CODE END Includes */
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
@@ -57,6 +61,7 @@
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
|
||||
// define the magic number for the bootloader 8 bytes
|
||||
/* USER CODE BEGIN PV */
|
||||
uint8_t gCLS_DEVICE_ADDRESS = 0x11;
|
||||
/* USER CODE END PV */
|
||||
@@ -69,6 +74,7 @@ static void MPU_Config(void);
|
||||
void MX_FREERTOS_Init(void);
|
||||
/* USER CODE BEGIN PFP */
|
||||
void ULOG_SendLPUART(ulog_level_t level, char *msg);
|
||||
|
||||
/* USER CODE END PFP */
|
||||
|
||||
/* Private user code ---------------------------------------------------------*/
|
||||
@@ -84,6 +90,7 @@ int main(void)
|
||||
{
|
||||
/* USER CODE BEGIN 1 */
|
||||
|
||||
|
||||
/* USER CODE END 1 */
|
||||
|
||||
/* Enable I-Cache---------------------------------------------------------*/
|
||||
@@ -108,7 +115,7 @@ int main(void)
|
||||
PeriphCommonClock_Config();
|
||||
|
||||
/* USER CODE BEGIN SysInit */
|
||||
|
||||
BSP_POWER_WakeUp();
|
||||
/* USER CODE END SysInit */
|
||||
|
||||
/* Initialize all configured peripherals */
|
||||
@@ -129,15 +136,16 @@ int main(void)
|
||||
MX_TIM2_Init();
|
||||
MX_LPTIM4_Init();
|
||||
/* USER CODE BEGIN 2 */
|
||||
|
||||
BSP_GPIO_PeriperalsOn();
|
||||
BSP_POWER_Init();
|
||||
ULOG_INIT();
|
||||
ULOG_SUBSCRIBE(ULOG_SendLPUART,ULOG_DEBUG_LEVEL);
|
||||
ULOG_DEBUG("Setup Logger");
|
||||
HAL_GPIO_WritePin(Periph_Power_GPIO_Port,Periph_Power_Pin,GPIO_PIN_RESET);
|
||||
HAL_GPIO_WritePin(CLS_POWER_GPIO_Port, CLS_POWER_Pin, GPIO_PIN_SET);
|
||||
ULOG_DEBUG("Enable Power on CLS and Periph");
|
||||
gCLS_DEVICE_ADDRESS = 0x11;
|
||||
gCLS_DEVICE_ADDRESS = 0x11; // Address is set to master
|
||||
ULOG_DEBUG("Setting Global CLS address to 0b10001");
|
||||
ULOG_DEBUG("Init Kernel and start schedule");
|
||||
|
||||
/* USER CODE END 2 */
|
||||
|
||||
/* Init scheduler */
|
||||
@@ -281,6 +289,9 @@ void ULOG_SendLPUART(ulog_level_t level, char *msg) {
|
||||
HAL_UART_Transmit(&hlpuart1, (const uint8_t*)ulog_send_buffer, send_length, LOG_TIMEOUT);
|
||||
}
|
||||
|
||||
void DataClbk_cls_usb_JumpToBootloader(void* msg, uint32_t length) {
|
||||
RamLoader_LoadApplication();
|
||||
}
|
||||
/* USER CODE END 4 */
|
||||
|
||||
/* MPU Configuration */
|
||||
@@ -341,6 +352,13 @@ void Error_Handler(void)
|
||||
{
|
||||
/* USER CODE BEGIN Error_Handler_Debug */
|
||||
/* User can add his own implementation to report the HAL error return state */
|
||||
|
||||
ULOG_ERROR("Error Handler");
|
||||
osThreadId_t error_thread = osThreadGetId();
|
||||
if(error_thread != NULL) {
|
||||
const char * thread_name = osThreadGetName(error_thread);
|
||||
ULOG_ERROR("Error in thread: %s", thread_name);
|
||||
}
|
||||
__disable_irq();
|
||||
while (1)
|
||||
{
|
||||
|
||||
@@ -73,18 +73,6 @@ void HAL_MspInit(void)
|
||||
/* PendSV_IRQn interrupt configuration */
|
||||
HAL_NVIC_SetPriority(PendSV_IRQn, 15, 0);
|
||||
|
||||
/** Enable the VREF clock
|
||||
*/
|
||||
__HAL_RCC_VREF_CLK_ENABLE();
|
||||
|
||||
/** Disable the Internal Voltage Reference buffer
|
||||
*/
|
||||
HAL_SYSCFG_DisableVREFBUF();
|
||||
|
||||
/** Configure the internal voltage reference buffer high impedance mode
|
||||
*/
|
||||
HAL_SYSCFG_VREFBUF_HighImpedanceConfig(SYSCFG_VREFBUF_HIGH_IMPEDANCE_ENABLE);
|
||||
|
||||
/* USER CODE BEGIN MspInit 1 */
|
||||
|
||||
/* USER CODE END MspInit 1 */
|
||||
|
||||
@@ -56,6 +56,8 @@
|
||||
|
||||
/* External variables --------------------------------------------------------*/
|
||||
extern PCD_HandleTypeDef hpcd_USB_OTG_HS;
|
||||
extern DMA_HandleTypeDef hdma_adc1;
|
||||
extern ADC_HandleTypeDef hadc1;
|
||||
extern FDCAN_HandleTypeDef hfdcan1;
|
||||
extern FDCAN_HandleTypeDef hfdcan2;
|
||||
extern LPTIM_HandleTypeDef hlptim4;
|
||||
@@ -97,6 +99,21 @@ void HardFault_Handler(void)
|
||||
while (1)
|
||||
{
|
||||
/* USER CODE BEGIN W1_HardFault_IRQn 0 */
|
||||
|
||||
HAL_GPIO_TogglePin(DIO12_L2_GPIO_Port, DIO12_L2_Pin);
|
||||
|
||||
for (size_t i = 0; i < 10000000; i++)
|
||||
{
|
||||
__NOP();
|
||||
__NOP();
|
||||
__NOP();
|
||||
__NOP();
|
||||
__NOP();
|
||||
__NOP();
|
||||
__NOP();
|
||||
}
|
||||
|
||||
|
||||
/* USER CODE END W1_HardFault_IRQn 0 */
|
||||
}
|
||||
}
|
||||
@@ -112,6 +129,18 @@ void MemManage_Handler(void)
|
||||
while (1)
|
||||
{
|
||||
/* USER CODE BEGIN W1_MemoryManagement_IRQn 0 */
|
||||
HAL_GPIO_TogglePin(DIO12_L2_GPIO_Port, DIO12_L2_Pin);
|
||||
|
||||
for (size_t i = 0; i < 30000000; i++)
|
||||
{
|
||||
__NOP();
|
||||
__NOP();
|
||||
__NOP();
|
||||
__NOP();
|
||||
__NOP();
|
||||
__NOP();
|
||||
__NOP();
|
||||
}
|
||||
/* USER CODE END W1_MemoryManagement_IRQn 0 */
|
||||
}
|
||||
}
|
||||
@@ -250,6 +279,34 @@ void DMA1_Stream3_IRQHandler(void)
|
||||
/* USER CODE END DMA1_Stream3_IRQn 1 */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief This function handles DMA1 stream4 global interrupt.
|
||||
*/
|
||||
void DMA1_Stream4_IRQHandler(void)
|
||||
{
|
||||
/* USER CODE BEGIN DMA1_Stream4_IRQn 0 */
|
||||
|
||||
/* USER CODE END DMA1_Stream4_IRQn 0 */
|
||||
HAL_DMA_IRQHandler(&hdma_adc1);
|
||||
/* USER CODE BEGIN DMA1_Stream4_IRQn 1 */
|
||||
|
||||
/* USER CODE END DMA1_Stream4_IRQn 1 */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief This function handles ADC1 and ADC2 global interrupts.
|
||||
*/
|
||||
void ADC_IRQHandler(void)
|
||||
{
|
||||
/* USER CODE BEGIN ADC_IRQn 0 */
|
||||
|
||||
/* USER CODE END ADC_IRQn 0 */
|
||||
HAL_ADC_IRQHandler(&hadc1);
|
||||
/* USER CODE BEGIN ADC_IRQn 1 */
|
||||
|
||||
/* USER CODE END ADC_IRQn 1 */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief This function handles FDCAN1 interrupt 0.
|
||||
*/
|
||||
|
||||
27
Revision/CMakeLists.txt
Normal file
27
Revision/CMakeLists.txt
Normal file
@@ -0,0 +1,27 @@
|
||||
# Add your source files
|
||||
set(SOURCES
|
||||
|
||||
)
|
||||
|
||||
# Add your header files
|
||||
set(HEADERS
|
||||
version_info.h
|
||||
)
|
||||
|
||||
# Generate the version_info.c file as a build step
|
||||
add_custom_command(
|
||||
OUTPUT version_info.c
|
||||
COMMAND python3 ${CMAKE_CURRENT_SOURCE_DIR}/generate_version_info.py
|
||||
DEPENDS generate_version_info.py
|
||||
COMMENT "Generating version_info.c"
|
||||
)
|
||||
|
||||
# Add the generated file to the list of sources
|
||||
list(APPEND SOURCES ${CMAKE_CURRENT_BINARY_DIR}/version_info.c)
|
||||
|
||||
add_custom_target(generate_version_info DEPENDS version_info.c)
|
||||
|
||||
# Add the target
|
||||
add_library(Revision STATIC ${SOURCES} ${HEADERS})
|
||||
add_dependencies(Revision generate_version_info)
|
||||
target_include_directories(Revision PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
42
Revision/generate_version_info.py
Normal file
42
Revision/generate_version_info.py
Normal file
@@ -0,0 +1,42 @@
|
||||
import subprocess
|
||||
|
||||
def get_git_info():
|
||||
try:
|
||||
# Get the latest tag
|
||||
latest_tag = subprocess.check_output(['git', 'describe', '--abbrev=0', '--tags']).decode().strip()
|
||||
# Get the number of commits since the latest tag
|
||||
commit_count = subprocess.check_output(['git', 'rev-list', f'{latest_tag}..HEAD', '--count']).decode().strip()
|
||||
# Get the current branch
|
||||
branch = subprocess.check_output(['git', 'rev-parse', '--abbrev-ref', 'HEAD']).decode().strip()
|
||||
# Get the short hash of the latest commit
|
||||
commit_hash = subprocess.check_output(['git', 'rev-parse', '--short', 'HEAD']).decode().strip()
|
||||
|
||||
# Parse the version string
|
||||
version_parts = latest_tag.split('.')
|
||||
major, minor, patch = map(int, version_parts)
|
||||
|
||||
return major, minor, patch, int(commit_count), branch, commit_hash
|
||||
except Exception as e:
|
||||
print(f"Error: {e}")
|
||||
return None, None, None, None, None, None
|
||||
|
||||
def generate_c_file(filename, version_info):
|
||||
version_info_string = f"""\
|
||||
// This file is auto-generated by a Python script
|
||||
// Do not modify manually
|
||||
|
||||
#include "version_info.h"
|
||||
|
||||
__attribute__((section(".version"))) const firmware_version_t VERSION_INFO = {{ {version_info[0]}, {version_info[1]}, {version_info[2]}, {version_info[3]}, "{version_info[4]}", "{version_info[5]}" }};
|
||||
"""
|
||||
|
||||
with open(filename, 'w') as f:
|
||||
f.write(version_info_string)
|
||||
|
||||
if __name__ == "__main__":
|
||||
version_info = get_git_info()
|
||||
if version_info:
|
||||
generate_c_file("version_info.c", version_info)
|
||||
print("Version information has been written to version_info.c")
|
||||
else:
|
||||
print("Failed to retrieve Git information.")
|
||||
15
Revision/version_info.h
Normal file
15
Revision/version_info.h
Normal file
@@ -0,0 +1,15 @@
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
typedef struct firmware_version {
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
uint8_t patch;
|
||||
uint8_t count;
|
||||
char branch[50];
|
||||
char commit_hash[8];
|
||||
} firmware_version_t;
|
||||
|
||||
|
||||
extern const firmware_version_t VERSION_INFO;
|
||||
@@ -135,6 +135,15 @@ SECTIONS
|
||||
_edata = .; /* define a global symbol at data end */
|
||||
} >RAM_D1 AT> FLASH
|
||||
|
||||
.version :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sversion = .; /* create a global symbol at data start */
|
||||
*(.version) /* .data sections */
|
||||
*(.version*) /* .data* sections */
|
||||
} > FLASH
|
||||
|
||||
|
||||
/* Uninitialized data section */
|
||||
. = ALIGN(4);
|
||||
.bss :
|
||||
|
||||
@@ -43,8 +43,9 @@ _Min_Stack_Size = 0x400; /* required amount of stack */
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
RAM_EXEC (xrw) : ORIGIN = 0x24000000, LENGTH = 320K
|
||||
DTCMRAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
RAM_EXEC (xrw) : ORIGIN = 0x24000000, LENGTH = 319K
|
||||
RAM_NOINIT(xrw) : ORIGIN = 0x2404fc00, LENGTH = 1K
|
||||
DTCMRAM (xrw) : ORIGIN = 0x20000000, LENGTH = 127K
|
||||
ITCMRAM (xrw) : ORIGIN = 0x00000000, LENGTH = 64K
|
||||
RAM_D2 (xrw) : ORIGIN = 0x30000000, LENGTH = 32K
|
||||
RAM_D3 (xrw) : ORIGIN = 0x38000000, LENGTH = 16K
|
||||
@@ -161,6 +162,12 @@ SECTIONS
|
||||
. = ALIGN(8);
|
||||
} >DTCMRAM
|
||||
|
||||
|
||||
.noinit :
|
||||
{
|
||||
KEEP(*(.noinitdata))
|
||||
} >DTCMRAM2
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
|
||||
@@ -12,6 +12,8 @@
|
||||
|
||||
#include "AsyncComm.h"
|
||||
|
||||
#include "string.h"
|
||||
|
||||
#include "stm32h7xx_ll_dma.h"
|
||||
#include "stm32h7xx_ll_usart.h"
|
||||
|
||||
@@ -210,7 +212,7 @@ void usart_send_data(const uart_desc_t* uart, const void* data, size_t len) {
|
||||
* \param[in] str: String to send
|
||||
*/
|
||||
void usart_send_string(const uart_desc_t* uart, const char* str) {
|
||||
lwrb_write(&uart->data->tx_rb, str, strnlen(str, 255)); /* Write data to TX buffer for loopback */
|
||||
lwrb_write(&uart->data->tx_rb, str, strlen(str)); /* Write data to TX buffer for loopback */
|
||||
usart_start_tx_dma_transfer(uart); /* Then try to start transfer */
|
||||
}
|
||||
|
||||
|
||||
BIN
pinout.png
Normal file
BIN
pinout.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 293 KiB |
2
proto
2
proto
Submodule proto updated: 3937207744...4ff29f9d5b
13
tools/bootloader.py
Normal file
13
tools/bootloader.py
Normal file
@@ -0,0 +1,13 @@
|
||||
from usb_pb2 import PackageType, JumpToBootloader
|
||||
from vcp_driver import *
|
||||
|
||||
if __name__ == "__main__":
|
||||
ser = setup_connection()
|
||||
# Create a message
|
||||
request = JumpToBootloader()
|
||||
request.magic = 0xdeadbeef
|
||||
# Serialize the request to a bytearray
|
||||
request_data = request.SerializeToString()
|
||||
|
||||
# Send the request
|
||||
send_package(PackageType.JUMP_TO_BOOTLOADER, request_data, ser)
|
||||
@@ -30,7 +30,7 @@ def make_header(typeid: PackageType, length: int) -> bytearray:
|
||||
struct_format = '<HHB' # '<' for little-endian, 'H' for uint16_t, 'B' for uint8_t
|
||||
# Calculate the check byte as the sum of length and type
|
||||
typeidint = int(typeid)
|
||||
check = (length & 0xFF) + ((length >> 8) & 0xFF) + (typeidint & 0xFF) + ((typeidint >> 8) & 0xFF)
|
||||
check = ((length & 0xFF) + ((length >> 8) & 0xFF) + (typeidint & 0xFF) + ((typeidint >> 8) & 0xFF) ) & 0xff
|
||||
packed_data = struct.pack(struct_format, length, typeid, check)
|
||||
return packed_data
|
||||
|
||||
|
||||
20
tools/set_device_type.py
Normal file
20
tools/set_device_type.py
Normal file
@@ -0,0 +1,20 @@
|
||||
from cls_device_pb2 import UpdateDeviceSettings, Type, Position
|
||||
from usb_pb2 import PackageType
|
||||
from vcp_driver import *
|
||||
|
||||
if __name__ == "__main__":
|
||||
ser = setup_connection()
|
||||
# Create a message
|
||||
request = UpdateDeviceSettings()
|
||||
request.device = 0
|
||||
request.type = Type.COMMING_HOME
|
||||
request.position.append(Position.LEFT)
|
||||
request.position.append(Position.CENTER)
|
||||
# Serialize the request to a bytearray
|
||||
request_data = request.SerializeToString()
|
||||
|
||||
|
||||
print(request)
|
||||
print(request_data)
|
||||
# Send the request
|
||||
send_package(PackageType.UPDATE_DEVICE_SETTINGS, request_data, ser)
|
||||
47
tools/test_get_theme.py
Normal file
47
tools/test_get_theme.py
Normal file
@@ -0,0 +1,47 @@
|
||||
import serial
|
||||
import struct
|
||||
from google.protobuf.message import DecodeError
|
||||
from serial.tools import list_ports
|
||||
|
||||
from light_pb2 import RequestThemeSetting, Theme, ThemeSettings
|
||||
from usb_pb2 import PackageType
|
||||
from vcp_driver import *
|
||||
|
||||
if __name__ == "__main__":
|
||||
ser = setup_connection()
|
||||
|
||||
request = RequestThemeSetting()
|
||||
request.deviceId = 0
|
||||
request.theme = 1
|
||||
print("send request")
|
||||
print(request)
|
||||
|
||||
request_data = request.SerializeToString()
|
||||
send_package(PackageType.LIGHT_REQUEST_THEME, request_data, ser)
|
||||
|
||||
|
||||
print("wait for response")
|
||||
# Read the header from the serial port
|
||||
response_header = ser.read(5) # assuming the header is 5 bytes long
|
||||
|
||||
# Unpack the header to get the length and type
|
||||
length, typeid, check = struct.unpack('<HHB', response_header)
|
||||
|
||||
print(length, typeid, check)
|
||||
|
||||
# Check if the type is RESPONSE_DEVICE_LIST
|
||||
if typeid == PackageType.LIGHT_SETTING_THEME:
|
||||
# Read the response data from the serial port
|
||||
response_data = ser.read(length)
|
||||
|
||||
# Try to parse the data as a ResponseDeviceList message
|
||||
try:
|
||||
response = ThemeSettings.FromString(response_data)
|
||||
|
||||
except DecodeError:
|
||||
# If we get a DecodeError, it means the data we read is not a valid
|
||||
# ResponseDeviceList message. Ignore it and continue reading.
|
||||
pass
|
||||
|
||||
|
||||
print(response)
|
||||
71
tools/upload_firmware.py
Normal file
71
tools/upload_firmware.py
Normal file
@@ -0,0 +1,71 @@
|
||||
import hmac
|
||||
import hashlib
|
||||
import sys
|
||||
from pathlib import Path
|
||||
import requests
|
||||
import subprocess
|
||||
import base64
|
||||
|
||||
def load_secret_key(keyb64: str):
|
||||
# Decode the base64 encoded key
|
||||
decoded_key = base64.b64decode(keyb64)
|
||||
|
||||
return decoded_key
|
||||
|
||||
def compute_hmac(file_path, secret_key):
|
||||
"""Compute the HMAC of a file using HMAC-SHA256."""
|
||||
hmac_obj = hmac.new(secret_key, digestmod=hashlib.sha256)
|
||||
with open(file_path, 'rb') as f:
|
||||
while chunk := f.read(4096):
|
||||
hmac_obj.update(chunk)
|
||||
return hmac_obj.hexdigest()
|
||||
|
||||
def upload_file(url, file_path, secret_key):
|
||||
"""Upload a file to the server with an HMAC signature."""
|
||||
# Compute HMAC of the file
|
||||
signature = compute_hmac(file_path, secret_key)
|
||||
print(signature)
|
||||
# Prepare headers
|
||||
headers = {'X-Signature': signature}
|
||||
|
||||
# Read file and prepare files dictionary for request
|
||||
with open(file_path, 'rb') as f:
|
||||
files = {'file': (Path(file_path).name, f)}
|
||||
response = requests.post(url, files=files, headers=headers)
|
||||
|
||||
return response
|
||||
|
||||
|
||||
def get_short_git_commit_hash():
|
||||
try:
|
||||
# Run the Git command to get the short commit hash
|
||||
result = subprocess.run(['git', 'rev-parse', '--short', 'HEAD'], stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True, check=True)
|
||||
# Extract and return the commit hash
|
||||
return result.stdout.strip()
|
||||
except subprocess.CalledProcessError as e:
|
||||
print(f"Error getting Git commit hash: {e}")
|
||||
return None
|
||||
|
||||
if __name__ == "__main__":
|
||||
url = "https://fw.revwal.de/master/upload" # Adjust this to your server's URL
|
||||
|
||||
|
||||
fw_path = "build/CLS_Master.bin" # Path to the file you want to upload
|
||||
|
||||
# Get the Git commit hash
|
||||
commit_hash = get_short_git_commit_hash()
|
||||
if commit_hash is None:
|
||||
print("Error: Could not get Git commit hash")
|
||||
sys.exit(1)
|
||||
|
||||
# replace the file name with the commit hash
|
||||
file_path = fw_path.replace("CLS_Master", commit_hash)
|
||||
|
||||
# copy the file to the new name
|
||||
subprocess.run(['cp', fw_path, file_path])
|
||||
|
||||
|
||||
secret_key = load_secret_key(sys.argv[1])
|
||||
|
||||
response = upload_file(url, file_path, secret_key)
|
||||
print(f"Server response: {response.text}")
|
||||
Reference in New Issue
Block a user