24#include "../Inc/Files/can1_dbc.h"
25#include "../Inc/Scheduler/Scheduler.h"
26#include "../Inc/Sensors/AnalogSensor.h"
27#include "../Inc/Systems/Comms/Can/Can.h"
28#include "../Inc/Systems/Controller/Apps.h"
29#include "../Inc/Systems/Controller/BrakeSystemControl.h"
30#include "../Inc/Systems/Controller/RTD.h"
31#include "../Inc/Systems/Controller/TorqueControl.h"
32#include "../Inc/Systems/External/Inverter.h"
33#include "../Inc/Systems/Monitor/AppsMonitor.h"
34#include "../Inc/Systems/Monitor/BrakePolice.h"
35#include "../Inc/Systems/Monitor/RTDMonitor.h"
36#include "../Inc/Systems/Monitor/TorquePolice.h"
37#include "../Inc/Utils/Constants.h"
40#include "stm32f7xx_hal_adc.h"
172 printf(
"\033[2J\033[1;1H");
173 printf(
"Welcome to VCU!!!\r\n");
175 printf(
"CAN1 init failed\r\n");
196 uint32_t multi_mode = (ADC123_COMMON->CCR & ADC_CCR_MULTI);
197 printf(
"ADC Multi-mode: 0x%08lX\r\n", multi_mode);
203 { .
name =
"VDD", .start_bit = 0, .length = 8, .endian = 0, .isSigned = 0, .scale = 0.1, .offset = 0, .min = 0, .max = 255, .unit =
"voltage", .reciever =
"reciever" },
204 { .name =
"Char 2", .start_bit = 8, .length = 8, .endian = 0, .isSigned = 0, .scale = 1, .offset = 0, .min = 0, .max = 255, .unit =
"unit", .reciever =
"reciever" },
205 { .name =
"Char 3", .start_bit = 16, .length = 8, .endian = 0, .isSigned = 0, .scale = 1, .offset = 0, .min = 0, .max = 255, .unit =
"unit", .reciever =
"reciever" },
206 { .name =
"Char 4", .start_bit = 24, .length = 8, .endian = 0, .isSigned = 0, .scale = 1, .offset = 0, .min = 0, .max = 255, .unit =
"unit", .reciever =
"reciever" },
207 { .name =
"Char 5", .start_bit = 32, .length = 8, .endian = 0, .isSigned = 0, .scale = 1, .offset = 0, .min = 0, .max = 255, .unit =
"unit", .reciever =
"reciever" },
208 { .name =
"Char 6", .start_bit = 40, .length = 8, .endian = 0, .isSigned = 0, .scale = 1, .offset = 0, .min = 0, .max = 255, .unit =
"unit", .reciever =
"reciever" },
209 { .name =
"Char 7", .start_bit = 48, .length = 8, .endian = 0, .isSigned = 0, .scale = 1, .offset = 0, .min = 0, .max = 255, .unit =
"unit", .reciever =
"reciever" },
210 { .name =
"Char 8", .start_bit = 56, .length = 8, .endian = 0, .isSigned = 0, .scale = 1, .offset = 0, .min = 0, .max = 255, .unit =
"unit", .reciever =
"reciever" }
221 uint8_t txdata[8] = {0, 1, 2, 3, 4, 5, 6, 7};
253 initRTD(&rtd, &apps, &bsc, 10, 0, 1);
292 updateables[5] = NULL;
319 RCC_OscInitTypeDef RCC_OscInitStruct = {0};
320 RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
324 HAL_PWR_EnableBkUpAccess();
328 __HAL_RCC_PWR_CLK_ENABLE();
329 __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE3);
334 RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
335 RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS;
336 RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
337 RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
338 RCC_OscInitStruct.PLL.PLLM = 4;
339 RCC_OscInitStruct.PLL.PLLN = 96;
340 RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4;
341 RCC_OscInitStruct.PLL.PLLQ = 4;
342 RCC_OscInitStruct.PLL.PLLR = 2;
343 if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
350 RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
351 |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
352 RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
353 RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
354 RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
355 RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
357 if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK)
375 ADC_ChannelConfTypeDef sConfig = {0};
383 hadc1.Instance = ADC1;
384 hadc1.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
385 hadc1.Init.Resolution = ADC_RESOLUTION_12B;
386 hadc1.Init.ScanConvMode = ADC_SCAN_ENABLE;
389 hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING;
390 hadc1.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T2_TRGO;
391 hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT;
392 hadc1.Init.NbrOfConversion = 7;
394 hadc1.Init.EOCSelection = ADC_EOC_SEQ_CONV;
395 if (HAL_ADC_Init(&
hadc1) != HAL_OK)
402 sConfig.Channel = ADC_CHANNEL_0;
403 sConfig.Rank = ADC_REGULAR_RANK_1;
404 sConfig.SamplingTime = ADC_SAMPLETIME_28CYCLES;
405 if (HAL_ADC_ConfigChannel(&
hadc1, &sConfig) != HAL_OK)
412 sConfig.Channel = ADC_CHANNEL_2;
413 sConfig.Rank = ADC_REGULAR_RANK_2;
414 if (HAL_ADC_ConfigChannel(&
hadc1, &sConfig) != HAL_OK)
421 sConfig.Channel = ADC_CHANNEL_6;
422 sConfig.Rank = ADC_REGULAR_RANK_3;
423 if (HAL_ADC_ConfigChannel(&
hadc1, &sConfig) != HAL_OK)
430 sConfig.Channel = ADC_CHANNEL_8;
431 sConfig.Rank = ADC_REGULAR_RANK_4;
432 if (HAL_ADC_ConfigChannel(&
hadc1, &sConfig) != HAL_OK)
439 sConfig.Channel = ADC_CHANNEL_10;
440 sConfig.Rank = ADC_REGULAR_RANK_5;
441 if (HAL_ADC_ConfigChannel(&
hadc1, &sConfig) != HAL_OK)
448 sConfig.Channel = ADC_CHANNEL_12;
449 sConfig.Rank = ADC_REGULAR_RANK_6;
450 if (HAL_ADC_ConfigChannel(&
hadc1, &sConfig) != HAL_OK)
457 sConfig.Rank = ADC_REGULAR_RANK_7;
458 if (HAL_ADC_ConfigChannel(&
hadc1, &sConfig) != HAL_OK)
480 ADC_ChannelConfTypeDef sConfig = {0};
488 hadc2.Instance = ADC2;
489 hadc2.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
490 hadc2.Init.Resolution = ADC_RESOLUTION_12B;
491 hadc2.Init.ScanConvMode = ADC_SCAN_ENABLE;
494 hadc2.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING;
495 hadc2.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T2_TRGO;
496 hadc2.Init.DataAlign = ADC_DATAALIGN_RIGHT;
497 hadc2.Init.NbrOfConversion = 7;
499 hadc2.Init.EOCSelection = ADC_EOC_SEQ_CONV;
500 if (HAL_ADC_Init(&
hadc2) != HAL_OK)
507 sConfig.Channel = ADC_CHANNEL_1;
508 sConfig.Rank = ADC_REGULAR_RANK_1;
509 sConfig.SamplingTime = ADC_SAMPLETIME_28CYCLES;
510 if (HAL_ADC_ConfigChannel(&
hadc2, &sConfig) != HAL_OK)
517 sConfig.Channel = ADC_CHANNEL_3;
518 sConfig.Rank = ADC_REGULAR_RANK_2;
519 if (HAL_ADC_ConfigChannel(&
hadc2, &sConfig) != HAL_OK)
526 sConfig.Channel = ADC_CHANNEL_7;
527 sConfig.Rank = ADC_REGULAR_RANK_3;
528 if (HAL_ADC_ConfigChannel(&
hadc2, &sConfig) != HAL_OK)
535 sConfig.Channel = ADC_CHANNEL_9;
536 sConfig.Rank = ADC_REGULAR_RANK_4;
537 if (HAL_ADC_ConfigChannel(&
hadc2, &sConfig) != HAL_OK)
544 sConfig.Channel = ADC_CHANNEL_11;
545 sConfig.Rank = ADC_REGULAR_RANK_5;
546 if (HAL_ADC_ConfigChannel(&
hadc2, &sConfig) != HAL_OK)
553 sConfig.Channel = ADC_CHANNEL_13;
554 sConfig.Rank = ADC_REGULAR_RANK_6;
555 if (HAL_ADC_ConfigChannel(&
hadc2, &sConfig) != HAL_OK)
562 sConfig.Channel = ADC_CHANNEL_15;
563 sConfig.Rank = ADC_REGULAR_RANK_7;
564 if (HAL_ADC_ConfigChannel(&
hadc2, &sConfig) != HAL_OK)
586 ADC_ChannelConfTypeDef sConfig = {0};
594 hadc3.Instance = ADC3;
595 hadc3.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
596 hadc3.Init.Resolution = ADC_RESOLUTION_12B;
597 hadc3.Init.ScanConvMode = ADC_SCAN_ENABLE;
600 hadc3.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING;
601 hadc3.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T2_TRGO;
602 hadc3.Init.DataAlign = ADC_DATAALIGN_RIGHT;
603 hadc3.Init.NbrOfConversion = 8;
605 hadc3.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
606 if (HAL_ADC_Init(&
hadc3) != HAL_OK)
613 sConfig.Channel = ADC_CHANNEL_4;
614 sConfig.Rank = ADC_REGULAR_RANK_1;
615 sConfig.SamplingTime = ADC_SAMPLETIME_28CYCLES;
616 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
623 sConfig.Channel = ADC_CHANNEL_5;
624 sConfig.Rank = ADC_REGULAR_RANK_2;
625 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
632 sConfig.Channel = ADC_CHANNEL_6;
633 sConfig.Rank = ADC_REGULAR_RANK_3;
634 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
641 sConfig.Channel = ADC_CHANNEL_7;
642 sConfig.Rank = ADC_REGULAR_RANK_4;
643 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
650 sConfig.Channel = ADC_CHANNEL_8;
651 sConfig.Rank = ADC_REGULAR_RANK_5;
652 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
659 sConfig.Channel = ADC_CHANNEL_9;
660 sConfig.Rank = ADC_REGULAR_RANK_6;
661 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
668 sConfig.Channel = ADC_CHANNEL_14;
669 sConfig.Rank = ADC_REGULAR_RANK_7;
670 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
677 sConfig.Channel = ADC_CHANNEL_15;
678 sConfig.Rank = ADC_REGULAR_RANK_8;
679 if (HAL_ADC_ConfigChannel(&
hadc3, &sConfig) != HAL_OK)
704 hcan1.Instance = CAN1;
705 hcan1.Init.Prescaler = 3;
706 hcan1.Init.Mode = CAN_MODE_NORMAL;
707 hcan1.Init.SyncJumpWidth = CAN_SJW_1TQ;
708 hcan1.Init.TimeSeg1 = CAN_BS1_13TQ;
709 hcan1.Init.TimeSeg2 = CAN_BS2_2TQ;
716 if (HAL_CAN_Init(&
hcan1) != HAL_OK)
721 CAN_FilterTypeDef sFilterConfig;
722 sFilterConfig.FilterBank = 0;
723 sFilterConfig.FilterMode = CAN_FILTERMODE_IDMASK;
724 sFilterConfig.FilterScale = CAN_FILTERSCALE_32BIT;
725 sFilterConfig.FilterIdHigh = 0x0000;
726 sFilterConfig.FilterIdLow = 0x0000;
727 sFilterConfig.FilterMaskIdHigh = 0x0000;
728 sFilterConfig.FilterMaskIdLow = 0x0000;
729 sFilterConfig.FilterFIFOAssignment = CAN_RX_FIFO0;
730 sFilterConfig.FilterActivation =
ENABLE;
731 sFilterConfig.SlaveStartFilterBank = 14;
732 HAL_CAN_ConfigFilter(&
hcan1, &sFilterConfig);
735 HAL_CAN_Stop(&
hcan1);
737 if (HAL_CAN_Start(&
hcan1) != HAL_OK) {
738 printf(
"CAN1 Start Error: ErrorCode = 0x%lX\r\n",
hcan1.ErrorCode);
742 if (HAL_CAN_ActivateNotification(&
hcan1, CAN_IT_RX_FIFO0_MSG_PENDING) != HAL_OK) {
743 printf(
"interrupt CAN1 init failed\r\n");
764 hcan2.Instance = CAN2;
765 hcan2.Init.Prescaler = 4;
766 hcan2.Init.Mode = CAN_MODE_NORMAL;
767 hcan2.Init.SyncJumpWidth = CAN_SJW_1TQ;
768 hcan2.Init.TimeSeg1 = CAN_BS1_10TQ;
769 hcan2.Init.TimeSeg2 = CAN_BS2_1TQ;
776 if (HAL_CAN_Init(&
hcan2) != HAL_OK)
781 CAN_FilterTypeDef sFilterConfig;
782 sFilterConfig.FilterBank = 0;
783 sFilterConfig.FilterMode = CAN_FILTERMODE_IDMASK;
784 sFilterConfig.FilterScale = CAN_FILTERSCALE_32BIT;
785 sFilterConfig.FilterIdHigh = 0x0000;
786 sFilterConfig.FilterIdLow = 0x0000;
787 sFilterConfig.FilterMaskIdHigh = 0x0000;
788 sFilterConfig.FilterMaskIdLow = 0x0000;
789 sFilterConfig.FilterFIFOAssignment = CAN_RX_FIFO0;
790 sFilterConfig.FilterActivation =
ENABLE;
791 sFilterConfig.SlaveStartFilterBank = 14;
792 HAL_CAN_ConfigFilter(&
hcan2, &sFilterConfig);
795 HAL_CAN_Stop(&
hcan2);
797 if (HAL_CAN_Start(&
hcan2) != HAL_OK) {
798 printf(
"CAN2 Start Error: ErrorCode = 0x%lX\r\n",
hcan2.ErrorCode);
802 if (HAL_CAN_ActivateNotification(&
hcan2, CAN_IT_RX_FIFO0_MSG_PENDING) != HAL_OK) {
803 printf(
"interrupt CAN2 init failed\r\n");
824 hcan3.Instance = CAN3;
825 hcan3.Init.Prescaler = 16;
826 hcan3.Init.Mode = CAN_MODE_NORMAL;
827 hcan3.Init.SyncJumpWidth = CAN_SJW_1TQ;
828 hcan3.Init.TimeSeg1 = CAN_BS1_1TQ;
829 hcan3.Init.TimeSeg2 = CAN_BS2_1TQ;
836 if (HAL_CAN_Init(&
hcan3) != HAL_OK)
858 DAC_ChannelConfTypeDef sConfig = {0};
867 if (HAL_DAC_Init(&
hdac) != HAL_OK)
874 sConfig.DAC_Trigger = DAC_TRIGGER_T2_TRGO;
875 sConfig.DAC_OutputBuffer = DAC_OUTPUTBUFFER_ENABLE;
876 if (HAL_DAC_ConfigChannel(&
hdac, &sConfig, DAC_CHANNEL_1) != HAL_OK)
883 if (HAL_DAC_ConfigChannel(&
hdac, &sConfig, DAC_CHANNEL_2) != HAL_OK)
908 hi2c2.Instance = I2C2;
909 hi2c2.Init.Timing = 0x00506682;
910 hi2c2.Init.OwnAddress1 = 0;
911 hi2c2.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
912 hi2c2.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
913 hi2c2.Init.OwnAddress2 = 0;
914 hi2c2.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
915 hi2c2.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
916 hi2c2.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
917 if (HAL_I2C_Init(&
hi2c2) != HAL_OK)
924 if (HAL_I2CEx_ConfigAnalogFilter(&
hi2c2, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
931 if (HAL_I2CEx_ConfigDigitalFilter(&
hi2c2, 0) != HAL_OK)
956 hi2c4.Instance = I2C4;
957 hi2c4.Init.Timing = 0x00506682;
958 hi2c4.Init.OwnAddress1 = 0;
959 hi2c4.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
960 hi2c4.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
961 hi2c4.Init.OwnAddress2 = 0;
962 hi2c4.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
963 hi2c4.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
964 hi2c4.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
965 if (HAL_I2C_Init(&
hi2c4) != HAL_OK)
972 if (HAL_I2CEx_ConfigAnalogFilter(&
hi2c4, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
979 if (HAL_I2CEx_ConfigDigitalFilter(&
hi2c4, 0) != HAL_OK)
1005 hspi4.Instance = SPI4;
1006 hspi4.Init.Mode = SPI_MODE_MASTER;
1007 hspi4.Init.Direction = SPI_DIRECTION_2LINES;
1008 hspi4.Init.DataSize = SPI_DATASIZE_4BIT;
1009 hspi4.Init.CLKPolarity = SPI_POLARITY_LOW;
1010 hspi4.Init.CLKPhase = SPI_PHASE_1EDGE;
1011 hspi4.Init.NSS = SPI_NSS_SOFT;
1012 hspi4.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
1013 hspi4.Init.FirstBit = SPI_FIRSTBIT_MSB;
1014 hspi4.Init.TIMode = SPI_TIMODE_DISABLE;
1015 hspi4.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
1016 hspi4.Init.CRCPolynomial = 7;
1017 hspi4.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
1018 hspi4.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
1019 if (HAL_SPI_Init(&
hspi4) != HAL_OK)
1045 hspi6.Instance = SPI6;
1046 hspi6.Init.Mode = SPI_MODE_MASTER;
1047 hspi6.Init.Direction = SPI_DIRECTION_2LINES;
1048 hspi6.Init.DataSize = SPI_DATASIZE_4BIT;
1049 hspi6.Init.CLKPolarity = SPI_POLARITY_LOW;
1050 hspi6.Init.CLKPhase = SPI_PHASE_1EDGE;
1051 hspi6.Init.NSS = SPI_NSS_SOFT;
1052 hspi6.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
1053 hspi6.Init.FirstBit = SPI_FIRSTBIT_MSB;
1054 hspi6.Init.TIMode = SPI_TIMODE_DISABLE;
1055 hspi6.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
1056 hspi6.Init.CRCPolynomial = 7;
1057 hspi6.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
1058 hspi6.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
1059 if (HAL_SPI_Init(&
hspi6) != HAL_OK)
1081 TIM_ClockConfigTypeDef sClockSourceConfig = {0};
1082 TIM_MasterConfigTypeDef sMasterConfig = {0};
1087 htim1.Instance = TIM1;
1088 htim1.Init.Prescaler = 47999;
1089 htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
1090 htim1.Init.Period = 999;
1091 htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
1092 htim1.Init.RepetitionCounter = 0;
1093 htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
1094 if (HAL_TIM_Base_Init(&
htim1) != HAL_OK)
1098 sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
1099 if (HAL_TIM_ConfigClockSource(&
htim1, &sClockSourceConfig) != HAL_OK)
1103 sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
1104 sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET;
1105 sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
1106 if (HAL_TIMEx_MasterConfigSynchronization(&
htim1, &sMasterConfig) != HAL_OK)
1128 TIM_ClockConfigTypeDef sClockSourceConfig = {0};
1129 TIM_MasterConfigTypeDef sMasterConfig = {0};
1134 htim2.Instance = TIM2;
1135 htim2.Init.Prescaler = 0;
1136 htim2.Init.CounterMode = TIM_COUNTERMODE_UP;
1137 htim2.Init.Period = 479999;
1138 htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
1139 htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
1140 if (HAL_TIM_Base_Init(&
htim2) != HAL_OK)
1144 sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
1145 if (HAL_TIM_ConfigClockSource(&
htim2, &sClockSourceConfig) != HAL_OK)
1149 sMasterConfig.MasterOutputTrigger = TIM_TRGO_UPDATE;
1150 sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
1151 if (HAL_TIMEx_MasterConfigSynchronization(&
htim2, &sMasterConfig) != HAL_OK)
1156 if (HAL_TIM_Base_Start_IT(&
htim2) != HAL_OK) {
1178 huart3.Instance = USART3;
1179 huart3.Init.BaudRate = 115200;
1180 huart3.Init.WordLength = UART_WORDLENGTH_8B;
1181 huart3.Init.StopBits = UART_STOPBITS_1;
1182 huart3.Init.Parity = UART_PARITY_NONE;
1183 huart3.Init.Mode = UART_MODE_TX_RX;
1184 huart3.Init.HwFlowCtl = UART_HWCONTROL_NONE;
1185 huart3.Init.OverSampling = UART_OVERSAMPLING_16;
1186 huart3.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
1187 huart3.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
1188 if (HAL_UART_Init(&
huart3) != HAL_OK)
1205 __HAL_RCC_DMA2_CLK_ENABLE();
1206 __HAL_RCC_DMA1_CLK_ENABLE();
1210 HAL_NVIC_SetPriority(DMA1_Stream5_IRQn, 0, 0);
1211 HAL_NVIC_EnableIRQ(DMA1_Stream5_IRQn);
1213 HAL_NVIC_SetPriority(DMA1_Stream6_IRQn, 0, 0);
1214 HAL_NVIC_EnableIRQ(DMA1_Stream6_IRQn);
1216 HAL_NVIC_SetPriority(DMA2_Stream0_IRQn, 0, 0);
1217 HAL_NVIC_EnableIRQ(DMA2_Stream0_IRQn);
1219 HAL_NVIC_SetPriority(DMA2_Stream1_IRQn, 0, 0);
1220 HAL_NVIC_EnableIRQ(DMA2_Stream1_IRQn);
1222 HAL_NVIC_SetPriority(DMA2_Stream2_IRQn, 0, 0);
1223 HAL_NVIC_EnableIRQ(DMA2_Stream2_IRQn);
1234 GPIO_InitTypeDef GPIO_InitStruct = {0};
1239 __HAL_RCC_GPIOE_CLK_ENABLE();
1240 __HAL_RCC_GPIOC_CLK_ENABLE();
1241 __HAL_RCC_GPIOF_CLK_ENABLE();
1242 __HAL_RCC_GPIOH_CLK_ENABLE();
1243 __HAL_RCC_GPIOA_CLK_ENABLE();
1244 __HAL_RCC_GPIOB_CLK_ENABLE();
1245 __HAL_RCC_GPIOG_CLK_ENABLE();
1246 __HAL_RCC_GPIOD_CLK_ENABLE();
1249 HAL_GPIO_WritePin(GPIOF, GPIO_PIN_12|GPIO_PIN_13, GPIO_PIN_RESET);
1252 HAL_GPIO_WritePin(GPIOE, GPIO_PIN_7|GPIO_PIN_8|GPIO_PIN_9|GPIO_PIN_11
1253 |GPIO_PIN_13, GPIO_PIN_RESET);
1256 HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14|GPIO_PIN_15, GPIO_PIN_RESET);
1259 HAL_GPIO_WritePin(GPIOG, GPIO_PIN_9, GPIO_PIN_RESET);
1266 GPIO_InitStruct.Pin = GPIO_PIN_3|GPIO_PIN_4|GPIO_PIN_10|GPIO_PIN_12
1267 |GPIO_PIN_14|GPIO_PIN_15|GPIO_PIN_0|GPIO_PIN_1;
1268 GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
1269 GPIO_InitStruct.Pull = GPIO_NOPULL;
1270 HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
1274 GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
1275 GPIO_InitStruct.Pull = GPIO_NOPULL;
1279 GPIO_InitStruct.Pin = GPIO_PIN_2|GPIO_PIN_11;
1280 GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
1281 GPIO_InitStruct.Pull = GPIO_NOPULL;
1282 HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);
1286 GPIO_InitStruct.Pin = GPIO_PIN_2|GPIO_PIN_10|GPIO_PIN_11|GPIO_PIN_12
1287 |GPIO_PIN_14|GPIO_PIN_15|GPIO_PIN_4|GPIO_PIN_6;
1288 GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
1289 GPIO_InitStruct.Pull = GPIO_NOPULL;
1290 HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
1293 GPIO_InitStruct.Pin = GPIO_PIN_12|GPIO_PIN_13;
1294 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
1295 GPIO_InitStruct.Pull = GPIO_NOPULL;
1296 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
1297 HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);
1302 GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_3
1303 |GPIO_PIN_4|GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_8
1304 |GPIO_PIN_10|GPIO_PIN_11|GPIO_PIN_15;
1305 GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
1306 GPIO_InitStruct.Pull = GPIO_NOPULL;
1307 HAL_GPIO_Init(GPIOG, &GPIO_InitStruct);
1311 GPIO_InitStruct.Pin = GPIO_PIN_7|GPIO_PIN_8|GPIO_PIN_9|GPIO_PIN_11
1313 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
1314 GPIO_InitStruct.Pull = GPIO_NOPULL;
1315 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
1316 HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
1321 GPIO_InitStruct.Pin = GPIO_PIN_10|GPIO_PIN_11|GPIO_PIN_12|GPIO_PIN_13
1322 |GPIO_PIN_3|GPIO_PIN_4|GPIO_PIN_5|GPIO_PIN_6
1324 GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
1325 GPIO_InitStruct.Pull = GPIO_NOPULL;
1326 HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
1329 GPIO_InitStruct.Pin = GPIO_PIN_14|GPIO_PIN_15;
1330 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
1331 GPIO_InitStruct.Pull = GPIO_NOPULL;
1332 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
1333 HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
1337 GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
1338 GPIO_InitStruct.Pull = GPIO_NOPULL;
1343 GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7|GPIO_PIN_8|GPIO_PIN_9
1344 |GPIO_PIN_10|GPIO_PIN_11|GPIO_PIN_12;
1345 GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
1346 GPIO_InitStruct.Pull = GPIO_NOPULL;
1347 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
1348 GPIO_InitStruct.Alternate = GPIO_AF12_SDMMC1;
1349 HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
1353 GPIO_InitStruct.Pin = GPIO_PIN_8|GPIO_PIN_9|GPIO_PIN_10|GPIO_PIN_11
1355 GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
1356 GPIO_InitStruct.Pull = GPIO_NOPULL;
1357 HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
1360 GPIO_InitStruct.Pin = GPIO_PIN_2;
1361 GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
1362 GPIO_InitStruct.Pull = GPIO_NOPULL;
1363 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
1364 GPIO_InitStruct.Alternate = GPIO_AF12_SDMMC1;
1365 HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
1368 GPIO_InitStruct.Pin = GPIO_PIN_9;
1369 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
1370 GPIO_InitStruct.Pull = GPIO_NOPULL;
1371 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
1372 HAL_GPIO_Init(GPIOG, &GPIO_InitStruct);
1375 GPIO_InitStruct.Pin =
LD2_Pin;
1376 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
1377 GPIO_InitStruct.Pull = GPIO_NOPULL;
1378 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
1382 GPIO_InitStruct.Pin = GPIO_PIN_8|GPIO_PIN_9;
1383 GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
1384 GPIO_InitStruct.Pull = GPIO_NOPULL;
1385 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
1386 GPIO_InitStruct.Alternate = GPIO_AF12_SDMMC1;
1387 HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
1398 HAL_UART_Transmit(&
huart3, (uint8_t *)data, len, HAL_MAX_DELAY);
1422 printf(
"Error_Handler\r\n");
1427#ifdef USE_FULL_ASSERT
1435void 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[])
Initializes the scheduler with the given sensors.
void SchedulerRun(Scheduler *scheduler)
Runs the scheduler, executing tasks based on their priority.
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.
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.
static void MX_SPI6_Init(void)
SPI6 Initialization Function.
static void MX_DMA_Init(void)
uint32_t adc2_buffer[ADC2_CHANNEL_SIZE]
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]
static void MX_ADC1_Init(void)
ADC1 Initialization Function.
uint8_t digital_out_buffer[NUM_DIGITAL_OUTPUTS]
DMA_HandleTypeDef hdma_dac2
UART_HandleTypeDef huart3
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]
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
char name[MAX_SIGNAL_NAME_LENGTH]
int(* addMonitor)(struct ControllerSystem *controller, MonitorSystem *monitor)