Da Vinci Firmware 1
Firmware for the DaVinci-M rocket avionics board.
Loading...
Searching...
No Matches
main.c File Reference

: Main program body for the flight computer. Initializes hardware, RTOS, and starts all application tasks. More...

#include "main.h"
#include "cmsis_os.h"
#include "kalmanFilter.h"
#include "mekf.h"
#include "OptimalAngle.h"
#include "z_qflash_W25QXXX.h"
#include "attitude_estimation.h"
#include "buzzer.h"
#include "profiler.h"
Include dependency graph for main.c:

Go to the source code of this file.

Data Structures

struct  Linear_IMU_Package
 Represents a 3-axis linear acceleration data packet. More...
 
struct  Data_Package_no_Linear_IMU
 A comprehensive sensor data packet, excluding linear acceleration. More...
 
struct  Data_Package_For_Marconi
 Data packet formatted for transmission to the Marconi ground station. More...
 

Macros

#define SENSOR_FLAG   (1U << 0)
 
#define MPC_FLAG   (1U << 1)
 
#define RECEIVED_VEL_FLAG   (1U << 2)
 
#define KALMAN_FLAG   (1U << 3)
 
#define FSM_FLAG   (1U << 4)
 
#define UART_RX_ERROR_FLAG   (1U << 5)
 

Functions

static double P[] __attribute__ ((aligned(4)))
 
void SystemClock_Config (void)
 System Clock Configuration.
 
void PeriphCommonClock_Config (void)
 Peripherals Common Clock Configuration.
 
static void MPU_Config (void)
 
static void MX_GPIO_Init (void)
 GPIO Initialization Function.
 
static void MX_DMA_Init (void)
 
static void MX_MDMA_Init (void)
 
static void MX_USART1_UART_Init (void)
 USART1 Initialization Function.
 
static void MX_USB_OTG_FS_PCD_Init (void)
 USB_OTG_FS Initialization Function.
 
static void MX_FDCAN1_Init (void)
 FDCAN1 Initialization Function.
 
static void MX_QUADSPI_Init (void)
 QUADSPI Initialization Function.
 
static void MX_SPI1_Init (void)
 SPI1 Initialization Function.
 
static void MX_SPI2_Init (void)
 SPI2 Initialization Function.
 
static void MX_SPI3_Init (void)
 SPI3 Initialization Function.
 
static void MX_TIM2_Init (void)
 TIM2 Initialization Function.
 
static void MX_TIM15_Init (void)
 TIM15 Initialization Function.
 
static void MX_UART4_Init (void)
 UART4 Initialization Function.
 
static void MX_ADC1_Init (void)
 ADC1 Initialization Function.
 
static void MX_ADC2_Init (void)
 ADC2 Initialization Function.
 
static void MX_ADC3_Init (void)
 ADC3 Initialization Function.
 
static void MX_TIM7_Init (void)
 TIM7 Initialization Function.
 
static void MX_TIM6_Init (void)
 TIM6 Initialization Function.
 
static void MX_TIM13_Init (void)
 TIM13 Initialization Function.
 
void StartSensor_Task (void *argument)
 Function implementing the Sensor_Task thread.
 
void StartFSM (void *argument)
 Function implementing the FSM thread.
 
void StartKalman_mkf (void *argument)
 Function implementing the Kalman_mkf thread.
 
void StartMPC_Task (void *argument)
 Function implementing the MPC_Task thread.
 
void StartReceiveVel_Task (void *argument)
 Function implementing the ReceiveVel_Task thread.
 
void HAL_UART_RxCpltCallback (UART_HandleTypeDef *huart)
 
void HAL_UART_ErrorCallback (UART_HandleTypeDef *huart)
 
int main (void)
 The application entry point.
 
void HAL_TIM_PeriodElapsedCallback (TIM_HandleTypeDef *htim)
 Period elapsed callback in non blocking mode.
 
void Error_Handler (void)
 This function is executed in case of error occurrence.
 

Variables

ADC_HandleTypeDef hadc1
 
ADC_HandleTypeDef hadc2
 
ADC_HandleTypeDef hadc3
 
FDCAN_HandleTypeDef hfdcan1
 
QSPI_HandleTypeDef hqspi
 HAL QSPI handle for the external flash memory.
 
MDMA_HandleTypeDef hmdma_quadspi_fifo_th
 
SPI_HandleTypeDef hspi1
 
SPI_HandleTypeDef hspi2
 HAL SPI handle for Sensor Bus 1 (e.g., IMU, Baro).
 
SPI_HandleTypeDef hspi3
 HAL SPI handle for Sensor Bus 2 (e.g., secondary sensors).
 
TIM_HandleTypeDef htim2
 
TIM_HandleTypeDef htim6
 
TIM_HandleTypeDef htim7
 
TIM_HandleTypeDef htim13
 
TIM_HandleTypeDef htim15
 HAL Timer handle for the buzzer PWM.
 
UART_HandleTypeDef huart4
 
UART_HandleTypeDef huart1
 
DMA_HandleTypeDef hdma_usart1_rx
 
DMA_HandleTypeDef hdma_usart1_tx
 
PCD_HandleTypeDef hpcd_USB_OTG_FS
 
osThreadId_t Sensor_TaskHandle
 
const osThreadAttr_t Sensor_Task_attributes
 
osThreadId_t FSMHandle
 
const osThreadAttr_t FSM_attributes
 
osThreadId_t Kalman_mkfHandle
 
const osThreadAttr_t Kalman_mkf_attributes
 
osThreadId_t MPC_TaskHandle
 
const osThreadAttr_t MPC_Task_attributes
 
osThreadId_t ReceiveVel_TaskHandle
 
const osThreadAttr_t ReceiveVel_Task_attributes
 
flight_phase_t flight_phase = CALIBRATING
 
flight_fsm_t flight_state
 
buzzer_tbz ={0}
 
struct bmp3_dev bmp390_1 = {0}
 
struct bmp3_dev bmp390_2 = {0}
 
stmdev_ctx_t imu_1 = {0}
 
stmdev_ctx_t imu_2 = {0}
 
struct bmp3_data barometer_data_1 = {-1, -1}
 
struct bmp3_data barometer_data_2 = {-1, -1}
 
static int16_t data_raw_angular_rate_1 [3] = {0}
 
static int16_t data_raw_acceleration_1 [3] = {0}
 
static float_t acceleration_mg_1 [3] = {0}
 
static float_t angular_rate_mdps_1 [3] = {0}
 
stmdev_ctx_t lis2mdl_dev_ctx
 
stmdev_ctx_t lis2mdl_dev_ctx_2
 
int16_t raw_mag_data [3]
 
float_t altitude = 0.0
 
float_t velocity = 0.0
 
float_t Pressure_1 = 0.0
 
float_t Temperature_1 = 0.0
 
Data_Package_For_Marconi message = {0}
 
uint8_t drogue = 0
 Status flag for the drogue parachute pyro channel.
 
uint8_t mainp = 0
 Status flag for the main parachute pyro channel.
 
float max_alt = 0
 
float max_vel =0
 
bool first_measure = true
 
double q [] = {0.7061377159181262, -0.03700710955926802, 0.03700710955926802, -0.7061377159181262}
 
double beta [] = {0, 0, 0}
 
double omega [] = {3.760494829166693e-05, -1.4118446451604494e-07, 0.0003572545679652845}
 
double b_B [] = {0,0,0}
 
double q_new [] = {0,0,0,0}
 
double beta_new [] = {0,0,0}
 
double P_2 [] = {5,0,0,5}
 
double z [] = {5003.24140978,329.14706741}
 
double alpha = 0.0
 
double a_m = -12.09
 
double Ts = 0.01
 
const double Q [] = {2769,1846,1846,1385}
 
const double R [] = {5.54e-3,0,0,0.121}
 
double x_est [] = {5000,330}
 
double time_step = 0.5
 
double sim_time_step = 0.5
 
double current_delta = 0
 
double target_apogee = 8900
 
double tolerance = 1
 
double tilt_angle = 0.24556997475102937
 
const double mach_states [] = {0.1,0.2,0.3,0.4,0.5}
 
const double deployment_states [] ={0.0,40.5000,69.7500,94.5000,108.0000,173.8000}
 
static double cd_table [] ={0.4510,0.3940,0.3610,0.3390,0.3320,0.5430,0.4960,0.4690,0.4250,0.4170,0.6240,0.5790,0.5550,0.5350,0.5280, 0.7450,0.7140,0.6780,0.6760,0.6720,0.7520,0.7230,0.6980,0.6850,0.6820,0.85,0.81,0.8,0.8,0.8}
 
double z_component = 0.0
 
TaskHandle_t xReceived_VelHandle = NULL
 
TaskHandle_t xMPCTaskHandle = NULL
 
TaskHandle_t xSensorsTaskHandle = NULL
 
TaskHandle_t xKalman_TaskHandle = NULL
 
osThreadId_t xReceived_VelID =NULL
 
osThreadId_t xMPCTaskID = NULL
 
osThreadId_t xSensorsTaskID = NULL
 
osThreadId_t xKalman_TaskID = NULL
 
uint8_t vel [4]
 
float gps_vel = 0.0f
 
uint8_t array [63]
 
bool gnss_flag = false
 
bool flag_kf = false
 RTOS event flag to trigger the Kalman Filter task.
 
bool flag_attitude = false
 RTOS event flag to trigger the attitude estimation task.
 
bool flag_MPC = false
 RTOS event flag to trigger the MPC task.
 
bool flag_flash = false
 RTOS event flag to trigger the data logging task.
 
uint32_t flash_address = 4
 
uint8_t data_buffer [4224] ={0}
 
uint8_t cpy_buffer [2112] = {0}
 
uint32_t num_of_lin_acc_saved = 0
 
uint32_t num_of_saved_rest_packages = 0
 
uint32_t num_of_saved_rest_packages_locked = 0
 
uint32_t num_of_lin_acc_saved_flash = 0
 
uint32_t num_of_saved_rest_packages_flash = 0
 
float initial_flag_value = 0.0f
 
float Vin =0
 
float Vr =0
 
uint32_t adcVal = 0
 
note_t Partition []
 

Detailed Description

: Main program body for the flight computer. Initializes hardware, RTOS, and starts all application tasks.

Author
: Francesco Abate, Giorgio Montesi, Tommaso Gualtierotti
Attention

Copyright (c) 2025 STMicroelectronics. All rights reserved.

This software is licensed under terms that can be found in the LICENSE file in the root directory of this software component. If no LICENSE file comes with this software, it is provided AS-IS.

Definition in file main.c.

Macro Definition Documentation

◆ FSM_FLAG

#define FSM_FLAG   (1U << 4)

Definition at line 287 of file main.c.

◆ KALMAN_FLAG

#define KALMAN_FLAG   (1U << 3)

Definition at line 286 of file main.c.

◆ MPC_FLAG

#define MPC_FLAG   (1U << 1)

Definition at line 284 of file main.c.

◆ RECEIVED_VEL_FLAG

#define RECEIVED_VEL_FLAG   (1U << 2)

Definition at line 285 of file main.c.

◆ SENSOR_FLAG

#define SENSOR_FLAG   (1U << 0)

Definition at line 283 of file main.c.

◆ UART_RX_ERROR_FLAG

#define UART_RX_ERROR_FLAG   (1U << 5)

Definition at line 288 of file main.c.

Function Documentation

◆ __attribute__()

static double P[] __attribute__ ( (aligned(4))  )
static

◆ Error_Handler()

void Error_Handler ( void  )

This function is executed in case of error occurrence.

Return values
None

Definition at line 2042 of file main.c.

2043{
2044 /* USER CODE BEGIN Error_Handler_Debug */
2045 /* User can add his own implementation to report the HAL error return state */
2046 __disable_irq();
2047 while (1)
2048 {
2049 }
2050 /* USER CODE END Error_Handler_Debug */
2051}

