]> git.leonardobizzoni.com Git - pioneer-stm32/commitdiff
UART message receive only via DMA
authorLeonardoBizzoni <leo2002714@gmail.com>
Wed, 11 Feb 2026 10:25:54 +0000 (11:25 +0100)
committerLeonardoBizzoni <leo2002714@gmail.com>
Wed, 11 Feb 2026 10:25:54 +0000 (11:25 +0100)
pioneer_controller/.settings/language.settings.xml
pioneer_controller/Core/Inc/firmware/fmw_core.h
pioneer_controller/Core/Inc/firmware/fmw_messages.h
pioneer_controller/Core/Inc/stm32f7xx_it.h
pioneer_controller/Core/Src/firmware/fwm_core.c
pioneer_controller/Core/Src/main.c
pioneer_controller/Core/Src/stm32f7xx_hal_msp.c
pioneer_controller/Core/Src/stm32f7xx_it.c
pioneer_controller/pioneer_controller.ioc

index a310404bf43f4da464155706b69744f1b58b6857..a1c742ccbeb5fc89fb79838f16cc4926c939398b 100644 (file)
@@ -5,7 +5,7 @@
                        <provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
                        <provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
                        <provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
-                       <provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="1126746484932729188" id="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" keep-relative-paths="false" name="MCU ARM GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
+                       <provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="1192945016184491573" id="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" keep-relative-paths="false" name="MCU ARM GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
                                <language-scope id="org.eclipse.cdt.core.gcc"/>
                                <language-scope id="org.eclipse.cdt.core.g++"/>
                        </provider>
@@ -17,7 +17,7 @@
                        <provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
                        <provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
                        <provider copy-of="extension" id="org.eclipse.cdt.managedbuilder.core.GCCBuildCommandParser"/>
-                       <provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="1055834460187919044" id="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" keep-relative-paths="false" name="MCU ARM GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
+                       <provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="1122032991439681429" id="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" keep-relative-paths="false" name="MCU ARM GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
                                <language-scope id="org.eclipse.cdt.core.gcc"/>
                                <language-scope id="org.eclipse.cdt.core.g++"/>
                        </provider>
index 30017495defc52c1e9b1e969d38b79484689f86d..74e99a4ad79afb69880d6f52c5362ff9ffdbd6cd 100644 (file)
@@ -1,6 +1,14 @@
 #ifndef FMW_CORE_H
 #define FMW_CORE_H
 
