25#include "../Inc/Files/can1_dbc.h"
26#include "../Inc/Scheduler/Scheduler.h"
27#include "../Inc/Sensors/AnalogSensor.h"
28#include "../Inc/Systems/Comms/Can/Can.h"
29#include "../Inc/Systems/Controller/Apps.h"
30#include "../Inc/Systems/Controller/BrakeSystemControl.h"
31#include "../Inc/Systems/Controller/RTD.h"
32#include "../Inc/Systems/Controller/TorqueControl.h"
33#include "../Inc/Systems/External/Inverter.h"
34#include "../Inc/Systems/Monitor/AppsMonitor.h"
35#include "../Inc/Systems/Monitor/BrakePolice.h"
36#include "../Inc/Systems/Monitor/RTDMonitor.h"
37#include "../Inc/Systems/Monitor/TorquePolice.h"
38#include "../Inc/Utils/Constants.h"
39#include "../Inc/Utils/Telemetry.h"
42#include "stm32f7xx_hal_adc.h"
92 .name =
"defaultTask",
93 .stack_size = 128 * 4,
94 .priority = (osPriority_t) osPriorityNormal,
211 __HAL_UART_ENABLE_IT(&
huart3, UART_IT_RXNE);
214 uint32_t multi_mode = (ADC123_COMMON->CCR & ADC_CCR_MULTI);
221 { .
name =
"VDD", .start_bit = 0, .length = 8, .endian = 0, .isSigned = 0, .scale = 0.1, .offset = 0, .min = 0, .max = 255, .unit =
"voltage", .reciever =
"reciever" },
222 { .name =
"Char 2", .start_bit = 8, .length = 8, .endian = 0, .isSigned = 0, .scale = 1, .offset = 0, .min = 0, .max = 255, .unit =
"unit", .reciever =
"reciever" },
223 { .name =
"Char 3", .start_bit = 16, .length = 8, .endian = 0, .isSigned = 0, .scale = 1, .offset = 0, .min = 0, .max = 255, .unit =
"unit", .reciever =
"reciever" },
224 { .name =
"Char 4", .start_bit = 24, .length = 8, .endian = 0, .isSigned = 0, .scale = 1, .offset = 0, .min = 0, .max = 255, .unit =
"unit", .reciever =
"reciever" },
225 { .name =
"Char 5", .start_bit = 32, .length = 8, .endian = 0, .isSigned = 0, .scale = 1, .offset = 0, .min = 0, .max = 255, .unit =
"unit", .reciever =
"reciever" },
226 { .name =
"Char 6", .start_bit = 40, .length = 8, .endian = 0, .isSigned = 0, .scale = 1, .offset = 0, .min = 0, .max = 255, .unit =
"unit", .reciever =
"reciever" },
227 { .name =
"Char 7", .start_bit = 48, .length = 8, .endian = 0, .isSigned = 0, .scale = 1, .offset = 0, .min = 0, .max = 255, .unit =
"unit", .reciever =
"reciever" },
228 { .name =
"Char 8", .start_bit = 56, .length = 8, .endian = 0, .isSigned = 0, .scale = 1, .offset = 0, .min = 0, .max = 255, .unit =
"unit", .reciever =
"reciever" }
239 uint8_t txdata[8] = {0, 1, 2, 3, 4, 5, 6, 7};
271 initRTD(&rtd, &apps, &bsc, 10, 0, 1);
310 updateables[5] = NULL;
321 osKernelInitialize();
358 static uint32_t test_can_counter = 0;
365 if (test_can_counter >= 5) {
366 test_can_counter = 0;
369 uint8_t test_data[8] = {0xAA, 0xBB, 0xCC, 0xDD, (uint8_t)(HAL_GetTick() & 0xFF), 0x55, 0x66, 0x77};
373 uint8_t test_data2[8] = {0x11, 0x22, 0x33, 0x44, 0x55, 0x66, 0x77, (uint8_t)((HAL_GetTick() >> 8) & 0xFF)};
392 RCC_OscInitTypeDef RCC_OscInitStruct = {0};
393 RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
397 HAL_PWR_EnableBkUpAccess();
401 __HAL_RCC_PWR_CLK_ENABLE();
402 __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE3);
407 RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
408 RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS;
409 RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
410 RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
411 RCC_OscInitStruct.PLL.PLLM = 4;
412 RCC_OscInitStruct.PLL.PLLN = 96;
413 RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4;
414 RCC_OscInitStruct.PLL.PLLQ = 4;
415 RCC_OscInitStruct.PLL.PLLR = 2;
416 if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
423 RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
424 |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
425 RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
426 RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
427 RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
428 RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
430 if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK)
448 ADC_ChannelConfTypeDef sConfig = {0};
456 hadc1.Instance = ADC1;
457 hadc1.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
458 hadc1.Init.Resolution = ADC_RESOLUTION_12B;
459 hadc1.Init.ScanConvMode = ADC_SCAN_ENABLE;
462 hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING;
463 hadc1.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T2_TRGO;
464 hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT;
465 hadc1.Init.NbrOfConversion = 7;
467 hadc1.Init.EOCSelection = ADC_EOC_SEQ_CONV;
468 if (HAL_ADC_Init(&
hadc1) != HAL_OK)
475 sConfig.Channel = ADC_CHANNEL_0;
476 sConfig.Rank = ADC_REGULAR_RANK_1;
477 sConfig.SamplingTime = ADC_SAMPLETIME_28CYCLES;
478 if (HAL_ADC_ConfigChannel(&
hadc1, &sConfig) != HAL_OK)
485 sConfig.Channel = ADC_CHANNEL_2;
486 sConfig.Rank = ADC_REGULAR_RANK_2;
487 if (HAL_ADC_ConfigChannel(&
hadc1, &sConfig) != HAL_OK)
494 sConfig.Channel = ADC_CHANNEL_6;
495 sConfig.Rank = ADC_REGULAR_RANK_3;
496 if (HAL_ADC_ConfigChannel(&
hadc1, &sConfig) != HAL_OK)
503 sConfig.Channel = ADC_CHANNEL_8;
504 sConfig.Rank = ADC_REGULAR_RANK_4;
505 if (HAL_ADC_ConfigChannel(&
hadc1, &sConfig) != HAL_OK)
512 sConfig.Channel = ADC_CHANNEL_10;
513 sConfig.Rank = ADC_REGULAR_RANK_5;
514 if (HAL_ADC_ConfigChannel(&
hadc1, &sConfig) != HAL_OK)
521 sConfig.Channel = ADC_CHANNEL_12;
522 sConfig.Rank = ADC_REGULAR_RANK_6;
523 if (HAL_ADC_ConfigChannel(&
hadc1, &sConfig) != HAL_OK)
530 sConfig.Rank = ADC_REGULAR_RANK_7;
531 if (HAL_ADC_ConfigChannel(&
hadc1, &sConfig) != HAL_OK)
553 ADC_ChannelConfTypeDef sConfig = {0};
561 hadc2.Instance = ADC2;
562 hadc2.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
563 hadc2.Init.Resolution = ADC_RESOLUTION_12B;
564 hadc2.Init.ScanConvMode = ADC_SCAN_ENABLE;
567 hadc2.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING;
568 hadc2.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T2_TRGO;
569 hadc2.Init.DataAlign = ADC_DATAALIGN_RIGHT;
570 hadc2.Init.NbrOfConversion = 7;
572 hadc2.Init.EOCSelection = ADC_EOC_SEQ_CONV;
573 if (HAL_ADC_Init(&
hadc2) != HAL_OK)
580 sConfig.Channel = ADC_CHANNEL_1;
581 sConfig.Rank = ADC_REGULAR_RANK_1;
582 sConfig.SamplingTime = ADC_SAMPLETIME_28CYCLES;
583 if (HAL_ADC_ConfigChannel(&
hadc2, &sConfig) != HAL_OK)
590 sConfig.Channel = ADC_CHANNEL_3;
591 sConfig.Rank = ADC_REGULAR_RANK_2;
592 if (HAL_ADC_ConfigChannel(&
hadc2, &sConfig) != HAL_OK)
599 sConfig.Channel = ADC_CHANNEL_7;
600 sConfig.Rank = ADC_REGULAR_RANK_3;
601 if (HAL_ADC_ConfigChannel(&
hadc2, &sConfig) != HAL_OK)
608 sConfig.Channel = ADC_CHANNEL_9;
609 sConfig.Rank = ADC_REGULAR_RANK_4;
610 if (HAL_ADC_ConfigChannel(&
hadc2, &sConfig) != HAL_OK)
617 sConfig.Channel = ADC_CHANNEL_11;
618 sConfig.Rank = ADC_REGULAR_RANK_5;
619 if (HAL_ADC_ConfigChannel(&
hadc2, &sConfig) != HAL_OK)
626 sConfig.Channel = ADC_CHANNEL_13;
627 sConfig.Rank = ADC_REGULAR_RANK_6;
628 if (HAL_ADC_ConfigChannel(&
hadc2, &sConfig) != HAL_OK)
635 sConfig.Channel = ADC_CHANNEL_15;
636 sConfig.Rank = ADC_REGULAR_RANK_7;
637 if (HAL_ADC_ConfigChannel(&
hadc2, &sConfig) != HAL_OK)
659 ADC_ChannelConfTypeDef sConfig = {0};
667 hadc3.Instance = ADC3;
668 hadc3.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
669 hadc3.Init.Resolution = ADC_RESOLUTION_12B;
670 hadc3.Init.ScanConvMode = ADC_SCAN_ENABLE;
673 hadc3.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING;
674 hadc3.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T2_TRGO;
675 hadc3.Init.DataAlign = ADC_DATAALIGN_RIGHT;
676 hadc3.Init.NbrOfConversion = 8;
678 hadc3.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
679 if (HAL_ADC_Init(&
hadc3) != HAL_OK)
686 sConfig.Channel = ADC_CHANNEL_4;
687 sConfig.Rank = ADC_REGULAR_RANK_1;
688 sConfig.SamplingTime = ADC_SAMPLETIME_28CYCLES;
689 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
696 sConfig.Channel = ADC_CHANNEL_5;
697 sConfig.Rank = ADC_REGULAR_RANK_2;
698 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
705 sConfig.Channel = ADC_CHANNEL_6;
706 sConfig.Rank = ADC_REGULAR_RANK_3;
707 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
714 sConfig.Channel = ADC_CHANNEL_7;
715 sConfig.Rank = ADC_REGULAR_RANK_4;
716 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
723 sConfig.Channel = ADC_CHANNEL_8;
724 sConfig.Rank = ADC_REGULAR_RANK_5;
725 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
732 sConfig.Channel = ADC_CHANNEL_9;
733 sConfig.Rank = ADC_REGULAR_RANK_6;
734 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
741 sConfig.Channel = ADC_CHANNEL_14;
742 sConfig.Rank = ADC_REGULAR_RANK_7;
743 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
750 sConfig.Channel = ADC_CHANNEL_15;
751 sConfig.Rank = ADC_REGULAR_RANK_8;
752 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
777 hcan1.Instance = CAN1;
778 hcan1.Init.Prescaler = 3;
779 hcan1.Init.Mode = CAN_MODE_NORMAL;
780 hcan1.Init.SyncJumpWidth = CAN_SJW_1TQ;
781 hcan1.Init.TimeSeg1 = CAN_BS1_13TQ;
782 hcan1.Init.TimeSeg2 = CAN_BS2_2TQ;
789 if (HAL_CAN_Init(&
hcan1) != HAL_OK)
794 CAN_FilterTypeDef sFilterConfig;
795 sFilterConfig.FilterBank = 0;
796 sFilterConfig.FilterMode = CAN_FILTERMODE_IDMASK;
797 sFilterConfig.FilterScale = CAN_FILTERSCALE_32BIT;
798 sFilterConfig.FilterIdHigh = 0x0000;
799 sFilterConfig.FilterIdLow = 0x0000;
800 sFilterConfig.FilterMaskIdHigh = 0x0000;
801 sFilterConfig.FilterMaskIdLow = 0x0000;
802 sFilterConfig.FilterFIFOAssignment = CAN_RX_FIFO0;
803 sFilterConfig.FilterActivation =
ENABLE;
804 sFilterConfig.SlaveStartFilterBank = 14;
805 HAL_CAN_ConfigFilter(&
hcan1, &sFilterConfig);
808 HAL_CAN_Stop(&
hcan1);
810 if (HAL_CAN_Start(&
hcan1) != HAL_OK) {
815 if (HAL_CAN_ActivateNotification(&
hcan1, CAN_IT_RX_FIFO0_MSG_PENDING) != HAL_OK) {
820 if (HAL_CAN_ActivateNotification(&
hcan1, CAN_IT_TX_MAILBOX_EMPTY) != HAL_OK) {
842 hcan2.Instance = CAN2;
843 hcan2.Init.Prescaler = 4;
844 hcan2.Init.Mode = CAN_MODE_NORMAL;
845 hcan2.Init.SyncJumpWidth = CAN_SJW_1TQ;
846 hcan2.Init.TimeSeg1 = CAN_BS1_10TQ;
847 hcan2.Init.TimeSeg2 = CAN_BS2_1TQ;
854 if (HAL_CAN_Init(&
hcan2) != HAL_OK)
859 CAN_FilterTypeDef sFilterConfig;
860 sFilterConfig.FilterBank = 0;
861 sFilterConfig.FilterMode = CAN_FILTERMODE_IDMASK;
862 sFilterConfig.FilterScale = CAN_FILTERSCALE_32BIT;
863 sFilterConfig.FilterIdHigh = 0x0000;
864 sFilterConfig.FilterIdLow = 0x0000;
865 sFilterConfig.FilterMaskIdHigh = 0x0000;
866 sFilterConfig.FilterMaskIdLow = 0x0000;
867 sFilterConfig.FilterFIFOAssignment = CAN_RX_FIFO0;
868 sFilterConfig.FilterActivation =
ENABLE;
869 sFilterConfig.SlaveStartFilterBank = 14;
870 HAL_CAN_ConfigFilter(&
hcan2, &sFilterConfig);
873 HAL_CAN_Stop(&
hcan2);
875 if (HAL_CAN_Start(&
hcan2) != HAL_OK) {
880 if (HAL_CAN_ActivateNotification(&
hcan2, CAN_IT_RX_FIFO0_MSG_PENDING) != HAL_OK) {
885 if (HAL_CAN_ActivateNotification(&
hcan2, CAN_IT_TX_MAILBOX_EMPTY) != HAL_OK) {
907 hcan3.Instance = CAN3;
908 hcan3.Init.Prescaler = 16;
909 hcan3.Init.Mode = CAN_MODE_NORMAL;
910 hcan3.Init.SyncJumpWidth = CAN_SJW_1TQ;
911 hcan3.Init.TimeSeg1 = CAN_BS1_1TQ;
912 hcan3.Init.TimeSeg2 = CAN_BS2_1TQ;
919 if (HAL_CAN_Init(&
hcan3) != HAL_OK)
941 DAC_ChannelConfTypeDef sConfig = {0};
950 if (HAL_DAC_Init(&
hdac) != HAL_OK)
957 sConfig.DAC_Trigger = DAC_TRIGGER_T2_TRGO;
958 sConfig.DAC_OutputBuffer = DAC_OUTPUTBUFFER_ENABLE;
959 if (HAL_DAC_ConfigChannel(&
hdac, &sConfig, DAC_CHANNEL_1) != HAL_OK)
966 if (HAL_DAC_ConfigChannel(&
hdac, &sConfig, DAC_CHANNEL_2) != HAL_OK)
991 hi2c2.Instance = I2C2;
992 hi2c2.Init.Timing = 0x00506682;
993 hi2c2.Init.OwnAddress1 = 0;
994 hi2c2.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
995 hi2c2.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
996 hi2c2.Init.OwnAddress2 = 0;
997 hi2c2.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
998 hi2c2.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
999 hi2c2.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
1000 if (HAL_I2C_Init(&
hi2c2) != HAL_OK)
1007 if (HAL_I2CEx_ConfigAnalogFilter(&
hi2c2, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
1014 if (HAL_I2CEx_ConfigDigitalFilter(&
hi2c2, 0) != HAL_OK)
1039 hi2c4.Instance = I2C4;
1040 hi2c4.Init.Timing = 0x00506682;
1041 hi2c4.Init.OwnAddress1 = 0;
1042 hi2c4.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
1043 hi2c4.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
1044 hi2c4.Init.OwnAddress2 = 0;
1045 hi2c4.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
1046 hi2c4.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
1047 hi2c4.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
1048 if (HAL_I2C_Init(&
hi2c4) != HAL_OK)
1055 if (HAL_I2CEx_ConfigAnalogFilter(&
hi2c4, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
1062 if (HAL_I2CEx_ConfigDigitalFilter(&
hi2c4, 0) != HAL_OK)
1088 hspi4.Instance = SPI4;
1089 hspi4.Init.Mode = SPI_MODE_MASTER;
1090 hspi4.Init.Direction = SPI_DIRECTION_2LINES;
1091 hspi4.Init.DataSize = SPI_DATASIZE_4BIT;
1092 hspi4.Init.CLKPolarity = SPI_POLARITY_LOW;
1093 hspi4.Init.CLKPhase = SPI_PHASE_1EDGE;
1094 hspi4.Init.NSS = SPI_NSS_SOFT;
1095 hspi4.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
1096 hspi4.Init.FirstBit = SPI_FIRSTBIT_MSB;
1097 hspi4.Init.TIMode = SPI_TIMODE_DISABLE;
1098 hspi4.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
1099 hspi4.Init.CRCPolynomial = 7;
1100 hspi4.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
1101 hspi4.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
1102 if (HAL_SPI_Init(&
hspi4) != HAL_OK)
1128 hspi6.Instance = SPI6;
1129 hspi6.Init.Mode = SPI_MODE_MASTER;
1130 hspi6.Init.Direction = SPI_DIRECTION_2LINES;
1131 hspi6.Init.DataSize = SPI_DATASIZE_4BIT;
1132 hspi6.Init.CLKPolarity = SPI_POLARITY_LOW;
1133 hspi6.Init.CLKPhase = SPI_PHASE_1EDGE;
1134 hspi6.Init.NSS = SPI_NSS_SOFT;
1135 hspi6.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
1136 hspi6.Init.FirstBit = SPI_FIRSTBIT_MSB;
1137 hspi6.Init.TIMode = SPI_TIMODE_DISABLE;
1138 hspi6.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
1139 hspi6.Init.CRCPolynomial = 7;
1140 hspi6.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
1141 hspi6.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
1142 if (HAL_SPI_Init(&
hspi6) != HAL_OK)
1164 TIM_ClockConfigTypeDef sClockSourceConfig = {0};
1165 TIM_MasterConfigTypeDef sMasterConfig = {0};
1170 htim1.Instance = TIM1;
1171 htim1.Init.Prescaler = 47999;
1172 htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
1173 htim1.Init.Period = 999;
1174 htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
1175 htim1.Init.RepetitionCounter = 0;
1176 htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
1177 if (HAL_TIM_Base_Init(&
htim1) != HAL_OK)
1181 sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
1182 if (HAL_TIM_ConfigClockSource(&
htim1, &sClockSourceConfig) != HAL_OK)
1186 sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
1187 sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET;
1188 sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
1189 if (HAL_TIMEx_MasterConfigSynchronization(&
htim1, &sMasterConfig) != HAL_OK)
1211 TIM_ClockConfigTypeDef sClockSourceConfig = {0};
1212 TIM_MasterConfigTypeDef sMasterConfig = {0};
1217 htim2.Instance = TIM2;
1218 htim2.Init.Prescaler = 0;
1219 htim2.Init.CounterMode = TIM_COUNTERMODE_UP;
1220 htim2.Init.Period = 479999;
1221 htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
1222 htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
1223 if (HAL_TIM_Base_Init(&
htim2) != HAL_OK)
1227 sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
1228 if (HAL_TIM_ConfigClockSource(&
htim2, &sClockSourceConfig) != HAL_OK)
1232 sMasterConfig.MasterOutputTrigger = TIM_TRGO_UPDATE;
1233 sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
1234 if (HAL_TIMEx_MasterConfigSynchronization(&
htim2, &sMasterConfig) != HAL_OK)
1239 if (HAL_TIM_Base_Start_IT(&
htim2) != HAL_OK) {
1261 huart3.Instance = USART3;
1262 huart3.Init.BaudRate = 115200;
1263 huart3.Init.WordLength = UART_WORDLENGTH_8B;
1264 huart3.Init.StopBits = UART_STOPBITS_1;
1265 huart3.Init.Parity = UART_PARITY_NONE;
1266 huart3.Init.Mode = UART_MODE_TX_RX;
1267 huart3.Init.HwFlowCtl = UART_HWCONTROL_NONE;
1268 huart3.Init.OverSampling = UART_OVERSAMPLING_16;
1269 huart3.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
1270 huart3.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
1271 if (HAL_UART_Init(&
huart3) != HAL_OK)
1288 __HAL_RCC_DMA2_CLK_ENABLE();
1289 __HAL_RCC_DMA1_CLK_ENABLE();
1293 HAL_NVIC_SetPriority(DMA1_Stream5_IRQn, 5, 0);
1294 HAL_NVIC_EnableIRQ(DMA1_Stream5_IRQn);
1296 HAL_NVIC_SetPriority(DMA1_Stream6_IRQn, 5, 0);
1297 HAL_NVIC_EnableIRQ(DMA1_Stream6_IRQn);
1299 HAL_NVIC_SetPriority(DMA2_Stream0_IRQn, 5, 0);
1300 HAL_NVIC_EnableIRQ(DMA2_Stream0_IRQn);
1302 HAL_NVIC_SetPriority(DMA2_Stream1_IRQn, 5, 0);
1303 HAL_NVIC_EnableIRQ(DMA2_Stream1_IRQn);
1305 HAL_NVIC_SetPriority(DMA2_Stream2_IRQn, 5, 0);
1306 HAL_NVIC_EnableIRQ(DMA2_Stream2_IRQn);
1317 GPIO_InitTypeDef GPIO_InitStruct = {0};
1322 __HAL_RCC_GPIOE_CLK_ENABLE();
1323 __HAL_RCC_GPIOC_CLK_ENABLE();
1324 __HAL_RCC_GPIOF_CLK_ENABLE();
1325 __HAL_RCC_GPIOH_CLK_ENABLE();
1326 __HAL_RCC_GPIOA_CLK_ENABLE();
1327 __HAL_RCC_GPIOB_CLK_ENABLE();
1328 __HAL_RCC_GPIOG_CLK_ENABLE();
1329 __HAL_RCC_GPIOD_CLK_ENABLE();
1332 HAL_GPIO_WritePin(GPIOF, GPIO_PIN_12|GPIO_PIN_13, GPIO_PIN_RESET);
1335 HAL_GPIO_WritePin(GPIOE, GPIO_PIN_7|GPIO_PIN_8|GPIO_PIN_9|GPIO_PIN_11
1336 |GPIO_PIN_13, GPIO_PIN_RESET);
1339 HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14|GPIO_PIN_15, GPIO_PIN_RESET);
1342 HAL_GPIO_WritePin(GPIOG, GPIO_PIN_9, GPIO_PIN_RESET);
1349 GPIO_InitStruct.Pin = GPIO_PIN_3|GPIO_PIN_4|GPIO_PIN_10|GPIO_PIN_12
1350 |GPIO_PIN_14|GPIO_PIN_15|GPIO_PIN_0|GPIO_PIN_1;
1351 GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
1352 GPIO_InitStruct.Pull = GPIO_NOPULL;
1353 HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
1357 GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
1358 GPIO_InitStruct.Pull = GPIO_NOPULL;
1362 GPIO_InitStruct.Pin = GPIO_PIN_2|GPIO_PIN_11;
1363 GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
1364 GPIO_InitStruct.Pull = GPIO_NOPULL;
1365 HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);
1369 GPIO_InitStruct.Pin = GPIO_PIN_2|GPIO_PIN_10|GPIO_PIN_11|GPIO_PIN_12
1370 |GPIO_PIN_14|GPIO_PIN_15|GPIO_PIN_4|GPIO_PIN_6;
1371 GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
1372 GPIO_InitStruct.Pull = GPIO_NOPULL;
1373 HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
1376 GPIO_InitStruct.Pin = GPIO_PIN_12|GPIO_PIN_13;
1377 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
1378 GPIO_InitStruct.Pull = GPIO_NOPULL;
1379 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
1380 HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);
1385 GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_3
1386 |GPIO_PIN_4|GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_8
1387 |GPIO_PIN_10|GPIO_PIN_11|GPIO_PIN_15;
1388 GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
1389 GPIO_InitStruct.Pull = GPIO_NOPULL;
1390 HAL_GPIO_Init(GPIOG, &GPIO_InitStruct);
1394 GPIO_InitStruct.Pin = GPIO_PIN_7|GPIO_PIN_8|GPIO_PIN_9|GPIO_PIN_11
1396 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
1397 GPIO_InitStruct.Pull = GPIO_NOPULL;
1398 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
1399 HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
1404 GPIO_InitStruct.Pin = GPIO_PIN_10|GPIO_PIN_11|GPIO_PIN_12|GPIO_PIN_13
1405 |GPIO_PIN_3|GPIO_PIN_4|GPIO_PIN_5|GPIO_PIN_6
1407 GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
1408 GPIO_InitStruct.Pull = GPIO_NOPULL;
1409 HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
1412 GPIO_InitStruct.Pin = GPIO_PIN_14|GPIO_PIN_15;
1413 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
1414 GPIO_InitStruct.Pull = GPIO_NOPULL;
1415 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
1416 HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
1420 GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
1421 GPIO_InitStruct.Pull = GPIO_NOPULL;
1426 GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7|GPIO_PIN_8|GPIO_PIN_9
1427 |GPIO_PIN_10|GPIO_PIN_11|GPIO_PIN_12;
1428 GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
1429 GPIO_InitStruct.Pull = GPIO_NOPULL;
1430 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
1431 GPIO_InitStruct.Alternate = GPIO_AF12_SDMMC1;
1432 HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
1435 GPIO_InitStruct.Pin = GPIO_PIN_9|GPIO_PIN_10|GPIO_PIN_11|GPIO_PIN_12;
1436 GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
1437 GPIO_InitStruct.Pull = GPIO_NOPULL;
1438 HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
1441 GPIO_InitStruct.Pin = GPIO_PIN_2;
1442 GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
1443 GPIO_InitStruct.Pull = GPIO_NOPULL;
1444 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
1445 GPIO_InitStruct.Alternate = GPIO_AF12_SDMMC1;
1446 HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
1449 GPIO_InitStruct.Pin = GPIO_PIN_9;
1450 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
1451 GPIO_InitStruct.Pull = GPIO_NOPULL;
1452 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
1453 HAL_GPIO_Init(GPIOG, &GPIO_InitStruct);
1456 GPIO_InitStruct.Pin =
LD2_Pin;
1457 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
1458 GPIO_InitStruct.Pull = GPIO_NOPULL;
1459 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
1463 GPIO_InitStruct.Pin = GPIO_PIN_8|GPIO_PIN_9;
1464 GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
1465 GPIO_InitStruct.Pull = GPIO_NOPULL;
1466 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
1467 GPIO_InitStruct.Alternate = GPIO_AF12_SDMMC1;
1468 HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
1479 HAL_UART_Transmit(&
huart3, (uint8_t *)data, len, HAL_MAX_DELAY);
1546#ifdef USE_FULL_ASSERT
1554void assert_failed(uint8_t *file, uint32_t line)
void initAppsMonitor(AppsMonitor *am, Apps *apps, int hz)
int startAppsMonitor(AppsMonitor *am)
void initApps(Apps *apps, int hz, int channel1, int channel2)
Initializes the APPs with the given frequency and channel.
int startBrakePolice(BrakePolice *bp)
void initBrakePolice(BrakePolice *bp, BrakeSystemControl *bsc, int hz, int maxTemp)
void initBrakeSystemControl(BrakeSystemControl *bsc, int hz, int maxTemp, int brakeLightActivationPoint, int heavyBrakingActivationPoint, int fbp_channel, int rbp_channel, int temp_channel, int light_port)
Initializes the Braking System with initial settings.
int startBrakeSystemControl(BrakeSystemControl *bsc)
Starts the Brake System Controller.
int init_CANBus(CANBus bus)
Initializes the CANBus struct.
int add_message_lop(CANBus bus, int id, int dlc, int ide, int rtr, const char *name, const char *sender, int signal_count, CAN_Signal_Template *signals)
Adds a message to the CAN message list by passing in the individual message parameters hence "LOP" (L...
int send_CAN_message(CANBus bus, CANProtocol protocol, uint32_t id, uint8_t *data, uint8_t len)
Sends a CAN message.
void print_CAN_Messages_Lists()
Prints the CAN message list.
#define ADC2_CHANNEL_SIZE
#define NUM_DIGITAL_INPUTS
#define NUM_DIGITAL_OUTPUTS
#define ADC1_CHANNEL_SIZE
#define ADC3_CHANNEL_SIZE
void initInverter(Inverter *inverter, TorqueControl *tc, int hz, int maxCurrent, int maxTemp, int maxVoltage)
Initializes the Inverter with initial settings.
void initRTDMonitor(RTDMonitor *rtdm, RTD *rtd, int hz)
Initializes the RTD Monitor with initial settings.
int startRTDMonitor(RTDMonitor *rtdm)
Starts the RTD Monitor.
int startRTD(RTD *rtd)
Starts the RTD Actuator.
void initRTD(RTD *rtd, Apps *apps, BrakeSystemControl *bsc, int hz, int buttonPort, int piezoPort)
Initializes the RTD Actuator with initial settings.
void SchedulerInit(Scheduler *scheduler, Updateable *updatableArray[])
void SchedulerRun(Scheduler *scheduler)
static void MX_CAN3_Init(void)
CAN3 Initialization Function.
DMA_HandleTypeDef hdma_dac1
void Error_Handler(void)
This function is executed in case of error occurrence.
uint32_t adc3_buffer[ADC3_CHANNEL_SIZE]
DMA_HandleTypeDef hdma_adc1
static void MX_USART3_UART_Init(void)
USART3 Initialization Function.
static void MX_TIM1_Init(void)
TIM1 Initialization Function.
const osThreadAttr_t defaultTask_attributes
static void MX_CAN1_Init(void)
CAN1 Initialization Function.
DMA_HandleTypeDef hdma_adc3
uint8_t digital_in_buffer[NUM_DIGITAL_INPUTS]
static void MX_ADC2_Init(void)
ADC2 Initialization Function.
void vApplicationStackOverflowHook(TaskHandle_t xTask, char *pcTaskName)
static void MX_SPI6_Init(void)
SPI6 Initialization Function.
static void MX_DMA_Init(void)
uint32_t adc2_buffer[ADC2_CHANNEL_SIZE]
osThreadId_t defaultTaskHandle
void SystemClock_Config(void)
System Clock Configuration.
int main(void)
The application entry point.
int _write(int file, char *data, int len)
static void MX_CAN2_Init(void)
CAN2 Initialization Function.
uint32_t dac2_buffer[DAC2_BUFFER_SIZE]
void vApplicationIdleHook(void)
void StartDefaultTask(void *argument)
Function implementing the defaultTask thread.
void vApplicationTickHook(void)
static void MX_ADC1_Init(void)
ADC1 Initialization Function.
uint8_t digital_out_buffer[NUM_DIGITAL_OUTPUTS]
DMA_HandleTypeDef hdma_dac2
UART_HandleTypeDef huart3
void vApplicationMallocFailedHook(void)
DMA_HandleTypeDef hdma_adc2
static void MX_ADC3_Init(void)
ADC3 Initialization Function.
static void MX_SPI4_Init(void)
SPI4 Initialization Function.
static void MX_GPIO_Init(void)
GPIO Initialization Function.
static void MX_DAC_Init(void)
DAC Initialization Function.
static void MX_I2C4_Init(void)
I2C4 Initialization Function.
static void MX_I2C2_Init(void)
I2C2 Initialization Function.
uint32_t adc1_buffer[ADC1_CHANNEL_SIZE]
static void MX_TIM2_Init(void)
TIM2 Initialization Function.
uint32_t dac1_buffer[DAC1_BUFFER_SIZE]
static TelemetrySignal signals[MAX_TELEMETRY_SIGNALS]
int startTorqueControl(TorqueControl *tc)
Starts the Torque Control Actuator.
void initTorqueControl(TorqueControl *tc, Apps *apps, int hz, float maxTorque)
Initializes the Torque Control Actuator with initial settings.
void initTorquePolice(TorquePolice *tp, TorqueControl *tc, BrakeSystemControl *bsc, RTD *rtd, int hz, float maxTorque)
int startTorquePolice(TorquePolice *tp)
: Header for main.c file. This file contains the common defines of the application.
#define USB_OverCurrent_GPIO_Port
#define USB_OverCurrent_Pin
#define USER_Btn_GPIO_Port
void initUartConfigListener(void)
This file contains the headers of the interrupt handlers.
int(* addMonitor)(struct ControllerSystem *controller, MonitorSystem *monitor)