Referenced by buzzer_init(), HAL_FDCAN_MspInit(), HAL_PCD_MspInit(), HAL_QSPI_MspInit(), HAL_SPI_MspInit(), HAL_UART_MspInit(), main(), MX_ADC1_Init(), MX_ADC2_Init(), MX_ADC3_Init(), MX_FDCAN1_Init(), MX_QUADSPI_Init(), MX_SPI1_Init(), MX_SPI2_Init(), MX_SPI3_Init(), MX_TIM13_Init(), MX_TIM15_Init(), MX_TIM2_Init(), MX_TIM6_Init(), MX_TIM7_Init(), MX_UART4_Init(), MX_USART1_UART_Init(), MX_USB_OTG_FS_PCD_Init(), PeriphCommonClock_Config(), StartReceiveVel_Task(), and SystemClock_Config().

Here is the caller graph for this function:

◆ HAL_TIM_PeriodElapsedCallback()

void HAL_TIM_PeriodElapsedCallback ( TIM_HandleTypeDef *  htim)

Period elapsed callback in non blocking mode.

Note
This function is called when TIM4 interrupt took place, inside HAL_TIM_IRQHandler(). It makes a direct call to HAL_IncTick() to increment a global variable "uwTick" used as application time base.
Parameters
htim: TIM handle
Return values
None

Definition at line 2006 of file main.c.

2007{
2008 /* USER CODE BEGIN Callback 0 */
2009
2010 /* USER CODE END Callback 0 */
2011 if (htim->Instance == TIM4)
2012 {
2013 HAL_IncTick();
2014 }
2015 /* USER CODE BEGIN Callback 1 */
2016 if (htim->Instance == TIM7) { //500 ms
2017 if (HAL_UART_GetState(&huart1) == HAL_UART_STATE_READY || HAL_UART_GetState(&huart1) == HAL_UART_STATE_BUSY_RX) // Ready or only busy receiving
2018 {
2019
2020 osThreadFlagsSet(MPC_TaskHandle, MPC_FLAG);
2021 }
2022 }
2023
2024 if (htim->Instance == TIM6) { // <<< Check for the 4kHz (0.25ms) timer
2025
2026 osThreadFlagsSet(Sensor_TaskHandle, SENSOR_FLAG);
2027
2028
2029 }
2030
2031 if(htim->Instance == TIM13){ // 10ms timer for the FSM
2032 osThreadFlagsSet(FSMHandle, FSM_FLAG);
2033 }
2034
2035 /* USER CODE END Callback 1 */
2036}
osThreadId_t Sensor_TaskHandle
Definition main.c:79
UART_HandleTypeDef huart1
Definition main.c:72
#define MPC_FLAG
Definition main.c:284
#define SENSOR_FLAG
Definition main.c:283
osThreadId_t MPC_TaskHandle
Definition main.c:100
osThreadId_t FSMHandle
Definition main.c:86
#define FSM_FLAG
Definition main.c:287

References FSM_FLAG, FSMHandle, huart1, MPC_FLAG, MPC_TaskHandle, SENSOR_FLAG, and Sensor_TaskHandle.

◆ HAL_UART_ErrorCallback()

void HAL_UART_ErrorCallback ( UART_HandleTypeDef *  huart)

Definition at line 379 of file main.c.

379 {
380 if (huart->Instance == USART1){
381 uint32_t error = HAL_UART_GetError(huart);
382 __HAL_UART_CLEAR_OREFLAG(huart);
383 HAL_UART_AbortReceive(huart); // This should handle associated DMA abort too
384
385
386 if (ReceiveVel_TaskHandle != NULL) { // Ensure task handle is valid
387 osThreadFlagsSet(ReceiveVel_TaskHandle, UART_RX_ERROR_FLAG);
388 }
389 }
390}
#define NULL
Definition bmp3_defs.h:88
#define UART_RX_ERROR_FLAG
Definition main.c:288
osThreadId_t ReceiveVel_TaskHandle
Definition main.c:107

References NULL, ReceiveVel_TaskHandle, and UART_RX_ERROR_FLAG.

◆ HAL_UART_RxCpltCallback()

void HAL_UART_RxCpltCallback ( UART_HandleTypeDef *  huart)

Definition at line 370 of file main.c.

370 {
371 if (huart->Instance == USART1) {
372
373 osThreadFlagsSet(ReceiveVel_TaskHandle, RECEIVED_VEL_FLAG);
374
375
376 }
377}
#define RECEIVED_VEL_FLAG
Definition main.c:285

References RECEIVED_VEL_FLAG, and ReceiveVel_TaskHandle.

◆ main()

int main ( void  )

The application entry point.

Return values
int

Definition at line 399 of file main.c.

400{
401
402 /* USER CODE BEGIN 1 */
403
404 /* USER CODE END 1 */
405
406 /* MPU Configuration--------------------------------------------------------*/
407 MPU_Config();
408
409 /* MCU Configuration--------------------------------------------------------*/
410
411 /* Reset of all peripherals, Initializes the Flash interface and the Systick. */
412 HAL_Init();
413
414 /* USER CODE BEGIN Init */
415
416 /* USER CODE END Init */
417
418 /* Configure the system clock */
420
421 /* Configure the peripherals common clocks */
423
424 /* USER CODE BEGIN SysInit */
425 initDWT();
426 /* USER CODE END SysInit */
427
428 /* Initialize all configured peripherals */
429 MX_GPIO_Init();
430 MX_DMA_Init();
431 MX_MDMA_Init();
436 MX_SPI1_Init();
437 MX_SPI2_Init();
438 MX_SPI3_Init();
439 MX_TIM2_Init();
442 MX_ADC1_Init();
443 MX_ADC2_Init();
444 MX_ADC3_Init();
445 MX_TIM7_Init();
446 MX_TIM6_Init();
448 /* USER CODE BEGIN 2 */
449 //----------------------------------------------------------------------------------------------------------------------------------------
450//TODO CODICE PER INIZIALIZZARE I MAGNETOMETRI, COMMENTATO FINQUANDO AVREMO UNA SCHEDA CON I MAGNETOMETRI GIRATI NEL VERSO GIUSTO
451 //uint8_t result = lis2mdl_init(&lis2mdl_dev_ctx);
452 //uint8_t result_7 = lis2mdl_init_2(&lis2mdl_dev_ctx_2);
453//TODO: SETTAGGIO DELL'SPI IN 4WAY PIUTTOSTO CHE 3WAY, SERVE A GESTIRE LA QUESTIONE DEL REGISTRO DEL MAGNETOMETRO, SE GIA STA SU 4WAY NO NEED
454 // HAL_SPI_DeInit(&hspi2);
455 // HAL_Delay(10);
456 // hspi2.Init.Direction = SPI_DIRECTION_2LINES;
457 // HAL_SPI_Init(&hspi2);
458 //----------------------------------------------------------------------------------------------------------------------------------------
459
460 LED_ON(GPIO_LED_FLASH_GPIO_Port, GPIO_LED_FLASH_Pin);
461
462
463
464 IMU_CS_HIGH;
465 MAG_CS_HIGH;
466 BMP390_CS_HIGH;
467
468 HAL_Delay(100);
469
470
471 uint8_t result_4 = init_bmp390_B(&bmp390_2);
472
474
475 //TODO: the result of the init of the backup of the imu and of the barometer are currently not checked, we can add a very similar snippet of code to the lines 494 to 498 but using a different LED
476
477 uint8_t result_3 = init_bmp390_p(&bmp390_1);
478
480
481
482 if(result_1 != 0 || result_3 != 0){
483 LED_ON(GPIO_LED2_GPIO_Port, GPIO_LED2_Pin);
484 }
485
486 calibrateIMU(&imu_1, 1000, HWOFFSET);
487 calibrateIMU(&imu_2, 1000, HWOFFSET);
488
489
490 buzzer_init(bz, &htim15, TIM_CHANNEL_2);
491
492 musica_maestro(bz,Partition,sizeof(Partition)/sizeof(note_t));
493
494
495 if (QFlash_Init() != 0) {
496 // Handle initialization error
498 }
499
500
501 uint8_t small_buffer[4];
502 if (QFlash_Read(0, (uint8_t*)small_buffer, 4) != HAL_OK) {
503 // Handle read error
505 }
506
507 memcpy(&initial_flag_value, (uint8_t*)small_buffer, 4);
508
509 if(initial_flag_value != 1.0) {
510 HAL_TIM_PWM_Start(&htim15, TIM_CHANNEL_2);
511
512 for(int i = 0; i < 10; i++) {
513 __HAL_TIM_SET_PRESCALER(&htim15, NOTE_B5);
514 HAL_Delay(100);
515 __HAL_TIM_SET_PRESCALER(&htim15, 0);
516 HAL_Delay(100);
517 __HAL_TIM_SET_PRESCALER(&htim15, NOTE_B5);
518 HAL_Delay(100);
519 __HAL_TIM_SET_PRESCALER(&htim15, 0);
520
521 HAL_Delay(700);
522 }
523
524 __HAL_TIM_SET_PRESCALER(&htim15, NOTE_B5);
525 HAL_Delay(1000);
526
527 HAL_TIM_PWM_Stop(&htim15, TIM_CHANNEL_2);
528
530
531 HAL_TIM_PWM_Start(&htim15, TIM_CHANNEL_2);
532
533 __HAL_TIM_SET_PRESCALER(&htim15, NOTE_B5);
534 HAL_Delay(700);
535
536 HAL_TIM_PWM_Stop(&htim15, TIM_CHANNEL_2);
537 }
538
539 LED_ON(GPIO_LED1_GPIO_Port, GPIO_LED1_Pin);
541
542
543
544 /* USER CODE END 2 */
545
546 /* Init scheduler */
547 osKernelInitialize();
548
549 /* USER CODE BEGIN RTOS_MUTEX */
550 /* add mutexes, ... */
551 /* USER CODE END RTOS_MUTEX */
552
553 /* USER CODE BEGIN RTOS_SEMAPHORES */
554 /* add semaphores, ... */
555 /* USER CODE END RTOS_SEMAPHORES */
556
557 /* USER CODE BEGIN RTOS_TIMERS */
558 /* start timers, add new ones, ... */
559 /* USER CODE END RTOS_TIMERS */
560
561 /* USER CODE BEGIN RTOS_QUEUES */
562 /* add queues, ... */
563 /* USER CODE END RTOS_QUEUES */
564
565 /* Create the thread(s) */
566 /* creation of Sensor_Task */
568
569 /* creation of FSM */
570 FSMHandle = osThreadNew(StartFSM, NULL, &FSM_attributes);
571
572 /* creation of Kalman_mkf */
574
575 /* creation of MPC_Task */
577
578 /* creation of ReceiveVel_Task */
580
581 /* USER CODE BEGIN RTOS_THREADS */
582 /* add threads, ... */
583 /* USER CODE END RTOS_THREADS */
584
585 /* USER CODE BEGIN RTOS_EVENTS */
586 /* add events, ... */
587
588 /* USER CODE END RTOS_EVENTS */
589
590 /* Start scheduler */
591 osKernelStart();
592
593 /* We should never get here as control is now taken by the scheduler */
594
595 /* Infinite loop */
596 /* USER CODE BEGIN WHILE */
597
598 while (1)
599 {
600 /* USER CODE END WHILE */
601
602 /* USER CODE BEGIN 3 */
603 }
604 /* USER CODE END 3 */
605}
#define NOTE_B5
Note B, 5th octave.
Definition buzzer.h:58
void musica_maestro(buzzer_t *bz, const note_t *partition, uint16_t melody_length)
Plays a melody by iterating through an array of notes.
Definition buzzer.c:38
void buzzer_init(buzzer_t *bz, TIM_HandleTypeDef *htim, uint32_t channel)
Initializes the buzzer object and its associated timer hardware.
Definition buzzer.c:23
TIM_HandleTypeDef htim15
HAL Timer handle for the buzzer PWM.
Definition main.c:69
int8_t calibrateIMU(stmdev_ctx_t *imu, uint16_t iterationNum, OFFSET_TYPE type)
Calibrates the IMU by calculating sensor offsets.
Definition utilities.c:366
int8_t init_imup(stmdev_ctx_t *imu, lsm6dso32_fs_xl_t acc_full_scale, lsm6dso32_fs_g_t gyro_full_scale, lsm6dso32_odr_xl_t acc_output_data_rate, lsm6dso32_odr_g_t gyro_output_data_rate)
Initializes the primary IMU (LSM6DSO32).
Definition utilities.c:193
int8_t init_imuB(stmdev_ctx_t *imu, lsm6dso32_fs_xl_t acc_full_scale, lsm6dso32_fs_g_t gyro_full_scale, lsm6dso32_odr_xl_t acc_output_data_rate, lsm6dso32_odr_g_t gyro_output_data_rate)
Initializes the backup IMU (LSM6DSO32).
Definition utilities.c:665
@ HWOFFSET
Use the hardware's internal offset registers.
Definition utilities.h:61
void StartKalman_mkf(void *argument)
Function implementing the Kalman_mkf thread.
Definition main.c:1758
void StartSensor_Task(void *argument)
Function implementing the Sensor_Task thread.
Definition main.c:1588
void StartMPC_Task(void *argument)
Function implementing the MPC_Task thread.
Definition main.c:1837
void StartFSM(void *argument)
Function implementing the FSM thread.
Definition main.c:1721
HAL_StatusTypeDef QFlash_Init()
HAL_StatusTypeDef QFlash_ChipErase()
HAL_StatusTypeDef QFlash_Read(uint32_t address, uint8_t *buffer, uint32_t dataSize)
int8_t init_bmp390_B(struct bmp3_dev *bmp390)
Initializes the backup barometer (BMP390).
Definition utilities.c:723
int8_t init_bmp390_p(struct bmp3_dev *bmp390)
Initializes the primary barometer (BMP390).
Definition utilities.c:252
@ LSM6DSO32_XL_ODR_6667Hz_HIGH_PERF
@ LSM6DSO32_2000dps
@ LSM6DSO32_GY_ODR_208Hz_HIGH_PERF
@ LSM6DSO32_16g
static void MX_USB_OTG_FS_PCD_Init(void)
USB_OTG_FS Initialization Function.
Definition main.c:1435
flight_phase_t flight_phase
Definition main.c:115
struct bmp3_dev bmp390_1
Definition main.c:122
void Error_Handler(void)
This function is executed in case of error occurrence.
Definition main.c:2042
struct bmp3_dev bmp390_2
Definition main.c:122
const osThreadAttr_t FSM_attributes
Definition main.c:87
static void MX_TIM7_Init(void)
TIM7 Initialization Function.
Definition main.c:1204
static void MX_QUADSPI_Init(void)
QUADSPI Initialization Function.
Definition main.c:938
static void MX_SPI1_Init(void)
SPI1 Initialization Function.
Definition main.c:973
float initial_flag_value
Definition main.c:316
flight_fsm_t flight_state
Definition main.c:117
void PeriphCommonClock_Config(void)
Peripherals Common Clock Configuration.
Definition main.c:669
static void MX_ADC2_Init(void)
ADC2 Initialization Function.
Definition main.c:765
static void MX_DMA_Init(void)
Definition main.c:1469
static void MX_USART1_UART_Init(void)
USART1 Initialization Function.
Definition main.c:1387
const osThreadAttr_t Kalman_mkf_attributes
Definition main.c:94
static void MX_MDMA_Init(void)
Definition main.c:1488
const osThreadAttr_t ReceiveVel_Task_attributes
Definition main.c:108
static void MX_FDCAN1_Init(void)
FDCAN1 Initialization Function.
Definition main.c:885
note_t Partition[]
Definition main.c:365
void SystemClock_Config(void)
System Clock Configuration.
Definition main.c:611
buzzer_t * bz
Definition main.c:121
static void MPU_Config(void)
Definition main.c:1971
static void MX_ADC1_Init(void)
ADC1 Initialization Function.
Definition main.c:696
stmdev_ctx_t imu_1
Definition main.c:124
osThreadId_t Kalman_mkfHandle
Definition main.c:93
const osThreadAttr_t MPC_Task_attributes
Definition main.c:101
static void MX_TIM15_Init(void)
TIM15 Initialization Function.
Definition main.c:1273
static void MX_SPI3_Init(void)
SPI3 Initialization Function.
Definition main.c:1069
static void MX_UART4_Init(void)
UART4 Initialization Function.
Definition main.c:1339
void StartReceiveVel_Task(void *argument)
Function implementing the ReceiveVel_Task thread.
Definition main.c:1943
static void MX_SPI2_Init(void)
SPI2 Initialization Function.
Definition main.c:1021
static void MX_ADC3_Init(void)
ADC3 Initialization Function.
Definition main.c:825
static void MX_GPIO_Init(void)
GPIO Initialization Function.
Definition main.c:1507
static void MX_TIM13_Init(void)
TIM13 Initialization Function.
Definition main.c:1242
stmdev_ctx_t imu_2
Definition main.c:124
static void MX_TIM6_Init(void)
TIM6 Initialization Function.
Definition main.c:1166
const osThreadAttr_t Sensor_Task_attributes
Definition main.c:80
static void MX_TIM2_Init(void)
TIM2 Initialization Function.
Definition main.c:1117
void initDWT(void)
Initializes the DWT (Data Watchpoint and Trace) cycle counter.
Definition profiler.h:70
flight_phase_t flight_state
The current state of the FSM.
Represents a single musical note with a frequency and duration.
Definition buzzer.h:31
@ HAL_OK