+typedef uint8_t FMW_Mode;
+enum {
+  FMW_Mode_None,
+  FMW_Mode_Init,
+  FMW_Mode_Run,
+  FMW_Mode_COUNT,
+};
+
 typedef struct FMW_Encoder {
   TIM_HandleTypeDef *const timer;
   uint32_t previous_millis;
@@ -74,8 +82,8 @@ typedef struct FMW_Hook {
 void fmw_motor_init(FMW_Motor motors[], int32_t count)          __attribute__((nonnull));
 void fmw_motor_set_speed(FMW_Motor *motor, int32_t duty_cycle)  __attribute__((nonnull));
 void fmw_motor_brake(FMW_Motor motors[], int32_t count)         __attribute__((nonnull));
-void fmw_motor_enable(FMW_Motor * motor)                        __attribute__((nonnull));
-void fmw_motor_disable(FMW_Motor * motor)                       __attribute__((nonnull));
+void fmw_motor_enable(FMW_Motor motors[], int32_t count)        __attribute__((nonnull));
+void fmw_motor_disable(FMW_Motor motors[], int32_t count)       __attribute__((nonnull));
 
 void fmw_encoder_init(FMW_Encoder encoders[], int32_t count)            __attribute__((nonnull));
 void fmw_encoder_update(FMW_Encoder *encoder)                           __attribute__((nonnull));
index fb65170d7eb409ead29ddcb12710f7a3f43834e3..be39bce36c4fa809fea4de7ed827f741b75e89b5 100644 (file)
@@ -10,16 +10,6 @@ typedef union {
   float values[3];
 } FMW_PidConstants;
 
-typedef uint8_t FMW_State;
-enum {
-  FMW_State_None,
-
-  FMW_State_Init,
-  FMW_State_Running,
-
-  FMW_State_COUNT,
-};
-
 typedef uint8_t FMW_MessageType;
 enum {
   FMW_MessageType_None,
index 7fbeafb64bb7155d370b24dbdcd3c00e3a29ef4a..0b4ba8b499808238d69ba717cfdf7af37b9242ec 100644 (file)
@@ -58,7 +58,9 @@ void PendSV_Handler(void);
 void SysTick_Handler(void);\r
 void EXTI3_IRQHandler(void);\r
 void EXTI4_IRQHandler(void);\r
+void DMA1_Stream1_IRQHandler(void);\r
 void ADC_IRQHandler(void);\r
+void USART3_IRQHandler(void);\r
 void EXTI15_10_IRQHandler(void);\r
 /* USER CODE BEGIN EFP */\r
 \r
index a75c3a492582938aa95601aa3569c899be738120..6042b5acea4280f68439504e249bc6b267df7d66 100644 (file)
@@ -114,16 +114,34 @@ void fmw_motor_brake(FMW_Motor motors[], int32_t count) {
   }
 }
 
-void fmw_motor_enable(FMW_Motor *motor) {
-  HAL_StatusTypeDef res = HAL_TIM_PWM_Start(motor->pwm_timer, motor->pwm_channel);
-  FMW_ASSERT(res == HAL_OK);
-  motor->active = true;
+void fmw_motor_enable(FMW_Motor motors[], int32_t count) {
+  FMW_ASSERT(count > 0);
+  for (int32_t i = 0; i < count; ++i) {
+    FMW_ASSERT(motors[i].pwm_timer != NULL);
+    FMW_ASSERT(motors[i].pwm_channel == TIM_CHANNEL_1 || motors[i].pwm_channel == TIM_CHANNEL_2 ||
+               motors[i].pwm_channel == TIM_CHANNEL_3 || motors[i].pwm_channel == TIM_CHANNEL_4 ||
+               motors[i].pwm_channel == TIM_CHANNEL_5 || motors[i].pwm_channel == TIM_CHANNEL_6 ||
+               motors[i].pwm_channel == TIM_CHANNEL_ALL);
+    FMW_ASSERT(!motors[i].active);
+    HAL_StatusTypeDef res = HAL_TIM_PWM_Start(motors[i].pwm_timer, motors[i].pwm_channel);
+    FMW_ASSERT(res == HAL_OK);
+    motors[i].active = true;
+  }
 }
 
-void fmw_motor_disable(FMW_Motor *motor) {
-  HAL_StatusTypeDef res = HAL_TIM_PWM_Stop(motor->pwm_timer, motor->pwm_channel);
-  FMW_ASSERT(res == HAL_OK, .callback = fmw_hook_assert_fail);
-  motor->active = false;
+void fmw_motor_disable(FMW_Motor motors[], int32_t count) {
+  FMW_ASSERT(count > 0, .callback = fmw_hook_assert_fail);
+  for (int32_t i = 0; i < count; ++i) {
+    FMW_ASSERT(motors[i].pwm_timer != NULL, .callback = fmw_hook_assert_fail);
+    FMW_ASSERT(motors[i].pwm_channel == TIM_CHANNEL_1 || motors[i].pwm_channel == TIM_CHANNEL_2 ||
+               motors[i].pwm_channel == TIM_CHANNEL_3 || motors[i].pwm_channel == TIM_CHANNEL_4 ||
+               motors[i].pwm_channel == TIM_CHANNEL_5 || motors[i].pwm_channel == TIM_CHANNEL_6 ||
+               motors[i].pwm_channel == TIM_CHANNEL_ALL, .callback = fmw_hook_assert_fail);
+    FMW_ASSERT(motors[i].active);
+    HAL_StatusTypeDef res = HAL_TIM_PWM_Stop(motors[i].pwm_timer, motors[i].pwm_channel);
+    FMW_ASSERT(res == HAL_OK, .callback = fmw_hook_assert_fail);
+    motors[i].active = false;
+  }
 }
 
 // ============================================================
index 7c47c7a76e13e84735fe99596d34f8026b3b7d86..1a1b1cae125762e9c0414178a3c357894f8ce610 100644 (file)
@@ -38,12 +38,13 @@ FMW_Result message_handler(FMW_Message *msg, CRC_HandleTypeDef *hcrc)
 \r
 /* Private define ------------------------------------------------------------*/\r
 /* USER CODE BEGIN PD */\r
+#define MOTOR_COUNT 2\r
+#define ENCODER_COUNT 2\r
+#define UART_MESSANGER_HANDLE (&huart3)\r
 /* USER CODE END PD */\r
 \r
 /* Private macro -------------------------------------------------------------*/\r
 /* USER CODE BEGIN PM */\r
-#define MOTOR_COUNT 2\r
-#define ENCODER_COUNT 2\r
 /* USER CODE END PM */\r
 \r
 /* Private variables ---------------------------------------------------------*/\r
@@ -58,11 +59,10 @@ TIM_HandleTypeDef htim4;
 TIM_HandleTypeDef htim6;\r
 \r
 UART_HandleTypeDef huart3;\r
+DMA_HandleTypeDef hdma_usart3_rx;\r
 \r
 /* USER CODE BEGIN PV */\r
 \r
-#define UART_MESSANGER_HANDLE (&huart3)\r
-\r
 // TODO(lb): fill with sensible default\r
 static union {\r
   FMW_Encoder values[ENCODER_COUNT];\r
@@ -162,19 +162,16 @@ static uint32_t led_update_period = 200;
 \r
 static volatile int32_t ticks_left  = 0;\r
 static volatile int32_t ticks_right = 0;\r
-\r
-static volatile FMW_Message run_msg = {0};\r
-\r
-static volatile uint32_t time_aux_press = 0;\r
-static volatile uint32_t time_aux2_press = 0;\r
+static volatile FMW_Message uart_message_buffer = {0};\r
 static volatile uint32_t time_last_motors = 0;\r
-static volatile FMW_State fmw_state = FMW_State_Init;\r
+static volatile FMW_Mode current_mode = FMW_Mode_Init;\r
 \r
 /* USER CODE END PV */\r
 \r
 /* Private function prototypes -----------------------------------------------*/\r
 void SystemClock_Config(void);\r
 static void MX_GPIO_Init(void);\r
+static void MX_DMA_Init(void);\r
 static void MX_USART3_UART_Init(void);\r
 static void MX_ADC1_Init(void);\r
 static void MX_TIM4_Init(void);\r
@@ -191,6 +188,10 @@ static void MX_CRC_Init(void);
 /* USER CODE BEGIN 0 */\r
 /* USER CODE END 0 */\r
 \r
+/**\r
+  * @brief  The application entry point.\r
+  * @retval int\r
+  */\r
 int main(void)\r
 {\r
 \r
@@ -215,6 +216,7 @@ int main(void)
 \r
   /* Initialize all configured peripherals */\r
   MX_GPIO_Init();\r
+  MX_DMA_Init();\r
   MX_USART3_UART_Init();\r
   MX_ADC1_Init();\r
   MX_TIM4_Init();\r
@@ -240,26 +242,26 @@ int main(void)
 }\r
 \r
 /**\r
- * @brief System Clock Configuration\r
- * @retval None\r
- */\r
 * @brief System Clock Configuration\r
 * @retval None\r
 */\r
 void SystemClock_Config(void)\r
 {\r
   RCC_OscInitTypeDef RCC_OscInitStruct = {0};\r
   RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};\r
 \r
   /** Configure LSE Drive Capability\r
-   */\r
+  */\r
   HAL_PWR_EnableBkUpAccess();\r
 \r
   /** Configure the main internal regulator output voltage\r
-   */\r
+  */\r
   __HAL_RCC_PWR_CLK_ENABLE();\r
   __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE3);\r
 \r
   /** Initializes the RCC Oscillators according to the specified parameters\r
-   * in the RCC_OscInitTypeDef structure.\r
-   */\r
+  * in the RCC_OscInitTypeDef structure.\r
+  */\r
   RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;\r
   RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS;\r
   RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;\r
@@ -270,37 +272,37 @@ void SystemClock_Config(void)
   RCC_OscInitStruct.PLL.PLLQ = 4;\r
   RCC_OscInitStruct.PLL.PLLR = 2;\r
   if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
 \r
   /** Activate the Over-Drive mode\r
-   */\r
+  */\r
   if (HAL_PWREx_EnableOverDrive() != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
 \r
   /** Initializes the CPU, AHB and APB buses clocks\r
-   */\r
+  */\r
   RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK\r
-                                |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;\r
+                              |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;\r
   RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;\r
   RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;\r
   RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;\r
   RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;\r
 \r
   if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_3) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
 }\r
 \r
 /**\r
- * @brief ADC1 Initialization Function\r
- * @param None\r
- * @retval None\r
- */\r
 * @brief ADC1 Initialization Function\r
 * @param None\r
 * @retval None\r
 */\r
 static void MX_ADC1_Init(void)\r
 {\r
 \r
@@ -315,7 +317,7 @@ static void MX_ADC1_Init(void)
   /* USER CODE END ADC1_Init 1 */\r
 \r
   /** Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion)\r
-   */\r
+  */\r
   hadc1.Instance = ADC1;\r
   hadc1.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;\r
   hadc1.Init.Resolution = ADC_RESOLUTION_12B;\r
@@ -329,19 +331,19 @@ static void MX_ADC1_Init(void)
   hadc1.Init.DMAContinuousRequests = DISABLE;\r
   hadc1.Init.EOCSelection = ADC_EOC_SINGLE_CONV;\r
   if (HAL_ADC_Init(&hadc1) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
 \r
   /** Configure for the selected ADC regular channel its corresponding rank in the sequencer and its sample time.\r
-   */\r
+  */\r
   sConfig.Channel = ADC_CHANNEL_2;\r
   sConfig.Rank = ADC_REGULAR_RANK_1;\r
   sConfig.SamplingTime = ADC_SAMPLETIME_84CYCLES;\r
   if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   /* USER CODE BEGIN ADC1_Init 2 */\r
 \r
   /* USER CODE END ADC1_Init 2 */\r
@@ -349,10 +351,10 @@ static void MX_ADC1_Init(void)
 }\r
 \r
 /**\r
- * @brief CRC Initialization Function\r
- * @param None\r
- * @retval None\r
- */\r
 * @brief CRC Initialization Function\r
 * @param None\r
 * @retval None\r
 */\r
 static void MX_CRC_Init(void)\r
 {\r
 \r
@@ -370,9 +372,9 @@ static void MX_CRC_Init(void)
   hcrc.Init.OutputDataInversionMode = CRC_OUTPUTDATA_INVERSION_DISABLE;\r
   hcrc.InputDataFormat = CRC_INPUTDATA_FORMAT_BYTES;\r
   if (HAL_CRC_Init(&hcrc) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   /* USER CODE BEGIN CRC_Init 2 */\r
 \r
   /* USER CODE END CRC_Init 2 */\r
@@ -380,10 +382,10 @@ static void MX_CRC_Init(void)
 }\r
 \r
 /**\r
- * @brief TIM1 Initialization Function\r
- * @param None\r
- * @retval None\r
- */\r
 * @brief TIM1 Initialization Function\r
 * @param None\r
 * @retval None\r
 */\r
 static void MX_TIM1_Init(void)\r
 {\r
 \r
@@ -406,16 +408,16 @@ static void MX_TIM1_Init(void)
   htim1.Init.RepetitionCounter = 0;\r
   htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;\r
   if (HAL_TIM_PWM_Init(&htim1) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;\r
   sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET;\r
   sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;\r
   if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   sConfigOC.OCMode = TIM_OCMODE_PWM1;\r
   sConfigOC.Pulse = 0;\r
   sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;\r
@@ -424,13 +426,13 @@ static void MX_TIM1_Init(void)
   sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;\r
   sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;\r
   if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_2) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;\r
   sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE;\r
   sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;\r
@@ -443,9 +445,9 @@ static void MX_TIM1_Init(void)
   sBreakDeadTimeConfig.Break2Filter = 0;\r
   sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;\r
   if (HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   /* USER CODE BEGIN TIM1_Init 2 */\r
 \r
   /* USER CODE END TIM1_Init 2 */\r
@@ -454,10 +456,10 @@ static void MX_TIM1_Init(void)
 }\r
 \r
 /**\r
- * @brief TIM2 Initialization Function\r
- * @param None\r
- * @retval None\r
- */\r
 * @brief TIM2 Initialization Function\r
 * @param None\r
 * @retval None\r
 */\r
 static void MX_TIM2_Init(void)\r
 {\r
 \r
@@ -487,15 +489,15 @@ static void MX_TIM2_Init(void)
   sConfig.IC2Prescaler = TIM_ICPSC_DIV1;\r
   sConfig.IC2Filter = 0;\r
   if (HAL_TIM_Encoder_Init(&htim2, &sConfig) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;\r
   sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;\r
   if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   /* USER CODE BEGIN TIM2_Init 2 */\r
 \r
   /* USER CODE END TIM2_Init 2 */\r
@@ -503,10 +505,10 @@ static void MX_TIM2_Init(void)
 }\r
 \r
 /**\r
- * @brief TIM3 Initialization Function\r
- * @param None\r
- * @retval None\r
- */\r
 * @brief TIM3 Initialization Function\r
 * @param None\r
 * @retval None\r
 */\r
 static void MX_TIM3_Init(void)\r
 {\r
 \r
@@ -536,15 +538,15 @@ static void MX_TIM3_Init(void)
   sConfig.IC2Prescaler = TIM_ICPSC_DIV1;\r
   sConfig.IC2Filter = 0;\r
   if (HAL_TIM_Encoder_Init(&htim3, &sConfig) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;\r
   sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;\r
   if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   /* USER CODE BEGIN TIM3_Init 2 */\r
 \r
   /* USER CODE END TIM3_Init 2 */\r
@@ -552,10 +554,10 @@ static void MX_TIM3_Init(void)
 }\r
 \r
 /**\r
- * @brief TIM4 Initialization Function\r
- * @param None\r
- * @retval None\r
- */\r
 * @brief TIM4 Initialization Function\r
 * @param None\r
 * @retval None\r
 */\r
 static void MX_TIM4_Init(void)\r
 {\r
 \r
@@ -576,27 +578,27 @@ static void MX_TIM4_Init(void)
   htim4.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;\r
   htim4.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;\r
   if (HAL_TIM_PWM_Init(&htim4) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;\r
   sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;\r
   if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   sConfigOC.OCMode = TIM_OCMODE_PWM1;\r
   sConfigOC.Pulse = 0;\r
   sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;\r
   sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;\r
   if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_3) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   if (HAL_TIM_PWM_ConfigChannel(&htim4, &sConfigOC, TIM_CHANNEL_4) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   /* USER CODE BEGIN TIM4_Init 2 */\r
 \r
   /* USER CODE END TIM4_Init 2 */\r
@@ -605,10 +607,10 @@ static void MX_TIM4_Init(void)
 }\r
 \r
 /**\r
- * @brief TIM6 Initialization Function\r
- * @param None\r
- * @retval None\r
- */\r
 * @brief TIM6 Initialization Function\r
 * @param None\r
 * @retval None\r
 */\r
 static void MX_TIM6_Init(void)\r
 {\r
 \r
@@ -627,15 +629,15 @@ static void MX_TIM6_Init(void)
   htim6.Init.Period = 65535;\r
   htim6.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;\r
   if (HAL_TIM_Base_Init(&htim6) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;\r
   sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;\r
   if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   /* USER CODE BEGIN TIM6_Init 2 */\r
 \r
   /* USER CODE END TIM6_Init 2 */\r
@@ -643,10 +645,10 @@ static void MX_TIM6_Init(void)
 }\r
 \r
 /**\r
- * @brief USART3 Initialization Function\r
- * @param None\r
- * @retval None\r
- */\r
 * @brief USART3 Initialization Function\r
 * @param None\r
 * @retval None\r
 */\r
 static void MX_USART3_UART_Init(void)\r
 {\r
 \r
@@ -668,9 +670,9 @@ static void MX_USART3_UART_Init(void)
   huart3.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;\r
   huart3.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;\r
   if (HAL_UART_Init(&huart3) != HAL_OK)\r
-    {\r
-      Error_Handler();\r
-    }\r
+  {\r
+    Error_Handler();\r
+  }\r
   /* USER CODE BEGIN USART3_Init 2 */\r
 \r
   /* USER CODE END USART3_Init 2 */\r
@@ -678,10 +680,26 @@ static void MX_USART3_UART_Init(void)
 }\r
 \r
 /**\r
- * @brief GPIO Initialization Function\r
- * @param None\r
- * @retval None\r
- */\r
+  * Enable DMA controller clock\r
+  */\r
+static void MX_DMA_Init(void)\r
+{\r
+\r
+  /* DMA controller clock enable */\r
+  __HAL_RCC_DMA1_CLK_ENABLE();\r
+\r
+  /* DMA interrupt init */\r
+  /* DMA1_Stream1_IRQn interrupt configuration */\r
+  HAL_NVIC_SetPriority(DMA1_Stream1_IRQn, 0, 0);\r
+  HAL_NVIC_EnableIRQ(DMA1_Stream1_IRQn);\r
+\r
+}\r
+\r
+/**\r
+  * @brief GPIO Initialization Function\r
+  * @param None\r
+  * @retval None\r
+  */\r
 static void MX_GPIO_Init(void)\r
 {\r
   GPIO_InitTypeDef GPIO_InitStruct = {0};\r
@@ -780,13 +798,9 @@ static void MX_GPIO_Init(void)
 \r
 /* USER CODE BEGIN 4 */\r
 void start(void) {\r
-  for (FMW_Message msg = {0}; fmw_state == FMW_State_Init; ) {\r
-    FMW_Result res = fmw_message_uart_receive(UART_MESSANGER_HANDLE, &msg, 180 * 1000);\r
-    FMW_Message response = {0};\r
-    response.header.type = FMW_MessageType_Response;\r
-    response.result = (res == FMW_Result_Ok) ? message_handler(&msg, &hcrc) : res;\r
-    fmw_message_uart_send(UART_MESSANGER_HANDLE, &hcrc, &response, HAL_MAX_DELAY);\r
-  }\r
+  // Enables UART RX interrupt\r
+  HAL_UART_Receive_DMA(UART_MESSANGER_HANDLE, (uint8_t*)&uart_message_buffer, sizeof uart_message_buffer);\r
+  for (; current_mode == FMW_Mode_Init; );\r
 \r
   fmw_encoder_init(encoders.values, ENCODER_COUNT);\r
   fmw_motor_init(motors.values, MOTOR_COUNT);\r
@@ -801,9 +815,6 @@ void start(void) {
   HAL_StatusTypeDef timer_status = HAL_TIM_Base_Start_IT(&htim6);\r
   FMW_ASSERT(timer_status == HAL_OK);\r
 \r
-  // Enables UART RX interrupt\r
-  HAL_UART_Receive_DMA(UART_MESSANGER_HANDLE, (uint8_t*)&run_msg, sizeof run_msg);\r
-\r
   for (uint32_t time_last_led_update = 0;;) {\r
     uint32_t time_now = HAL_GetTick();\r
     if (time_now - time_last_led_update >= led_update_period) {\r
@@ -824,11 +835,11 @@ FMW_Result message_handler(FMW_Message *msg, CRC_HandleTypeDef *hcrc) {
     if (!(crc_computed == crc_received)) { return FMW_Result_Error_UART_Crc; }\r
   }\r
 \r
-  switch (fmw_state) {\r
-  case FMW_State_Init: {\r
+  switch (current_mode) {\r
+  case FMW_Mode_Init: {\r
     switch (msg->header.type) {\r
     case FMW_MessageType_StateChange_Run: {\r
-      fmw_state = FMW_State_Running;\r
+      current_mode = FMW_Mode_Run;\r
     } break;\r
     case FMW_MessageType_Config_Robot: {\r
       if (!(msg->config_robot.baseline > 0.f)) {\r
@@ -873,7 +884,7 @@ FMW_Result message_handler(FMW_Message *msg, CRC_HandleTypeDef *hcrc) {
     } break;\r
     }\r
   } break;\r
-  case FMW_State_Running: {\r
+  case FMW_Mode_Run: {\r
     switch (msg->header.type) {\r
     case FMW_MessageType_Run_GetStatus: {\r
       int32_t current_ticks_left = ticks_left + fmw_encoder_count_get(&encoders.left);\r
@@ -944,69 +955,34 @@ void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart) {
   if (huart == UART_MESSANGER_HANDLE) {\r
     FMW_Message response = {0};\r
     response.header.type = FMW_MessageType_Response;\r
-    response.result = message_handler((FMW_Message*)&run_msg, &hcrc);\r
+    response.result = message_handler((FMW_Message*)&uart_message_buffer, &hcrc);\r
     fmw_message_uart_send(UART_MESSANGER_HANDLE, &hcrc, &response, HAL_MAX_DELAY);\r
-\r
     // NOTE(lb): listen for the next message.\r
-    HAL_UART_Receive_DMA(huart, (uint8_t*)&run_msg, sizeof run_msg);\r
+    HAL_UART_Receive_DMA(UART_MESSANGER_HANDLE, (uint8_t*)&uart_message_buffer, sizeof uart_message_buffer);\r
   }\r
 }\r
 \r
+void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart) {\r
+  FMW_ASSERT(false);\r
+}\r
+\r
 void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) {\r
   uint32_t time_now = HAL_GetTick();\r
 \r
   switch (GPIO_Pin) {\r
-  case aux_Pin: {\r
-    if (time_now - time_aux_press > FMW_DEBOUNCE_DELAY) {\r
-      // NOTE(lb): is this useful?\r
-      time_aux_press = time_now;\r
-      HAL_GPIO_TogglePin(GPIOB, LD1_Pin);\r
-      HAL_GPIO_TogglePin(GPIOB, LD2_Pin);\r
-      HAL_GPIO_TogglePin(GPIOB, LD3_Pin);\r
-      /* char msg[] = "AUX1 button pressed\r\n"; */\r
-      /* HAL_UART_Transmit(&huart3, (uint8_t*)msg, strlen(msg), HAL_MAX_DELAY); */\r
-      // NOTE(lb): lol strlen\r
-    }\r
-  } break;\r
-  case aux2_Pin: {\r
-    if (time_now - time_aux2_press > FMW_DEBOUNCE_DELAY) {\r
-      // NOTE(lb): is this useful?\r
-      time_aux2_press = time_now;\r
-      /* char msg[] = "AUX2 button pressed\r\n"; */\r
-      /* HAL_UART_Transmit(&huart3, (uint8_t*)msg, strlen(msg), HAL_MAX_DELAY); */\r
-      // NOTE(lb): lol strlen\r
-    }\r
-  } break;\r
   case motors_btn_Pin: {\r
     if (time_now - time_last_motors > FMW_DEBOUNCE_DELAY) {\r
-      // NOTE(lb): in both branches the buffer is turned off. When i should turn it on?\r
-      //           even in https://github.com/giuseppe-caliaro/pioneer3dx-control\r
-      //           Buzzer_Set is never called with true.\r
-\r
       time_last_motors = time_now;\r
-      /* char msg[] = "Motors button pressed\r\n"; */\r
-      /* HAL_UART_Transmit(&huart3, (uint8_t*)msg, strlen(msg), HAL_MAX_DELAY); */\r
-      // NOTE(lb): lol strlen\r
       if (motors.left.active && motors.right.active) {\r
-        fmw_motor_disable(&motors.left);\r
-        fmw_motor_disable(&motors.right);\r
+        fmw_motor_disable(motors.values, ARRLENGTH(motors.values));\r
         HAL_GPIO_WritePin(SLED_GPIO_Port, SLED_Pin, GPIO_PIN_RESET);\r
-        fmw_buzzer_set(&buzzer, 1, false); // <--------------------------------\r
-        /* char msg[] = "Motors OFF\r\n"; */\r
-        /* HAL_UART_Transmit(&huart3, (uint8_t*)msg, strlen(msg), HAL_MAX_DELAY); */\r
-        // NOTE(lb): lol strlen\r
+        fmw_buzzer_set(&buzzer, 1, false);\r
       } else {\r
-        // NOTE(lb): is it safe to FMW_ASSERT here since the motors aren't running?\r
         FMW_ASSERT(!motors.left.active);\r
         FMW_ASSERT(!motors.right.active);\r
-\r
-        fmw_motor_enable(&motors.left);\r
-        fmw_motor_enable(&motors.right);\r
+        fmw_motor_enable(motors.values, ARRLENGTH(motors.values));\r
         HAL_GPIO_WritePin(SLED_GPIO_Port, SLED_Pin, GPIO_PIN_SET);\r
-        fmw_buzzer_set(&buzzer, 1, false);  // <--------------------------------\r
-        /* char msg[] = "Motors ON\r\n"; */\r
-        /* HAL_UART_Transmit(&huart3, (uint8_t*)msg, strlen(msg), HAL_MAX_DELAY); */\r
-        // NOTE(lb): lol strlen\r
+        fmw_buzzer_set(&buzzer, 1, false);\r
       }\r
     }\r
   } break;\r
@@ -1022,9 +998,9 @@ void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) {
 /* USER CODE END 4 */\r
 \r
 /**\r
- * @brief  This function is executed in case of error occurrence.\r
- * @retval None\r
- */\r
 * @brief  This function is executed in case of error occurrence.\r
 * @retval None\r
 */\r
 void Error_Handler(void)\r
 {\r
   /* USER CODE BEGIN Error_Handler_Debug */\r
@@ -1033,12 +1009,12 @@ void Error_Handler(void)
 }\r
 #ifdef USE_FULL_ASSERT\r
 /**\r
- * @brief  Reports the name of the source file and the source line number\r
- *         where the assert_param error has occurred.\r
- * @param  file: pointer to the source file name\r
- * @param  line: assert_param error line source number\r
- * @retval None\r
- */\r
 * @brief  Reports the name of the source file and the source line number\r
 *         where the assert_param error has occurred.\r
 * @param  file: pointer to the source file name\r
 * @param  line: assert_param error line source number\r
 * @retval None\r
 */\r
 void assert_failed(uint8_t *file, uint32_t line)\r
 {\r
   /* USER CODE BEGIN 6 */\r
index 0b7c5aa378346aa5822181df3dbb317a051b80d0..44e347554cfe8390daa2f20142f2629021cdcd02 100644 (file)
@@ -24,6 +24,7 @@
 /* USER CODE BEGIN Includes */\r
 \r
 /* USER CODE END Includes */\r
+extern DMA_HandleTypeDef hdma_usart3_rx;\r
 \r
 /* Private typedef -----------------------------------------------------------*/\r
 /* USER CODE BEGIN TD */\r
@@ -498,6 +499,28 @@ void HAL_UART_MspInit(UART_HandleTypeDef* huart)
     GPIO_InitStruct.Alternate = GPIO_AF7_USART3;\r
     HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);\r
 \r
+    /* USART3 DMA Init */\r
+    /* USART3_RX Init */\r
+    hdma_usart3_rx.Instance = DMA1_Stream1;\r
+    hdma_usart3_rx.Init.Channel = DMA_CHANNEL_4;\r
+    hdma_usart3_rx.Init.Direction = DMA_PERIPH_TO_MEMORY;\r
+    hdma_usart3_rx.Init.PeriphInc = DMA_PINC_DISABLE;\r
+    hdma_usart3_rx.Init.MemInc = DMA_MINC_ENABLE;\r
+    hdma_usart3_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;\r
+    hdma_usart3_rx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;\r
+    hdma_usart3_rx.Init.Mode = DMA_NORMAL;\r
+    hdma_usart3_rx.Init.Priority = DMA_PRIORITY_LOW;\r
+    hdma_usart3_rx.Init.FIFOMode = DMA_FIFOMODE_DISABLE;\r
+    if (HAL_DMA_Init(&hdma_usart3_rx) != HAL_OK)\r
+    {\r
+      Error_Handler();\r
+    }\r
+\r
+    __HAL_LINKDMA(huart,hdmarx,hdma_usart3_rx);\r
+\r
+    /* USART3 interrupt Init */\r
+    HAL_NVIC_SetPriority(USART3_IRQn, 0, 0);\r
+    HAL_NVIC_EnableIRQ(USART3_IRQn);\r
     /* USER CODE BEGIN USART3_MspInit 1 */\r
 \r
     /* USER CODE END USART3_MspInit 1 */\r
@@ -528,6 +551,11 @@ void HAL_UART_MspDeInit(UART_HandleTypeDef* huart)
     */\r
     HAL_GPIO_DeInit(GPIOD, STLK_RX_Pin|STLK_TX_Pin);\r
 \r
+    /* USART3 DMA DeInit */\r
+    HAL_DMA_DeInit(huart->hdmarx);\r
+\r
+    /* USART3 interrupt DeInit */\r
+    HAL_NVIC_DisableIRQ(USART3_IRQn);\r
     /* USER CODE BEGIN USART3_MspDeInit 1 */\r
 \r
     /* USER CODE END USART3_MspDeInit 1 */\r
index 04698f39241ad277473cbaee58ff15afb2fcb38e..117a7c446161fb9a69954357662d528b1fadf2ff 100644 (file)
@@ -57,6 +57,8 @@
 \r
 /* External variables --------------------------------------------------------*/\r
 extern ADC_HandleTypeDef hadc1;\r
+extern DMA_HandleTypeDef hdma_usart3_rx;\r
+extern UART_HandleTypeDef huart3;\r
 /* USER CODE BEGIN EV */\r
 \r
 /* USER CODE END EV */\r
@@ -225,6 +227,20 @@ void EXTI4_IRQHandler(void)
   /* USER CODE END EXTI4_IRQn 1 */\r
 }\r
 \r
+/**\r
+  * @brief This function handles DMA1 stream1 global interrupt.\r
+  */\r
+void DMA1_Stream1_IRQHandler(void)\r
+{\r
+  /* USER CODE BEGIN DMA1_Stream1_IRQn 0 */\r
+\r
+  /* USER CODE END DMA1_Stream1_IRQn 0 */\r
+  HAL_DMA_IRQHandler(&hdma_usart3_rx);\r
+  /* USER CODE BEGIN DMA1_Stream1_IRQn 1 */\r
+\r
+  /* USER CODE END DMA1_Stream1_IRQn 1 */\r
+}\r
+\r
 /**\r
   * @brief This function handles ADC1, ADC2 and ADC3 global interrupts.\r
   */\r
@@ -239,6 +255,20 @@ void ADC_IRQHandler(void)
   /* USER CODE END ADC_IRQn 1 */\r
 }\r
 \r
+/**\r
+  * @brief This function handles USART3 global interrupt.\r
+  */\r
+void USART3_IRQHandler(void)\r
+{\r
+  /* USER CODE BEGIN USART3_IRQn 0 */\r
+\r
+  /* USER CODE END USART3_IRQn 0 */\r
+  HAL_UART_IRQHandler(&huart3);\r
+  /* USER CODE BEGIN USART3_IRQn 1 */\r
+\r
+  /* USER CODE END USART3_IRQn 1 */\r
+}\r
+\r
 /**\r
   * @brief This function handles EXTI line[15:10] interrupts.\r
   */\r
index 219112d571477e136c845c0f60c820a51881590a..ab3cea3c836832ee18c15a87484b94bf5ef6580c 100644 (file)
@@ -8,6 +8,18 @@ ADC1.master=1
 CAD.formats=
 CAD.pinconfig=
 CAD.provider=
+Dma.Request0=USART3_RX
+Dma.RequestsNb=1
+Dma.USART3_RX.0.Direction=DMA_PERIPH_TO_MEMORY
+Dma.USART3_RX.0.FIFOMode=DMA_FIFOMODE_DISABLE
+Dma.USART3_RX.0.Instance=DMA1_Stream1
+Dma.USART3_RX.0.MemDataAlignment=DMA_MDATAALIGN_BYTE
+Dma.USART3_RX.0.MemInc=DMA_MINC_ENABLE
+Dma.USART3_RX.0.Mode=DMA_NORMAL
+Dma.USART3_RX.0.PeriphDataAlignment=DMA_PDATAALIGN_BYTE
+Dma.USART3_RX.0.PeriphInc=DMA_PINC_DISABLE
+Dma.USART3_RX.0.Priority=DMA_PRIORITY_LOW
+Dma.USART3_RX.0.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode
 File.Version=6
 GPIO.groupedBy=Group By Peripherals
 KeepUserPlacement=false
@@ -15,17 +27,18 @@ Mcu.CPN=STM32F767ZIT6
 Mcu.Family=STM32F7
 Mcu.IP0=ADC1
 Mcu.IP1=CORTEX_M7
-Mcu.IP10=TIM6
-Mcu.IP11=USART3
+Mcu.IP10=TIM4
+Mcu.IP11=TIM6
+Mcu.IP12=USART3
 Mcu.IP2=CRC
-Mcu.IP3=NVIC
-Mcu.IP4=RCC
-Mcu.IP5=SYS
-Mcu.IP6=TIM1
-Mcu.IP7=TIM2
-Mcu.IP8=TIM3
-Mcu.IP9=TIM4
-Mcu.IPNb=12
+Mcu.IP3=DMA
+Mcu.IP4=NVIC
+Mcu.IP5=RCC
+Mcu.IP6=SYS
+Mcu.IP7=TIM1
+Mcu.IP8=TIM2
+Mcu.IP9=TIM3
+Mcu.IPNb=13
 Mcu.Name=STM32F767ZITx
 Mcu.Package=LQFP144
 Mcu.Pin0=PC13
@@ -68,6 +81,7 @@ MxCube.Version=6.15.0
 MxDb.Version=DB.6.0.150
 NVIC.ADC_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
 NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:true\:false\:false
+NVIC.DMA1_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true
 NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:true\:false\:false
 NVIC.EXTI15_10_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
 NVIC.EXTI3_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
@@ -80,6 +94,7 @@ NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:true\:false\:false
 NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
 NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:true\:false\:false
 NVIC.SysTick_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:false
+NVIC.USART3_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
 NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:true\:false\:false
 PA0/WKUP.GPIOParameters=GPIO_Label
 PA0/WKUP.GPIO_Label=REA
@@ -228,7 +243,7 @@ ProjectManager.ToolChainLocation=
 ProjectManager.UAScriptAfterPath=
 ProjectManager.UAScriptBeforePath=
 ProjectManager.UnderRoot=true
-ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_USART3_UART_Init-USART3-false-HAL-true,4-MX_ADC1_Init-ADC1-false-HAL-true,5-MX_TIM4_Init-TIM4-false-HAL-true,6-MX_TIM1_Init-TIM1-false-HAL-true,7-MX_TIM2_Init-TIM2-false-HAL-true,8-MX_TIM3_Init-TIM3-false-HAL-true,9-MX_TIM6_Init-TIM6-false-HAL-true,0-MX_CORTEX_M7_Init-CORTEX_M7-false-HAL-true
+ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,4-MX_USART3_UART_Init-USART3-false-HAL-true,5-MX_ADC1_Init-ADC1-false-HAL-true,6-MX_TIM4_Init-TIM4-false-HAL-true,7-MX_TIM1_Init-TIM1-false-HAL-true,8-MX_TIM2_Init-TIM2-false-HAL-true,9-MX_TIM3_Init-TIM3-false-HAL-true,10-MX_TIM6_Init-TIM6-false-HAL-true,11-MX_CRC_Init-CRC-false-HAL-true,0-MX_DMA_Init-DMA-false-HAL-true
 RCC.48MHZClocksFreq_Value=24000000
 RCC.ADC12outputFreq_Value=72000000
 RCC.ADC34outputFreq_Value=72000000