References bmp390_1, bmp390_2, buzzer_init(), bz, calibrateIMU(), Error_Handler(), flight_phase, flight_fsm_t::flight_state, flight_state, FSM_attributes, FSMHandle, HAL_OK, htim15, HWOFFSET, imu_1, imu_2, init_bmp390_B(), init_bmp390_p(), init_imuB(), init_imup(), initDWT(), initial_flag_value, Kalman_mkf_attributes, Kalman_mkfHandle, LSM6DSO32_16g, LSM6DSO32_2000dps, LSM6DSO32_GY_ODR_208Hz_HIGH_PERF, LSM6DSO32_XL_ODR_6667Hz_HIGH_PERF, MPC_Task_attributes, MPC_TaskHandle, MPU_Config(), musica_maestro(), MX_ADC1_Init(), MX_ADC2_Init(), MX_ADC3_Init(), MX_DMA_Init(), MX_FDCAN1_Init(), MX_GPIO_Init(), MX_MDMA_Init(), MX_QUADSPI_Init(), MX_SPI1_Init(), MX_SPI2_Init(), MX_SPI3_Init(), MX_TIM13_Init(), MX_TIM15_Init(), MX_TIM2_Init(), MX_TIM6_Init(), MX_TIM7_Init(), MX_UART4_Init(), MX_USART1_UART_Init(), MX_USB_OTG_FS_PCD_Init(), NOTE_B5, NULL, Partition, PeriphCommonClock_Config(), QFlash_ChipErase(), QFlash_Init(), QFlash_Read(), ReceiveVel_Task_attributes, ReceiveVel_TaskHandle, Sensor_Task_attributes, Sensor_TaskHandle, StartFSM(), StartKalman_mkf(), StartMPC_Task(), StartReceiveVel_Task(), StartSensor_Task(), and SystemClock_Config().

Here is the call graph for this function:

◆ MPU_Config()

void MPU_Config ( void  )
static

Initializes and configures the Region and the memory to be protected

Definition at line 1971 of file main.c.

1972{
1973 MPU_Region_InitTypeDef MPU_InitStruct = {0};
1974
1975 /* Disables the MPU */
1976 HAL_MPU_Disable();
1977
1980 MPU_InitStruct.Enable = MPU_REGION_ENABLE;
1981 MPU_InitStruct.Number = MPU_REGION_NUMBER0;
1982 MPU_InitStruct.BaseAddress = 0x0;
1983 MPU_InitStruct.Size = MPU_REGION_SIZE_4GB;
1984 MPU_InitStruct.SubRegionDisable = 0x87;
1985 MPU_InitStruct.TypeExtField = MPU_TEX_LEVEL0;
1986 MPU_InitStruct.AccessPermission = MPU_REGION_NO_ACCESS;
1987 MPU_InitStruct.DisableExec = MPU_INSTRUCTION_ACCESS_DISABLE;
1988 MPU_InitStruct.IsShareable = MPU_ACCESS_SHAREABLE;
1989 MPU_InitStruct.IsCacheable = MPU_ACCESS_NOT_CACHEABLE;
1990 MPU_InitStruct.IsBufferable = MPU_ACCESS_NOT_BUFFERABLE;
1991
1992 HAL_MPU_ConfigRegion(&MPU_InitStruct);
1993 /* Enables the MPU */
1994 HAL_MPU_Enable(MPU_PRIVILEGED_DEFAULT);
1995
1996}

Referenced by main().

Here is the caller graph for this function:

◆ MX_ADC1_Init()

static void MX_ADC1_Init ( void  )
static

ADC1 Initialization Function.

Parameters
None
Return values
None

Common config

Configure the ADC multi-mode

Configure Regular Channel

Definition at line 696 of file main.c.

697{
698
699 /* USER CODE BEGIN ADC1_Init 0 */
700
701 /* USER CODE END ADC1_Init 0 */
702
703 ADC_MultiModeTypeDef multimode = {0};
704 ADC_ChannelConfTypeDef sConfig = {0};
705
706 /* USER CODE BEGIN ADC1_Init 1 */
707
708 /* USER CODE END ADC1_Init 1 */
709
712 hadc1.Instance = ADC1;
713 hadc1.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV1;
714 hadc1.Init.Resolution = ADC_RESOLUTION_16B;
715 hadc1.Init.ScanConvMode = ADC_SCAN_DISABLE;
716 hadc1.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
717 hadc1.Init.LowPowerAutoWait = DISABLE;
718 hadc1.Init.ContinuousConvMode = DISABLE;
719 hadc1.Init.NbrOfConversion = 1;
720 hadc1.Init.DiscontinuousConvMode = DISABLE;
721 hadc1.Init.ExternalTrigConv = ADC_SOFTWARE_START;
722 hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
723 hadc1.Init.ConversionDataManagement = ADC_CONVERSIONDATA_DR;
724 hadc1.Init.Overrun = ADC_OVR_DATA_PRESERVED;
725 hadc1.Init.LeftBitShift = ADC_LEFTBITSHIFT_NONE;
726 hadc1.Init.OversamplingMode = DISABLE;
727 hadc1.Init.Oversampling.Ratio = 1;
728 if (HAL_ADC_Init(&hadc1) != HAL_OK)
729 {
731 }
732
735 multimode.Mode = ADC_MODE_INDEPENDENT;
736 if (HAL_ADCEx_MultiModeConfigChannel(&hadc1, &multimode) != HAL_OK)
737 {
739 }
740
743 sConfig.Channel = ADC_CHANNEL_11;
744 sConfig.Rank = ADC_REGULAR_RANK_1;
745 sConfig.SamplingTime = ADC_SAMPLETIME_1CYCLE_5;
746 sConfig.SingleDiff = ADC_SINGLE_ENDED;
747 sConfig.OffsetNumber = ADC_OFFSET_NONE;
748 sConfig.Offset = 0;
749 sConfig.OffsetSignedSaturation = DISABLE;
750 if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK)
751 {
753 }
754 /* USER CODE BEGIN ADC1_Init 2 */
755
756 /* USER CODE END ADC1_Init 2 */
757
758}
ADC_HandleTypeDef hadc1
Definition main.c:52

References Error_Handler(), hadc1, and HAL_OK.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_ADC2_Init()

static void MX_ADC2_Init ( void  )
static

ADC2 Initialization Function.

Parameters
None
Return values
None

Common config

Configure Regular Channel

Definition at line 765 of file main.c.

766{
767
768 /* USER CODE BEGIN ADC2_Init 0 */
769
770 /* USER CODE END ADC2_Init 0 */
771
772 ADC_ChannelConfTypeDef sConfig = {0};
773
774 /* USER CODE BEGIN ADC2_Init 1 */
775
776 /* USER CODE END ADC2_Init 1 */
777
780 hadc2.Instance = ADC2;
781 hadc2.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV1;
782 hadc2.Init.Resolution = ADC_RESOLUTION_16B;
783 hadc2.Init.ScanConvMode = ADC_SCAN_DISABLE;
784 hadc2.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
785 hadc2.Init.LowPowerAutoWait = DISABLE;
786 hadc2.Init.ContinuousConvMode = DISABLE;
787 hadc2.Init.NbrOfConversion = 1;
788 hadc2.Init.DiscontinuousConvMode = DISABLE;
789 hadc2.Init.ExternalTrigConv = ADC_SOFTWARE_START;
790 hadc2.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
791 hadc2.Init.ConversionDataManagement = ADC_CONVERSIONDATA_DR;
792 hadc2.Init.Overrun = ADC_OVR_DATA_PRESERVED;
793 hadc2.Init.LeftBitShift = ADC_LEFTBITSHIFT_NONE;
794 hadc2.Init.OversamplingMode = DISABLE;
795 hadc2.Init.Oversampling.Ratio = 1;
796 if (HAL_ADC_Init(&hadc2) != HAL_OK)
797 {
799 }
800
803 sConfig.Channel = ADC_CHANNEL_9;
804 sConfig.Rank = ADC_REGULAR_RANK_1;
805 sConfig.SamplingTime = ADC_SAMPLETIME_1CYCLE_5;
806 sConfig.SingleDiff = ADC_SINGLE_ENDED;
807 sConfig.OffsetNumber = ADC_OFFSET_NONE;
808 sConfig.Offset = 0;
809 sConfig.OffsetSignedSaturation = DISABLE;
810 if (HAL_ADC_ConfigChannel(&hadc2, &sConfig) != HAL_OK)
811 {
813 }
814 /* USER CODE BEGIN ADC2_Init 2 */
815
816 /* USER CODE END ADC2_Init 2 */
817
818}
ADC_HandleTypeDef hadc2
Definition main.c:53

References Error_Handler(), hadc2, and HAL_OK.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_ADC3_Init()

static void MX_ADC3_Init ( void  )
static

ADC3 Initialization Function.

Parameters
None
Return values
None

Common config

Configure Regular Channel

Definition at line 825 of file main.c.

826{
827
828 /* USER CODE BEGIN ADC3_Init 0 */
829
830 /* USER CODE END ADC3_Init 0 */
831
832 ADC_ChannelConfTypeDef sConfig = {0};
833
834 /* USER CODE BEGIN ADC3_Init 1 */
835
836 /* USER CODE END ADC3_Init 1 */
837
840 hadc3.Instance = ADC3;
841 hadc3.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV1;
842 hadc3.Init.Resolution = ADC_RESOLUTION_12B;
843 hadc3.Init.ScanConvMode = ADC_SCAN_DISABLE;
844 hadc3.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
845 hadc3.Init.LowPowerAutoWait = DISABLE;
846 hadc3.Init.ContinuousConvMode = DISABLE;
847 hadc3.Init.NbrOfConversion = 1;
848 hadc3.Init.DiscontinuousConvMode = DISABLE;
849 hadc3.Init.ExternalTrigConv = ADC_SOFTWARE_START;
850 hadc3.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
851 hadc3.Init.ConversionDataManagement = ADC_CONVERSIONDATA_DR;
852 hadc3.Init.Overrun = ADC_OVR_DATA_PRESERVED;
853 hadc3.Init.LeftBitShift = ADC_LEFTBITSHIFT_NONE;
854 hadc3.Init.OversamplingMode = DISABLE;
855 hadc3.Init.Oversampling.Ratio = 1;
856 if (HAL_ADC_Init(&hadc3) != HAL_OK)
857 {
859 }
860
863 sConfig.Channel = ADC_CHANNEL_11;
864 sConfig.Rank = ADC_REGULAR_RANK_1;
865 sConfig.SamplingTime = ADC_SAMPLETIME_1CYCLE_5;
866 sConfig.SingleDiff = ADC_SINGLE_ENDED;
867 sConfig.OffsetNumber = ADC_OFFSET_NONE;
868 sConfig.Offset = 0;
869 sConfig.OffsetSignedSaturation = DISABLE;
870 if (HAL_ADC_ConfigChannel(&hadc3, &sConfig) != HAL_OK)
871 {
873 }
874 /* USER CODE BEGIN ADC3_Init 2 */
875
876 /* USER CODE END ADC3_Init 2 */
877
878}
ADC_HandleTypeDef hadc3
Definition main.c:54

References Error_Handler(), hadc3, and HAL_OK.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_DMA_Init()

static void MX_DMA_Init ( void  )
static

Enable DMA controller clock

Definition at line 1469 of file main.c.

1470{
1471
1472 /* DMA controller clock enable */
1473 __HAL_RCC_DMA1_CLK_ENABLE();
1474
1475 /* DMA interrupt init */
1476 /* DMA1_Stream0_IRQn interrupt configuration */
1477 HAL_NVIC_SetPriority(DMA1_Stream0_IRQn, 5, 0);
1478 HAL_NVIC_EnableIRQ(DMA1_Stream0_IRQn);
1479 /* DMA1_Stream1_IRQn interrupt configuration */
1480 HAL_NVIC_SetPriority(DMA1_Stream1_IRQn, 5, 0);
1481 HAL_NVIC_EnableIRQ(DMA1_Stream1_IRQn);
1482
1483}

Referenced by main().

Here is the caller graph for this function:

◆ MX_FDCAN1_Init()

static void MX_FDCAN1_Init ( void  )
static

FDCAN1 Initialization Function.

Parameters
None
Return values
None

Definition at line 885 of file main.c.

886{
887
888 /* USER CODE BEGIN FDCAN1_Init 0 */
889
890 /* USER CODE END FDCAN1_Init 0 */
891
892 /* USER CODE BEGIN FDCAN1_Init 1 */
893
894 /* USER CODE END FDCAN1_Init 1 */
895 hfdcan1.Instance = FDCAN1;
896 hfdcan1.Init.FrameFormat = FDCAN_FRAME_CLASSIC;
897 hfdcan1.Init.Mode = FDCAN_MODE_NORMAL;
898 hfdcan1.Init.AutoRetransmission = DISABLE;
899 hfdcan1.Init.TransmitPause = DISABLE;
900 hfdcan1.Init.ProtocolException = DISABLE;
901 hfdcan1.Init.NominalPrescaler = 16;
902 hfdcan1.Init.NominalSyncJumpWidth = 1;
903 hfdcan1.Init.NominalTimeSeg1 = 1;
904 hfdcan1.Init.NominalTimeSeg2 = 1;
905 hfdcan1.Init.DataPrescaler = 1;
906 hfdcan1.Init.DataSyncJumpWidth = 1;
907 hfdcan1.Init.DataTimeSeg1 = 1;
908 hfdcan1.Init.DataTimeSeg2 = 1;
909 hfdcan1.Init.MessageRAMOffset = 0;
910 hfdcan1.Init.StdFiltersNbr = 0;
911 hfdcan1.Init.ExtFiltersNbr = 0;
912 hfdcan1.Init.RxFifo0ElmtsNbr = 0;
913 hfdcan1.Init.RxFifo0ElmtSize = FDCAN_DATA_BYTES_8;
914 hfdcan1.Init.RxFifo1ElmtsNbr = 0;
915 hfdcan1.Init.RxFifo1ElmtSize = FDCAN_DATA_BYTES_8;
916 hfdcan1.Init.RxBuffersNbr = 0;
917 hfdcan1.Init.RxBufferSize = FDCAN_DATA_BYTES_8;
918 hfdcan1.Init.TxEventsNbr = 0;
919 hfdcan1.Init.TxBuffersNbr = 0;
920 hfdcan1.Init.TxFifoQueueElmtsNbr = 0;
921 hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION;
922 hfdcan1.Init.TxElmtSize = FDCAN_DATA_BYTES_8;
923 if (HAL_FDCAN_Init(&hfdcan1) != HAL_OK)
924 {
926 }
927 /* USER CODE BEGIN FDCAN1_Init 2 */
928
929 /* USER CODE END FDCAN1_Init 2 */
930
931}
FDCAN_HandleTypeDef hfdcan1
Definition main.c:56

References Error_Handler(), HAL_OK, and hfdcan1.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_GPIO_Init()

static void MX_GPIO_Init ( void  )
static

GPIO Initialization Function.

Parameters
None
Return values
None

Definition at line 1507 of file main.c.

1508{
1509 GPIO_InitTypeDef GPIO_InitStruct = {0};
1510 /* USER CODE BEGIN MX_GPIO_Init_1 */
1511
1512 /* USER CODE END MX_GPIO_Init_1 */
1513
1514 /* GPIO Ports Clock Enable */
1515 __HAL_RCC_GPIOE_CLK_ENABLE();
1516 __HAL_RCC_GPIOH_CLK_ENABLE();
1517 __HAL_RCC_GPIOC_CLK_ENABLE();
1518 __HAL_RCC_GPIOA_CLK_ENABLE();
1519 __HAL_RCC_GPIOB_CLK_ENABLE();
1520 __HAL_RCC_GPIOD_CLK_ENABLE();
1521
1522 /*Configure GPIO pin Output Level */
1523 HAL_GPIO_WritePin(GPIOE, GPIO_1_Pin|GPIO_LED_FLASH_Pin|GPIO_LED2_Pin|GPIO_LED3_Pin, GPIO_PIN_RESET);
1524
1525 /*Configure GPIO pin Output Level */
1526 HAL_GPIO_WritePin(GPIOA, GPIO_2_Pin|GPIO_3_AIRBRAKES_AUX_Pin|GPIO4_CAMERA_Pin|GIO_SPI1_CS_Pin
1527 |GPIO_LED_USB_Pin, GPIO_PIN_RESET);
1528
1529 /*Configure GPIO pin Output Level */
1530 HAL_GPIO_WritePin(GPIOD, BARO_CS_Pin|IMU_CS_Pin|MAG_CS_Pin|GPIO_LED1_Pin, GPIO_PIN_RESET);
1531
1532 /*Configure GPIO pin Output Level */
1533 HAL_GPIO_WritePin(GPIOC, GPIO_Pyro_EN1_Pin|GPIO_Pyro_EN2_Pin|GPIO_DaVinci_Marc_SYNC_Pin, GPIO_PIN_RESET);
1534
1535 /*Configure GPIO pins : GPIO_1_Pin GPIO_LED_FLASH_Pin GPIO_LED2_Pin GPIO_LED3_Pin */
1536 GPIO_InitStruct.Pin = GPIO_1_Pin|GPIO_LED_FLASH_Pin|GPIO_LED2_Pin|GPIO_LED3_Pin;
1537 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
1538 GPIO_InitStruct.Pull = GPIO_NOPULL;
1539 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
1540 HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
1541
1542 /*Configure GPIO pins : GPIO_2_Pin GPIO_3_AIRBRAKES_AUX_Pin GPIO4_CAMERA_Pin GIO_SPI1_CS_Pin
1543 GPIO_LED_USB_Pin */
1544 GPIO_InitStruct.Pin = GPIO_2_Pin|GPIO_3_AIRBRAKES_AUX_Pin|GPIO4_CAMERA_Pin|GIO_SPI1_CS_Pin
1545 |GPIO_LED_USB_Pin;
1546 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
1547 GPIO_InitStruct.Pull = GPIO_NOPULL;
1548 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
1549 HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
1550
1551 /*Configure GPIO pins : BARO_CS_Pin IMU_CS_Pin MAG_CS_Pin GPIO_LED1_Pin */
1552 GPIO_InitStruct.Pin = BARO_CS_Pin|IMU_CS_Pin|MAG_CS_Pin|GPIO_LED1_Pin;
1553 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
1554 GPIO_InitStruct.Pull = GPIO_NOPULL;
1555 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
1556 HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
1557
1558 /*Configure GPIO pins : GPIO_Pyro_EN1_Pin GPIO_Pyro_EN2_Pin GPIO_DaVinci_Marc_SYNC_Pin */
1559 GPIO_InitStruct.Pin = GPIO_Pyro_EN1_Pin|GPIO_Pyro_EN2_Pin|GPIO_DaVinci_Marc_SYNC_Pin;
1560 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
1561 GPIO_InitStruct.Pull = GPIO_NOPULL;
1562 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
1563 HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
1564
1565 /*AnalogSwitch Config */
1566 HAL_SYSCFG_AnalogSwitchConfig(SYSCFG_SWITCH_PA0, SYSCFG_SWITCH_PA0_CLOSE);
1567
1568 /*AnalogSwitch Config */
1569 HAL_SYSCFG_AnalogSwitchConfig(SYSCFG_SWITCH_PA1, SYSCFG_SWITCH_PA1_CLOSE);
1570
1571 /* USER CODE BEGIN MX_GPIO_Init_2 */
1572
1573 /* USER CODE END MX_GPIO_Init_2 */
1574}

Referenced by main().

Here is the caller graph for this function:

◆ MX_MDMA_Init()

static void MX_MDMA_Init ( void  )
static

Enable MDMA controller clock

Definition at line 1488 of file main.c.

1489{
1490
1491 /* MDMA controller clock enable */
1492 __HAL_RCC_MDMA_CLK_ENABLE();
1493 /* Local variables */
1494
1495 /* MDMA interrupt initialization */
1496 /* MDMA_IRQn interrupt configuration */
1497 HAL_NVIC_SetPriority(MDMA_IRQn, 5, 0);
1498 HAL_NVIC_EnableIRQ(MDMA_IRQn);
1499
1500}

Referenced by main().

Here is the caller graph for this function:

◆ MX_QUADSPI_Init()

static void MX_QUADSPI_Init ( void  )
static

QUADSPI Initialization Function.

Parameters
None
Return values
None

Definition at line 938 of file main.c.

939{
940
941 /* USER CODE BEGIN QUADSPI_Init 0 */
942
943 /* USER CODE END QUADSPI_Init 0 */
944
945 /* USER CODE BEGIN QUADSPI_Init 1 */
946
947 /* USER CODE END QUADSPI_Init 1 */
948 /* QUADSPI parameter configuration*/
949 hqspi.Instance = QUADSPI;
950 hqspi.Init.ClockPrescaler = 1;
951 hqspi.Init.FifoThreshold = 32;
952 hqspi.Init.SampleShifting = QSPI_SAMPLE_SHIFTING_NONE;
953 hqspi.Init.FlashSize = 25;
954 hqspi.Init.ChipSelectHighTime = QSPI_CS_HIGH_TIME_1_CYCLE;
955 hqspi.Init.ClockMode = QSPI_CLOCK_MODE_0;
956 hqspi.Init.FlashID = QSPI_FLASH_ID_2;
957 hqspi.Init.DualFlash = QSPI_DUALFLASH_DISABLE;
958 if (HAL_QSPI_Init(&hqspi) != HAL_OK)
959 {
961 }
962 /* USER CODE BEGIN QUADSPI_Init 2 */
963
964 /* USER CODE END QUADSPI_Init 2 */
965
966}
QSPI_HandleTypeDef hqspi
HAL QSPI handle for the external flash memory.
Definition main.c:58

References Error_Handler(), HAL_OK, and hqspi.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_SPI1_Init()

static void MX_SPI1_Init ( void  )
static

SPI1 Initialization Function.

Parameters
None
Return values
None

Definition at line 973 of file main.c.

974{
975
976 /* USER CODE BEGIN SPI1_Init 0 */
977
978 /* USER CODE END SPI1_Init 0 */
979
980 /* USER CODE BEGIN SPI1_Init 1 */
981
982 /* USER CODE END SPI1_Init 1 */
983 /* SPI1 parameter configuration*/
984 hspi1.Instance = SPI1;
985 hspi1.Init.Mode = SPI_MODE_MASTER;
986 hspi1.Init.Direction = SPI_DIRECTION_2LINES;
987 hspi1.Init.DataSize = SPI_DATASIZE_4BIT;
988 hspi1.Init.CLKPolarity = SPI_POLARITY_LOW;
989 hspi1.Init.CLKPhase = SPI_PHASE_1EDGE;
990 hspi1.Init.NSS = SPI_NSS_SOFT;
991 hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
992 hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB;
993 hspi1.Init.TIMode = SPI_TIMODE_DISABLE;
994 hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
995 hspi1.Init.CRCPolynomial = 0x0;
996 hspi1.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
997 hspi1.Init.NSSPolarity = SPI_NSS_POLARITY_LOW;
998 hspi1.Init.FifoThreshold = SPI_FIFO_THRESHOLD_01DATA;
999 hspi1.Init.TxCRCInitializationPattern = SPI_CRC_INITIALIZATION_ALL_ZERO_PATTERN;
1000 hspi1.Init.RxCRCInitializationPattern = SPI_CRC_INITIALIZATION_ALL_ZERO_PATTERN;
1001 hspi1.Init.MasterSSIdleness = SPI_MASTER_SS_IDLENESS_00CYCLE;
1002 hspi1.Init.MasterInterDataIdleness = SPI_MASTER_INTERDATA_IDLENESS_00CYCLE;
1003 hspi1.Init.MasterReceiverAutoSusp = SPI_MASTER_RX_AUTOSUSP_DISABLE;
1004 hspi1.Init.MasterKeepIOState = SPI_MASTER_KEEP_IO_STATE_DISABLE;
1005 hspi1.Init.IOSwap = SPI_IO_SWAP_DISABLE;
1006 if (HAL_SPI_Init(&hspi1) != HAL_OK)
1007 {
1008 Error_Handler();
1009 }
1010 /* USER CODE BEGIN SPI1_Init 2 */
1011
1012 /* USER CODE END SPI1_Init 2 */
1013
1014}
SPI_HandleTypeDef hspi1
Definition main.c:61

References Error_Handler(), HAL_OK, and hspi1.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_SPI2_Init()

static void MX_SPI2_Init ( void  )
static

SPI2 Initialization Function.

Parameters
None
Return values
None

Definition at line 1021 of file main.c.

1022{
1023
1024 /* USER CODE BEGIN SPI2_Init 0 */
1025
1026 /* USER CODE END SPI2_Init 0 */
1027
1028 /* USER CODE BEGIN SPI2_Init 1 */
1029
1030 /* USER CODE END SPI2_Init 1 */
1031 /* SPI2 parameter configuration*/
1032 hspi2.Instance = SPI2;
1033 hspi2.Init.Mode = SPI_MODE_MASTER;
1034 hspi2.Init.Direction = SPI_DIRECTION_2LINES;
1035 hspi2.Init.DataSize = SPI_DATASIZE_8BIT;
1036 hspi2.Init.CLKPolarity = SPI_POLARITY_HIGH;
1037 hspi2.Init.CLKPhase = SPI_PHASE_2EDGE;
1038 hspi2.Init.NSS = SPI_NSS_SOFT;
1039 hspi2.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8;
1040 hspi2.Init.FirstBit = SPI_FIRSTBIT_MSB;
1041 hspi2.Init.TIMode = SPI_TIMODE_DISABLE;
1042 hspi2.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
1043 hspi2.Init.CRCPolynomial = 0x0;
1044 hspi2.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
1045 hspi2.Init.NSSPolarity = SPI_NSS_POLARITY_LOW;
1046 hspi2.Init.FifoThreshold = SPI_FIFO_THRESHOLD_01DATA;
1047 hspi2.Init.TxCRCInitializationPattern = SPI_CRC_INITIALIZATION_ALL_ZERO_PATTERN;
1048 hspi2.Init.RxCRCInitializationPattern = SPI_CRC_INITIALIZATION_ALL_ZERO_PATTERN;
1049 hspi2.Init.MasterSSIdleness = SPI_MASTER_SS_IDLENESS_00CYCLE;
1050 hspi2.Init.MasterInterDataIdleness = SPI_MASTER_INTERDATA_IDLENESS_00CYCLE;
1051 hspi2.Init.MasterReceiverAutoSusp = SPI_MASTER_RX_AUTOSUSP_DISABLE;
1052 hspi2.Init.MasterKeepIOState = SPI_MASTER_KEEP_IO_STATE_DISABLE;
1053 hspi2.Init.IOSwap = SPI_IO_SWAP_DISABLE;
1054 if (HAL_SPI_Init(&hspi2) != HAL_OK)
1055 {
1056 Error_Handler();
1057 }
1058 /* USER CODE BEGIN SPI2_Init 2 */
1059
1060 /* USER CODE END SPI2_Init 2 */
1061
1062}
SPI_HandleTypeDef hspi2
HAL SPI handle for Sensor Bus 1 (e.g., IMU, Baro).
Definition main.c:62

References Error_Handler(), HAL_OK, and hspi2.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_SPI3_Init()

static void MX_SPI3_Init ( void  )
static

SPI3 Initialization Function.

Parameters
None
Return values
None

Definition at line 1069 of file main.c.

1070{
1071
1072 /* USER CODE BEGIN SPI3_Init 0 */
1073
1074 /* USER CODE END SPI3_Init 0 */
1075
1076 /* USER CODE BEGIN SPI3_Init 1 */
1077
1078 /* USER CODE END SPI3_Init 1 */
1079 /* SPI3 parameter configuration*/
1080 hspi3.Instance = SPI3;
1081 hspi3.Init.Mode = SPI_MODE_MASTER;
1082 hspi3.Init.Direction = SPI_DIRECTION_2LINES;
1083 hspi3.Init.DataSize = SPI_DATASIZE_8BIT;
1084 hspi3.Init.CLKPolarity = SPI_POLARITY_HIGH;
1085 hspi3.Init.CLKPhase = SPI_PHASE_2EDGE;
1086 hspi3.Init.NSS = SPI_NSS_SOFT;
1087 hspi3.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8;
1088 hspi3.Init.FirstBit = SPI_FIRSTBIT_MSB;
1089 hspi3.Init.TIMode = SPI_TIMODE_DISABLE;
1090 hspi3.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
1091 hspi3.Init.CRCPolynomial = 0x0;
1092 hspi3.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
1093 hspi3.Init.NSSPolarity = SPI_NSS_POLARITY_LOW;
1094 hspi3.Init.FifoThreshold = SPI_FIFO_THRESHOLD_01DATA;
1095 hspi3.Init.TxCRCInitializationPattern = SPI_CRC_INITIALIZATION_ALL_ZERO_PATTERN;
1096 hspi3.Init.RxCRCInitializationPattern = SPI_CRC_INITIALIZATION_ALL_ZERO_PATTERN;
1097 hspi3.Init.MasterSSIdleness = SPI_MASTER_SS_IDLENESS_00CYCLE;
1098 hspi3.Init.MasterInterDataIdleness = SPI_MASTER_INTERDATA_IDLENESS_00CYCLE;
1099 hspi3.Init.MasterReceiverAutoSusp = SPI_MASTER_RX_AUTOSUSP_DISABLE;
1100 hspi3.Init.MasterKeepIOState = SPI_MASTER_KEEP_IO_STATE_DISABLE;
1101 hspi3.Init.IOSwap = SPI_IO_SWAP_DISABLE;
1102 if (HAL_SPI_Init(&hspi3) != HAL_OK)
1103 {
1104 Error_Handler();
1105 }
1106 /* USER CODE BEGIN SPI3_Init 2 */
1107
1108 /* USER CODE END SPI3_Init 2 */
1109
1110}
SPI_HandleTypeDef hspi3
HAL SPI handle for Sensor Bus 2 (e.g., secondary sensors).
Definition main.c:63

References Error_Handler(), HAL_OK, and hspi3.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_TIM13_Init()

static void MX_TIM13_Init ( void  )
static

TIM13 Initialization Function.

Parameters
None
Return values
None

Definition at line 1242 of file main.c.

1243{
1244
1245 /* USER CODE BEGIN TIM13_Init 0 */
1246
1247 /* USER CODE END TIM13_Init 0 */
1248
1249 /* USER CODE BEGIN TIM13_Init 1 */
1250
1251 /* USER CODE END TIM13_Init 1 */
1252 htim13.Instance = TIM13;
1253 htim13.Init.Prescaler = 239;
1254 htim13.Init.CounterMode = TIM_COUNTERMODE_UP;
1255 htim13.Init.Period = 9999;
1256 htim13.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
1257 htim13.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
1258 if (HAL_TIM_Base_Init(&htim13) != HAL_OK)
1259 {
1260 Error_Handler();
1261 }
1262 /* USER CODE BEGIN TIM13_Init 2 */
1263
1264 /* USER CODE END TIM13_Init 2 */
1265
1266}
TIM_HandleTypeDef htim13
Definition main.c:68

References Error_Handler(), HAL_OK, and htim13.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_TIM15_Init()

static void MX_TIM15_Init ( void  )
static

TIM15 Initialization Function.

Parameters
None
Return values
None

Definition at line 1273 of file main.c.

1274{
1275
1276 /* USER CODE BEGIN TIM15_Init 0 */
1277
1278 /* USER CODE END TIM15_Init 0 */
1279
1280 TIM_MasterConfigTypeDef sMasterConfig = {0};
1281 TIM_OC_InitTypeDef sConfigOC = {0};
1282 TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0};
1283
1284 /* USER CODE BEGIN TIM15_Init 1 */
1285
1286 /* USER CODE END TIM15_Init 1 */
1287 htim15.Instance = TIM15;
1288 htim15.Init.Prescaler = 239;
1289 htim15.Init.CounterMode = TIM_COUNTERMODE_UP;
1290 htim15.Init.Period = 999;
1291 htim15.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
1292 htim15.Init.RepetitionCounter = 0;
1293 htim15.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
1294 if (HAL_TIM_PWM_Init(&htim15) != HAL_OK)
1295 {
1296 Error_Handler();
1297 }
1298 sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
1299 sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
1300 if (HAL_TIMEx_MasterConfigSynchronization(&htim15, &sMasterConfig) != HAL_OK)
1301 {
1302 Error_Handler();
1303 }
1304 sConfigOC.OCMode = TIM_OCMODE_PWM1;
1305 sConfigOC.Pulse = 499;
1306 sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
1307 sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
1308 sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
1309 sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
1310 sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
1311 if (HAL_TIM_PWM_ConfigChannel(&htim15, &sConfigOC, TIM_CHANNEL_2) != HAL_OK)
1312 {
1313 Error_Handler();
1314 }
1315 sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;
1316 sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE;
1317 sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;
1318 sBreakDeadTimeConfig.DeadTime = 0;
1319 sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
1320 sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
1321 sBreakDeadTimeConfig.BreakFilter = 0;
1322 sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
1323 if (HAL_TIMEx_ConfigBreakDeadTime(&htim15, &sBreakDeadTimeConfig) != HAL_OK)
1324 {
1325 Error_Handler();
1326 }
1327 /* USER CODE BEGIN TIM15_Init 2 */
1328
1329 /* USER CODE END TIM15_Init 2 */
1331
1332}
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim)

References Error_Handler(), HAL_OK, HAL_TIM_MspPostInit(), and htim15.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_TIM2_Init()

static void MX_TIM2_Init ( void  )
static

TIM2 Initialization Function.

Parameters
None
Return values
None

Definition at line 1117 of file main.c.

1118{
1119
1120 /* USER CODE BEGIN TIM2_Init 0 */
1121
1122 /* USER CODE END TIM2_Init 0 */
1123
1124 TIM_MasterConfigTypeDef sMasterConfig = {0};
1125 TIM_OC_InitTypeDef sConfigOC = {0};
1126
1127 /* USER CODE BEGIN TIM2_Init 1 */
1128
1129 /* USER CODE END TIM2_Init 1 */
1130 htim2.Instance = TIM2;
1131 htim2.Init.Prescaler = 0;
1132 htim2.Init.CounterMode = TIM_COUNTERMODE_UP;
1133 htim2.Init.Period = 4294967295;
1134 htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
1135 htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
1136 if (HAL_TIM_PWM_Init(&htim2) != HAL_OK)
1137 {
1138 Error_Handler();
1139 }
1140 sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
1141 sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
1142 if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK)
1143 {
1144 Error_Handler();
1145 }
1146 sConfigOC.OCMode = TIM_OCMODE_PWM1;
1147 sConfigOC.Pulse = 0;
1148 sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
1149 sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
1150 if (HAL_TIM_PWM_ConfigChannel(&htim2, &sConfigOC, TIM_CHANNEL_3) != HAL_OK)
1151 {
1152 Error_Handler();
1153 }
1154 /* USER CODE BEGIN TIM2_Init 2 */
1155
1156 /* USER CODE END TIM2_Init 2 */
1158
1159}
TIM_HandleTypeDef htim2
Definition main.c:65

References Error_Handler(), HAL_OK, HAL_TIM_MspPostInit(), and htim2.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_TIM6_Init()

static void MX_TIM6_Init ( void  )
static

TIM6 Initialization Function.

Parameters
None
Return values
None

Definition at line 1166 of file main.c.

1167{
1168
1169 /* USER CODE BEGIN TIM6_Init 0 */
1170
1171 /* USER CODE END TIM6_Init 0 */
1172
1173 TIM_MasterConfigTypeDef sMasterConfig = {0};
1174
1175 /* USER CODE BEGIN TIM6_Init 1 */
1176
1177 /* USER CODE END TIM6_Init 1 */
1178 htim6.Instance = TIM6;
1179 htim6.Init.Prescaler = 5999;
1180 htim6.Init.CounterMode = TIM_COUNTERMODE_UP;
1181 htim6.Init.Period = 9;
1182 htim6.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
1183 if (HAL_TIM_Base_Init(&htim6) != HAL_OK)
1184 {
1185 Error_Handler();
1186 }
1187 sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
1188 sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
1189 if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK)
1190 {
1191 Error_Handler();
1192 }
1193 /* USER CODE BEGIN TIM6_Init 2 */
1194
1195 /* USER CODE END TIM6_Init 2 */
1196
1197}
TIM_HandleTypeDef htim6
Definition main.c:66

References Error_Handler(), HAL_OK, and htim6.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_TIM7_Init()

static void MX_TIM7_Init ( void  )
static

TIM7 Initialization Function.

Parameters
None
Return values
None

Definition at line 1204 of file main.c.

1205{
1206
1207 /* USER CODE BEGIN TIM7_Init 0 */
1208
1209 /* USER CODE END TIM7_Init 0 */
1210
1211 TIM_MasterConfigTypeDef sMasterConfig = {0};
1212
1213 /* USER CODE BEGIN TIM7_Init 1 */
1214
1215 /* USER CODE END TIM7_Init 1 */
1216 htim7.Instance = TIM7;
1217 htim7.Init.Prescaler = 23999;
1218 htim7.Init.CounterMode = TIM_COUNTERMODE_UP;
1219 htim7.Init.Period = 4999;
1220 htim7.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
1221 if (HAL_TIM_Base_Init(&htim7) != HAL_OK)
1222 {
1223 Error_Handler();
1224 }
1225 sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
1226 sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
1227 if (HAL_TIMEx_MasterConfigSynchronization(&htim7, &sMasterConfig) != HAL_OK)
1228 {
1229 Error_Handler();
1230 }
1231 /* USER CODE BEGIN TIM7_Init 2 */
1232
1233 /* USER CODE END TIM7_Init 2 */
1234
1235}
TIM_HandleTypeDef htim7
Definition main.c:67

References Error_Handler(), HAL_OK, and htim7.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_UART4_Init()

static void MX_UART4_Init ( void  )
static

UART4 Initialization Function.

Parameters
None
Return values
None

Definition at line 1339 of file main.c.

1340{
1341
1342 /* USER CODE BEGIN UART4_Init 0 */
1343
1344 /* USER CODE END UART4_Init 0 */
1345
1346 /* USER CODE BEGIN UART4_Init 1 */
1347
1348 /* USER CODE END UART4_Init 1 */
1349 huart4.Instance = UART4;
1350 huart4.Init.BaudRate = 115200;
1351 huart4.Init.WordLength = UART_WORDLENGTH_8B;
1352 huart4.Init.StopBits = UART_STOPBITS_1;
1353 huart4.Init.Parity = UART_PARITY_NONE;
1354 huart4.Init.Mode = UART_MODE_TX_RX;
1355 huart4.Init.HwFlowCtl = UART_HWCONTROL_NONE;
1356 huart4.Init.OverSampling = UART_OVERSAMPLING_16;
1357 huart4.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
1358 huart4.Init.ClockPrescaler = UART_PRESCALER_DIV1;
1359 huart4.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
1360 if (HAL_UART_Init(&huart4) != HAL_OK)
1361 {
1362 Error_Handler();
1363 }
1364 if (HAL_UARTEx_SetTxFifoThreshold(&huart4, UART_TXFIFO_THRESHOLD_1_8) != HAL_OK)
1365 {
1366 Error_Handler();
1367 }
1368 if (HAL_UARTEx_SetRxFifoThreshold(&huart4, UART_RXFIFO_THRESHOLD_1_8) != HAL_OK)
1369 {
1370 Error_Handler();
1371 }
1372 if (HAL_UARTEx_DisableFifoMode(&huart4) != HAL_OK)
1373 {
1374 Error_Handler();
1375 }
1376 /* USER CODE BEGIN UART4_Init 2 */
1377
1378 /* USER CODE END UART4_Init 2 */
1379
1380}
UART_HandleTypeDef huart4
Definition main.c:71

References Error_Handler(), HAL_OK, and huart4.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_USART1_UART_Init()

static void MX_USART1_UART_Init ( void  )
static

USART1 Initialization Function.

Parameters
None
Return values
None

Definition at line 1387 of file main.c.

1388{
1389
1390 /* USER CODE BEGIN USART1_Init 0 */
1391
1392 /* USER CODE END USART1_Init 0 */
1393
1394 /* USER CODE BEGIN USART1_Init 1 */
1395
1396 /* USER CODE END USART1_Init 1 */
1397 huart1.Instance = USART1;
1398 huart1.Init.BaudRate = 1843200;
1399 huart1.Init.WordLength = UART_WORDLENGTH_8B;
1400 huart1.Init.StopBits = UART_STOPBITS_1;
1401 huart1.Init.Parity = UART_PARITY_NONE;
1402 huart1.Init.Mode = UART_MODE_TX_RX;
1403 huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE;
1404 huart1.Init.OverSampling = UART_OVERSAMPLING_16;
1405 huart1.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
1406 huart1.Init.ClockPrescaler = UART_PRESCALER_DIV1;
1407 huart1.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
1408 if (HAL_UART_Init(&huart1) != HAL_OK)
1409 {
1410 Error_Handler();
1411 }
1412 if (HAL_UARTEx_SetTxFifoThreshold(&huart1, UART_TXFIFO_THRESHOLD_1_8) != HAL_OK)
1413 {
1414 Error_Handler();
1415 }
1416 if (HAL_UARTEx_SetRxFifoThreshold(&huart1, UART_RXFIFO_THRESHOLD_1_8) != HAL_OK)
1417 {
1418 Error_Handler();
1419 }
1420 if (HAL_UARTEx_EnableFifoMode(&huart1) != HAL_OK)
1421 {
1422 Error_Handler();
1423 }
1424 /* USER CODE BEGIN USART1_Init 2 */
1425
1426 /* USER CODE END USART1_Init 2 */
1427
1428}

References Error_Handler(), HAL_OK, and huart1.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MX_USB_OTG_FS_PCD_Init()

static void MX_USB_OTG_FS_PCD_Init ( void  )
static

USB_OTG_FS Initialization Function.

Parameters
None
Return values
None

Definition at line 1435 of file main.c.

1436{
1437
1438 /* USER CODE BEGIN USB_OTG_FS_Init 0 */
1439
1440 /* USER CODE END USB_OTG_FS_Init 0 */
1441
1442 /* USER CODE BEGIN USB_OTG_FS_Init 1 */
1443
1444 /* USER CODE END USB_OTG_FS_Init 1 */
1445 hpcd_USB_OTG_FS.Instance = USB_OTG_FS;
1446 hpcd_USB_OTG_FS.Init.dev_endpoints = 9;
1447 hpcd_USB_OTG_FS.Init.speed = PCD_SPEED_FULL;
1448 hpcd_USB_OTG_FS.Init.dma_enable = DISABLE;
1449 hpcd_USB_OTG_FS.Init.phy_itface = PCD_PHY_EMBEDDED;
1450 hpcd_USB_OTG_FS.Init.Sof_enable = DISABLE;
1451 hpcd_USB_OTG_FS.Init.low_power_enable = DISABLE;
1452 hpcd_USB_OTG_FS.Init.lpm_enable = DISABLE;
1453 hpcd_USB_OTG_FS.Init.battery_charging_enable = DISABLE;
1454 hpcd_USB_OTG_FS.Init.vbus_sensing_enable = DISABLE;
1455 hpcd_USB_OTG_FS.Init.use_dedicated_ep1 = DISABLE;
1456 if (HAL_PCD_Init(&hpcd_USB_OTG_FS) != HAL_OK)
1457 {
1458 Error_Handler();
1459 }
1460 /* USER CODE BEGIN USB_OTG_FS_Init 2 */
1461
1462 /* USER CODE END USB_OTG_FS_Init 2 */
1463
1464}
PCD_HandleTypeDef hpcd_USB_OTG_FS
Definition main.c:76

References Error_Handler(), HAL_OK, and hpcd_USB_OTG_FS.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ PeriphCommonClock_Config()

void PeriphCommonClock_Config ( void  )

Peripherals Common Clock Configuration.

Return values
None

Initializes the peripherals clock

Definition at line 669 of file main.c.

670{
671 RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0};
672
675 PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_ADC;
676 PeriphClkInitStruct.PLL2.PLL2M = 1;
677 PeriphClkInitStruct.PLL2.PLL2N = 10;
678 PeriphClkInitStruct.PLL2.PLL2P = 2;
679 PeriphClkInitStruct.PLL2.PLL2Q = 2;
680 PeriphClkInitStruct.PLL2.PLL2R = 2;
681 PeriphClkInitStruct.PLL2.PLL2RGE = RCC_PLL2VCIRANGE_3;
682 PeriphClkInitStruct.PLL2.PLL2VCOSEL = RCC_PLL2VCOMEDIUM;
683 PeriphClkInitStruct.PLL2.PLL2FRACN = 0;
684 PeriphClkInitStruct.AdcClockSelection = RCC_ADCCLKSOURCE_PLL2;
685 if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
686 {
688 }
689}

References Error_Handler(), and HAL_OK.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ StartReceiveVel_Task()

void StartReceiveVel_Task ( void *  argument)

Function implementing the ReceiveVel_Task thread.

Parameters
argumentNot used
Return values
None

Definition at line 1943 of file main.c.

1944{
1945 /* USER CODE BEGIN StartReceiveVel_Task */
1946 /* Infinite loop */
1947 if (HAL_UART_Receive_DMA(&huart1, vel, 4) != HAL_OK) {
1948 Error_Handler();
1949 }
1950
1951 for(;;)
1952 {
1953 uint32_t flags = osThreadFlagsWait(RECEIVED_VEL_FLAG , osFlagsWaitAny, osWaitForever);
1954
1955 if (flags & RECEIVED_VEL_FLAG) {
1956 memcpy(&gps_vel,(uint8_t*)vel,sizeof(vel));
1957 HAL_UART_Receive_DMA(&huart1, vel, 4);
1958
1959 gnss_flag = gps_vel > 0;
1960
1961 if(gnss_flag) {
1962 LED_TOGGLE(GPIO_LED_USB_GPIO_Port, GPIO_LED_USB_Pin);
1963 }
1964 }
1965 }
1966 /* USER CODE END StartReceiveVel_Task */
1967}
bool gnss_flag
Definition main.c:300
uint8_t vel[4]
Definition main.c:292
float gps_vel
Definition main.c:293

References Error_Handler(), gnss_flag, gps_vel, HAL_OK, huart1, RECEIVED_VEL_FLAG, and vel.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ SystemClock_Config()

void SystemClock_Config ( void  )

System Clock Configuration.

Return values
None

Supply configuration update enable

Configure the main internal regulator output voltage

Initializes the RCC Oscillators according to the specified parameters in the RCC_OscInitTypeDef structure.

Initializes the CPU, AHB and APB buses clocks

Definition at line 611 of file main.c.

612{
613 RCC_OscInitTypeDef RCC_OscInitStruct = {0};
614 RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
615
618 HAL_PWREx_ConfigSupply(PWR_LDO_SUPPLY);
619
622 __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE0);
623
624 while(!__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY)) {}
625
629 RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
630 RCC_OscInitStruct.HSEState = RCC_HSE_ON;
631 RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
632 RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
633 RCC_OscInitStruct.PLL.PLLM = 1;
634 RCC_OscInitStruct.PLL.PLLN = 60;
635 RCC_OscInitStruct.PLL.PLLP = 2;
636 RCC_OscInitStruct.PLL.PLLQ = 15;
637 RCC_OscInitStruct.PLL.PLLR = 2;
638 RCC_OscInitStruct.PLL.PLLRGE = RCC_PLL1VCIRANGE_3;
639 RCC_OscInitStruct.PLL.PLLVCOSEL = RCC_PLL1VCOWIDE;
640 RCC_OscInitStruct.PLL.PLLFRACN = 0;
641 if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
642 {
644 }
645
648 RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
649 |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2
650 |RCC_CLOCKTYPE_D3PCLK1|RCC_CLOCKTYPE_D1PCLK1;
651 RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
652 RCC_ClkInitStruct.SYSCLKDivider = RCC_SYSCLK_DIV1;
653 RCC_ClkInitStruct.AHBCLKDivider = RCC_HCLK_DIV2;
654 RCC_ClkInitStruct.APB3CLKDivider = RCC_APB3_DIV2;
655 RCC_ClkInitStruct.APB1CLKDivider = RCC_APB1_DIV2;
656 RCC_ClkInitStruct.APB2CLKDivider = RCC_APB2_DIV2;
657 RCC_ClkInitStruct.APB4CLKDivider = RCC_APB4_DIV2;
658
659 if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_4) != HAL_OK)
660 {
662 }
663}

References Error_Handler(), and HAL_OK.

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

Variable Documentation

◆ a_m

double a_m = -12.09

Definition at line 250 of file main.c.

Referenced by kalmanFilter(), StartKalman_mkf(), and StartSensor_Task().

◆ acceleration_mg_1

float_t acceleration_mg_1[3] = {0}
static

Definition at line 132 of file main.c.

Referenced by StartFSM(), StartMPC_Task(), and StartSensor_Task().

◆ adcVal

uint32_t adcVal = 0

Definition at line 323 of file main.c.

Referenced by StartMPC_Task().

◆ alpha

double alpha = 0.0

Definition at line 249 of file main.c.

Referenced by attitude_estimation(), kalmanFilter(), StartKalman_mkf(), and StartMPC_Task().

◆ altitude

float_t altitude = 0.0

◆ angular_rate_mdps_1

float_t angular_rate_mdps_1[3] = {0}
static

Definition at line 133 of file main.c.

Referenced by StartMPC_Task(), and StartSensor_Task().

◆ array

uint8_t array[63]

Definition at line 296 of file main.c.

Referenced by StartMPC_Task().

◆ b_B

double b_B[] = {0,0,0}

Definition at line 241 of file main.c.

Referenced by mekf().

◆ barometer_data_1

struct bmp3_data barometer_data_1 = {-1, -1}

Definition at line 126 of file main.c.

Referenced by StartMPC_Task(), and StartSensor_Task().

◆ barometer_data_2

struct bmp3_data barometer_data_2 = {-1, -1}

Definition at line 127 of file main.c.

◆ beta

double beta[] = {0, 0, 0}

Definition at line 238 of file main.c.

Referenced by mekf().

◆ beta_new

double beta_new[] = {0,0,0}

Definition at line 244 of file main.c.

Referenced by mekf().

◆ bmp390_1

struct bmp3_dev bmp390_1 = {0}

Definition at line 122 of file main.c.

Referenced by main(), and StartSensor_Task().

◆ bmp390_2

struct bmp3_dev bmp390_2 = {0}

Definition at line 122 of file main.c.

Referenced by main().

◆ bz

buzzer_t* bz ={0}

Definition at line 121 of file main.c.

Referenced by buzzer_init(), main(), and musica_maestro().

◆ cd_table

double cd_table[] ={0.4510,0.3940,0.3610,0.3390,0.3320,0.5430,0.4960,0.4690,0.4250,0.4170,0.6240,0.5790,0.5550,0.5350,0.5280, 0.7450,0.7140,0.6780,0.6760,0.6720,0.7520,0.7230,0.6980,0.6850,0.6820,0.85,0.81,0.8,0.8,0.8}
static

Definition at line 263 of file main.c.

Referenced by cdEvaluation(), optimalAngle(), and StartMPC_Task().

◆ cpy_buffer

uint8_t cpy_buffer[2112] = {0}

Definition at line 310 of file main.c.

Referenced by StartKalman_mkf().

◆ current_delta

double current_delta = 0

Definition at line 257 of file main.c.

Referenced by optimalAngle().

◆ data_buffer

uint8_t data_buffer[4224] ={0}

Definition at line 309 of file main.c.

Referenced by StartKalman_mkf(), and StartSensor_Task().

◆ data_raw_acceleration_1

int16_t data_raw_acceleration_1[3] = {0}
static

Definition at line 130 of file main.c.

Referenced by StartSensor_Task().

◆ data_raw_angular_rate_1

int16_t data_raw_angular_rate_1[3] = {0}
static

Definition at line 129 of file main.c.

Referenced by StartSensor_Task().

◆ deployment_states

const double deployment_states[] ={0.0,40.5000,69.7500,94.5000,108.0000,173.8000}

Definition at line 262 of file main.c.

Referenced by optimalAngle(), and StartMPC_Task().

◆ first_measure

bool first_measure = true

Definition at line 233 of file main.c.

Referenced by StartSensor_Task().

◆ flash_address

uint32_t flash_address = 4

Definition at line 308 of file main.c.

Referenced by StartKalman_mkf().

◆ flight_phase

flight_phase_t flight_phase = CALIBRATING

Definition at line 115 of file main.c.

Referenced by main().

◆ flight_state

flight_fsm_t flight_state

Definition at line 117 of file main.c.

Referenced by main(), StartFSM(), StartMPC_Task(), and StartSensor_Task().

◆ FSM_attributes

const osThreadAttr_t FSM_attributes
Initial value:
= {
.name = "FSM",
.stack_size = 128 * 4,
.priority = (osPriority_t) osPriorityNormal,
}

Definition at line 87 of file main.c.

Referenced by main().

◆ FSMHandle

osThreadId_t FSMHandle

Definition at line 86 of file main.c.

Referenced by HAL_TIM_PeriodElapsedCallback(), and main().

◆ gnss_flag

bool gnss_flag = false

Definition at line 300 of file main.c.

Referenced by StartKalman_mkf(), and StartReceiveVel_Task().

◆ gps_vel

float gps_vel = 0.0f

Definition at line 293 of file main.c.

Referenced by StartKalman_mkf(), StartReceiveVel_Task(), and StartSensor_Task().

◆ hadc1

ADC_HandleTypeDef hadc1

Definition at line 52 of file main.c.

Referenced by MX_ADC1_Init().

◆ hadc2

ADC_HandleTypeDef hadc2

Definition at line 53 of file main.c.

Referenced by MX_ADC2_Init().

◆ hadc3

ADC_HandleTypeDef hadc3

Definition at line 54 of file main.c.

Referenced by MX_ADC3_Init(), and StartMPC_Task().

◆ hdma_usart1_rx

DMA_HandleTypeDef hdma_usart1_rx

Definition at line 73 of file main.c.

Referenced by DMA1_Stream0_IRQHandler(), and HAL_UART_MspInit().

◆ hdma_usart1_tx

DMA_HandleTypeDef hdma_usart1_tx

Definition at line 74 of file main.c.

Referenced by DMA1_Stream1_IRQHandler(), and HAL_UART_MspInit().

◆ hfdcan1

FDCAN_HandleTypeDef hfdcan1

Definition at line 56 of file main.c.

Referenced by MX_FDCAN1_Init().

◆ hmdma_quadspi_fifo_th

MDMA_HandleTypeDef hmdma_quadspi_fifo_th

Definition at line 59 of file main.c.

Referenced by HAL_QSPI_MspInit(), and MDMA_IRQHandler().

◆ hpcd_USB_OTG_FS

PCD_HandleTypeDef hpcd_USB_OTG_FS

Definition at line 76 of file main.c.

Referenced by MX_USB_OTG_FS_PCD_Init().

◆ hspi1

SPI_HandleTypeDef hspi1

Definition at line 61 of file main.c.

Referenced by MX_SPI1_Init().

◆ htim13

TIM_HandleTypeDef htim13

Definition at line 68 of file main.c.

Referenced by MX_TIM13_Init(), StartFSM(), and TIM8_UP_TIM13_IRQHandler().

◆ htim2

TIM_HandleTypeDef htim2

Definition at line 65 of file main.c.

Referenced by MX_TIM2_Init().

◆ htim6

TIM_HandleTypeDef htim6

Definition at line 66 of file main.c.

Referenced by MX_TIM6_Init(), StartSensor_Task(), and TIM6_DAC_IRQHandler().

◆ htim7

TIM_HandleTypeDef htim7

Definition at line 67 of file main.c.

Referenced by MX_TIM7_Init(), StartMPC_Task(), and TIM7_IRQHandler().

◆ huart1

UART_HandleTypeDef huart1

◆ huart4

UART_HandleTypeDef huart4

Definition at line 71 of file main.c.

Referenced by MX_UART4_Init().

◆ imu_1

stmdev_ctx_t imu_1 = {0}

Definition at line 124 of file main.c.

Referenced by main(), and StartSensor_Task().

◆ imu_2

stmdev_ctx_t imu_2 = {0}

Definition at line 124 of file main.c.

Referenced by main().

◆ initial_flag_value

float initial_flag_value = 0.0f

Definition at line 316 of file main.c.

Referenced by main().

◆ Kalman_mkf_attributes

const osThreadAttr_t Kalman_mkf_attributes
Initial value:
= {
.name = "Kalman_mkf",
.stack_size = 512 * 4,
.priority = (osPriority_t) osPriorityNormal,
}

Definition at line 94 of file main.c.

Referenced by main().

◆ Kalman_mkfHandle

osThreadId_t Kalman_mkfHandle

Definition at line 93 of file main.c.

Referenced by main(), and StartSensor_Task().

◆ lis2mdl_dev_ctx

stmdev_ctx_t lis2mdl_dev_ctx

Definition at line 135 of file main.c.

◆ lis2mdl_dev_ctx_2

stmdev_ctx_t lis2mdl_dev_ctx_2

Definition at line 136 of file main.c.

◆ mach_states

const double mach_states[] = {0.1,0.2,0.3,0.4,0.5}

Definition at line 261 of file main.c.

Referenced by cdEvaluation(), optimalAngle(), and StartMPC_Task().

◆ max_alt

float max_alt = 0

Definition at line 231 of file main.c.

Referenced by StartMPC_Task().

◆ max_vel

float max_vel =0

Definition at line 232 of file main.c.

Referenced by StartMPC_Task().

◆ message

Data_Package_For_Marconi message = {0}

Definition at line 228 of file main.c.

Referenced by StartMPC_Task().

◆ MPC_Task_attributes

const osThreadAttr_t MPC_Task_attributes
Initial value:
= {
.name = "MPC_Task",
.stack_size = 128 * 4,
.priority = (osPriority_t) osPriorityNormal,
}

Definition at line 101 of file main.c.

Referenced by main().

◆ MPC_TaskHandle

osThreadId_t MPC_TaskHandle

Definition at line 100 of file main.c.

Referenced by HAL_TIM_PeriodElapsedCallback(), and main().

◆ num_of_lin_acc_saved

uint32_t num_of_lin_acc_saved = 0

Definition at line 311 of file main.c.

Referenced by StartSensor_Task().

◆ num_of_lin_acc_saved_flash

uint32_t num_of_lin_acc_saved_flash = 0

Definition at line 314 of file main.c.

Referenced by StartKalman_mkf().

◆ num_of_saved_rest_packages

uint32_t num_of_saved_rest_packages = 0

Definition at line 312 of file main.c.

Referenced by StartSensor_Task().

◆ num_of_saved_rest_packages_flash

uint32_t num_of_saved_rest_packages_flash = 0

Definition at line 315 of file main.c.

Referenced by StartKalman_mkf().

◆ num_of_saved_rest_packages_locked

uint32_t num_of_saved_rest_packages_locked = 0

Definition at line 313 of file main.c.

Referenced by StartKalman_mkf(), and StartSensor_Task().

◆ omega

double omega[] = {3.760494829166693e-05, -1.4118446451604494e-07, 0.0003572545679652845}

Definition at line 240 of file main.c.

Referenced by mekf(), StartKalman_mkf(), and StartSensor_Task().

◆ P_2

double P_2[] = {5,0,0,5}

Definition at line 247 of file main.c.

Referenced by StartKalman_mkf().

◆ Partition

note_t Partition[]
Initial value:
#define NOTE_A5
Note A, 5th octave.
Definition buzzer.h:59
#define TEMPO_BASE_MS
The base duration for a note, in milliseconds.
Definition buzzer.h:61
#define NOTE_D6
Note D, 6th octave.
Definition buzzer.h:56
#define NOTE_Db6
Note D-flat, 6th octave.
Definition buzzer.h:57
#define NOTE_Gb5
Note G-flat, 5th octave.
Definition buzzer.h:55

Definition at line 365 of file main.c.

Referenced by main().

◆ Pressure_1

float_t Pressure_1 = 0.0

Definition at line 226 of file main.c.

Referenced by StartSensor_Task().

◆ q

double q[] = {0.7061377159181262, -0.03700710955926802, 0.03700710955926802, -0.7061377159181262}

Definition at line 237 of file main.c.

Referenced by mekf(), and StartKalman_mkf().

◆ Q

const double Q[] = {2769,1846,1846,1385}

Definition at line 252 of file main.c.

Referenced by kalmanFilter(), mekf(), and StartKalman_mkf().

◆ q_new

double q_new[] = {0,0,0,0}

Definition at line 243 of file main.c.

Referenced by mekf(), and StartKalman_mkf().

◆ R

const double R[] = {5.54e-3,0,0,0.121}

Definition at line 253 of file main.c.

Referenced by kalmanFilter(), mekf(), and StartKalman_mkf().

◆ raw_mag_data

int16_t raw_mag_data[3]

Definition at line 137 of file main.c.

◆ ReceiveVel_Task_attributes

const osThreadAttr_t ReceiveVel_Task_attributes
Initial value:
= {
.name = "ReceiveVel_Task",
.stack_size = 128 * 4,
.priority = (osPriority_t) osPriorityNormal,
}

Definition at line 108 of file main.c.

Referenced by main().

◆ ReceiveVel_TaskHandle

osThreadId_t ReceiveVel_TaskHandle

Definition at line 107 of file main.c.

Referenced by HAL_UART_ErrorCallback(), HAL_UART_RxCpltCallback(), and main().

◆ Sensor_Task_attributes

const osThreadAttr_t Sensor_Task_attributes
Initial value:
= {
.name = "Sensor_Task",
.stack_size = 128 * 4,
.priority = (osPriority_t) osPriorityRealtime7,
}

Definition at line 80 of file main.c.

Referenced by main().

◆ Sensor_TaskHandle

osThreadId_t Sensor_TaskHandle

Definition at line 79 of file main.c.

Referenced by HAL_TIM_PeriodElapsedCallback(), and main().

◆ sim_time_step

double sim_time_step = 0.5

Definition at line 256 of file main.c.

Referenced by optimalAngle(), and StartMPC_Task().

◆ target_apogee

double target_apogee = 8900

Definition at line 258 of file main.c.

Referenced by optimalAngle(), and StartMPC_Task().

◆ Temperature_1

float_t Temperature_1 = 0.0

Definition at line 227 of file main.c.

Referenced by StartSensor_Task().

◆ tilt_angle

double tilt_angle = 0.24556997475102937

Definition at line 260 of file main.c.

Referenced by optimalAngle().

◆ time_step

double time_step = 0.5

Definition at line 255 of file main.c.

◆ tolerance

double tolerance = 1

Definition at line 259 of file main.c.

Referenced by optimalAngle(), and StartMPC_Task().

◆ Ts

double Ts = 0.01

Definition at line 251 of file main.c.

Referenced by kalmanFilter(), and StartKalman_mkf().

◆ vel

uint8_t vel[4]

Definition at line 292 of file main.c.

Referenced by StartReceiveVel_Task().

◆ velocity

float_t velocity = 0.0

Definition at line 225 of file main.c.

Referenced by optimalAngle(), StartFSM(), StartKalman_mkf(), StartMPC_Task(), and StartSensor_Task().

◆ Vin

float Vin =0

Definition at line 321 of file main.c.

Referenced by StartMPC_Task().

◆ Vr

float Vr =0

Definition at line 322 of file main.c.

Referenced by StartMPC_Task().

◆ x_est

double x_est[] = {5000,330}

Definition at line 254 of file main.c.

Referenced by kalmanFilter(), StartKalman_mkf(), and StartMPC_Task().

◆ xKalman_TaskHandle

TaskHandle_t xKalman_TaskHandle = NULL

Definition at line 271 of file main.c.

◆ xKalman_TaskID

osThreadId_t xKalman_TaskID = NULL

Definition at line 278 of file main.c.

◆ xMPCTaskHandle

TaskHandle_t xMPCTaskHandle = NULL

Definition at line 269 of file main.c.

◆ xMPCTaskID

osThreadId_t xMPCTaskID = NULL

Definition at line 276 of file main.c.

◆ xReceived_VelHandle

TaskHandle_t xReceived_VelHandle = NULL

Definition at line 268 of file main.c.

◆ xReceived_VelID

osThreadId_t xReceived_VelID =NULL

Definition at line 275 of file main.c.

◆ xSensorsTaskHandle

TaskHandle_t xSensorsTaskHandle = NULL

Definition at line 270 of file main.c.

◆ xSensorsTaskID

osThreadId_t xSensorsTaskID = NULL

Definition at line 277 of file main.c.

◆ z

double z[] = {5003.24140978,329.14706741}

Definition at line 248 of file main.c.

Referenced by kalmanFilter(), StartKalman_mkf(), and StartSensor_Task().

◆ z_component

double z_component = 0.0

Definition at line 264 of file main.c.