]> git.leonardobizzoni.com Git - pioneer-stm32/commitdiff
UART transmission error reporting
authorLeonardoBizzoni <leo2002714@gmail.com>
Sat, 21 Feb 2026 15:42:13 +0000 (16:42 +0100)
committerLeonardoBizzoni <leo2002714@gmail.com>
Sat, 21 Feb 2026 15:42:13 +0000 (16:42 +0100)
pioneer_controller/Core/Inc/firmware/fmw_core.h
pioneer_controller/Core/Inc/firmware/fmw_messages.h
pioneer_controller/Core/Src/firmware/fwm_core.c
pioneer_controller/Core/Src/main.c
pioneer_controller/pioneer_controller.ioc
pioneer_workstation/src/main.c

index 74e99a4ad79afb69880d6f52c5362ff9ffdbd6cd..2d84ee772a9be36b3b85c2d79a61ef2be07b84a1 100644 (file)
@@ -103,6 +103,8 @@ void fmw_buzzer_set(FMW_Buzzer buzzer[], int32_t count, bool on) __attribute__((
 FMW_Result fmw_message_uart_receive(UART_HandleTypeDef *huart, FMW_Message *msg, int32_t wait_ms)                       __attribute__((warn_unused_result, nonnull));
 void fmw_message_uart_send(UART_HandleTypeDef *huart, CRC_HandleTypeDef *hcrc, FMW_Message *msg, int32_t wait_ms)       __attribute__((nonnull));
 
+FMW_Message fmw_message_from_uart_error(const UART_HandleTypeDef *huart);
+
 #define FMW_LED_UPDATE_PERIOD 200
 #define FMW_DEBOUNCE_DELAY 200
 
index be39bce36c4fa809fea4de7ed827f741b75e89b5..74f8172b719ff73e90746ab06eacba5714fc7573 100644 (file)
@@ -10,46 +10,49 @@ typedef union {
   float values[3];
 } FMW_PidConstants;
 
+#define FMW_MESSAGE_TYPE_VARIANTS(X)            \
+  X(FMW_MessageType_None)                       \
+  X(FMW_MessageType_Response)                   \
+  X(FMW_MessageType_StateChange_Init)           \
+  X(FMW_MessageType_StateChange_Run)            \
+  X(FMW_MessageType_Config_Robot)               \
+  X(FMW_MessageType_Config_PID)                 \
+  X(FMW_MessageType_Config_LED)                 \
+  X(FMW_MessageType_Run_GetStatus)              \
+  X(FMW_MessageType_Run_GetStatus_Response)     \
+  X(FMW_MessageType_Run_SetVelocity)            \
+  X(FMW_MessageType_Run_SetVelocity_Response)   \
+  X(FMW_MessageType_COUNT)
+
 typedef uint8_t FMW_MessageType;
 enum {
-  FMW_MessageType_None,
-
-  FMW_MessageType_Error,
-  FMW_MessageType_Response,
-
-  FMW_MessageType_StateChange_Init,
-  FMW_MessageType_StateChange_Run,
-
-  FMW_MessageType_Config_Robot,
-  FMW_MessageType_Config_PID,
-  FMW_MessageType_Config_LED,
-
-  FMW_MessageType_Run_GetStatus,
-  FMW_MessageType_Run_GetStatus_Response,
-  FMW_MessageType_Run_SetVelocity,
-  FMW_MessageType_Run_SetVelocity_Response,
-
-  FMW_MessageType_COUNT,
+#define X(Variant) Variant,
+  FMW_MESSAGE_TYPE_VARIANTS(X)
+#undef X
 };
 
-#define FMW_RESULT_VARIANTS(X)                                                  \
-  X(FMW_Result_Ok)                                                              \
-  X(FMW_Result_Error_InvalidArguments)                                          \
-  X(FMW_Result_Error_UART_Crc)                                                  \
-  X(FMW_Result_Error_UART_NegativeTimeout)                                      \
-  X(FMW_Result_Error_UART_ReceiveTimeoutElapsed)                                \
-  X(FMW_Result_Error_Encoder_InvalidTimer)                                      \
-  X(FMW_Result_Error_Encoder_NonPositiveTicksPerRevolution)                     \
-  X(FMW_Result_Error_Encoder_NonPositiveWheelCircumference)                     \
-  X(FMW_Result_Error_Encoder_GetTick)                                           \
-  X(FMW_Result_Error_Buzzer_Timer)                                              \
-  X(FMW_Result_Error_MessageHandler_InvalidState)                               \
-  X(FMW_Result_Error_MessageHandler_Init_NonPositiveBaseline)                   \
-  X(FMW_Result_Error_MessageHandler_Init_NonPositiveWheelCircumference)         \
-  X(FMW_Result_Error_MessageHandler_Init_NonPositiveTicksPerRevolution)         \
-  X(FMW_Result_Error_MessageHandler_Init_NonPositiveLEDUpdatePeriod)            \
-  X(FMW_Result_Error_Command_NotRecognized)                                     \
-  X(FMW_Result_Error_Command_NotAvailable)                                      \
+#define FMW_RESULT_VARIANTS(X)                                          \
+  X(FMW_Result_Ok)                                                      \
+  X(FMW_Result_Error_InvalidArguments)                                  \
+  X(FMW_Result_Error_UART_Crc)                                          \
+  X(FMW_Result_Error_UART_NegativeTimeout)                              \
+  X(FMW_Result_Error_UART_ReceiveTimeoutElapsed)                        \
+  X(FMW_Result_Error_UART_Parity)                                       \
+  X(FMW_Result_Error_UART_Frame)                                        \
+  X(FMW_Result_Error_UART_Noise)                                        \
+  X(FMW_Result_Error_UART_Overrun)                                      \
+  X(FMW_Result_Error_Encoder_InvalidTimer)                              \
+  X(FMW_Result_Error_Encoder_NonPositiveTicksPerRevolution)             \
+  X(FMW_Result_Error_Encoder_NonPositiveWheelCircumference)             \
+  X(FMW_Result_Error_Encoder_GetTick)                                   \
+  X(FMW_Result_Error_Buzzer_Timer)                                      \
+  X(FMW_Result_Error_MessageHandler_InvalidState)                       \
+  X(FMW_Result_Error_MessageHandler_Init_NonPositiveBaseline)           \
+  X(FMW_Result_Error_MessageHandler_Init_NonPositiveWheelCircumference) \
+  X(FMW_Result_Error_MessageHandler_Init_NonPositiveTicksPerRevolution) \
+  X(FMW_Result_Error_MessageHandler_Init_NonPositiveLEDUpdatePeriod)    \
+  X(FMW_Result_Error_Command_NotRecognized)                             \
+  X(FMW_Result_Error_Command_NotAvailable)                              \
   X(FMW_Result_COUNT)
 
 typedef uint8_t FMW_Result;
@@ -67,11 +70,6 @@ typedef struct {
   } header;
 
   union {
-    struct {
-      int32_t line;
-      int32_t file_size;
-    } error;
-
     struct {
       float baseline;
       float wheel_circumference_left;
@@ -91,7 +89,7 @@ typedef struct {
       uint32_t update_period;
     } config_led;
 
-    FMW_Result result;
+    FMW_Result response;
     struct {
       FMW_Result result;
       uint16_t delta_millis;
index 6042b5acea4280f68439504e249bc6b267df7d66..68f6499799f7930322e9449807344880fda9b117 100644 (file)
@@ -32,6 +32,33 @@ void fmw_message_uart_send(UART_HandleTypeDef *huart, CRC_HandleTypeDef *hcrc, F
   FMW_ASSERT(res == HAL_OK, .callback = fmw_hook_assert_fail);
 }
 
+FMW_Message fmw_message_from_uart_error(const UART_HandleTypeDef *huart) {
+  FMW_ASSERT(huart->ErrorCode != HAL_UART_ERROR_NONE, .callback = fmw_hook_assert_fail);
+  FMW_Message res = {0};
+  res.header.type = FMW_MessageType_Response;
+  switch (huart->ErrorCode) {
+  case HAL_UART_ERROR_PE: {
+    res.response = FMW_Result_Error_UART_Parity;
+  } break;
+  case HAL_UART_ERROR_FE: {
+    res.response = FMW_Result_Error_UART_Frame;
+  } break;
+  case HAL_UART_ERROR_NE: {
+    res.response = FMW_Result_Error_UART_Noise;
+  } break;
+  case HAL_UART_ERROR_ORE: {
+    res.response = FMW_Result_Error_UART_Overrun;
+  } break;
+  case HAL_UART_ERROR_RTO: {
+    res.response = FMW_Result_Error_UART_ReceiveTimeoutElapsed;
+  } break;
+  default: { // NOTE(lb): unreachable
+    FMW_ASSERT(false, .callback = fmw_hook_assert_fail);
+  } break;
+  }
+  return res;
+}
+
 // ============================================================
 // Motor controller
 void fmw_motor_init(FMW_Motor motors[], int32_t count) {
index 1a1b1cae125762e9c0414178a3c357894f8ce610..db12543865e5135d911a050fed420478cfb77c33 100644 (file)
@@ -815,11 +815,18 @@ void start(void) {
   HAL_StatusTypeDef timer_status = HAL_TIM_Base_Start_IT(&htim6);\r
   FMW_ASSERT(timer_status == HAL_OK);\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
-      time_last_led_update = time_now;\r
-      fmw_led_update(&pled);\r
+  for (;;) {\r
+    switch (current_mode) {\r
+    case FMW_Mode_Init: {\r
+    } break;\r
+    case FMW_Mode_Run: {\r
+      static 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
+        time_last_led_update = time_now;\r
+        fmw_led_update(&pled);\r
+      }\r
+    } break;\r
     }\r
   }\r
 }\r
@@ -929,6 +936,8 @@ FMW_Result message_handler(FMW_Message *msg, CRC_HandleTypeDef *hcrc) {
 \r
 // TIMER 100Hz PID control\r
 void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {\r
+  if (htim != &htim6) { return; }\r
+\r
   // NOTE(lb): metrics taken for transmission\r
   ticks_left  += fmw_encoder_count_get(&encoders.left);\r
   ticks_right += fmw_encoder_count_get(&encoders.right);\r
@@ -952,18 +961,22 @@ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {
 }\r
 \r
 void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart) {\r
-  if (huart == UART_MESSANGER_HANDLE) {\r
-    FMW_Message response = {0};\r
-    response.header.type = FMW_MessageType_Response;\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
-    // NOTE(lb): listen for the next message.\r
-    HAL_UART_Receive_DMA(UART_MESSANGER_HANDLE, (uint8_t*)&uart_message_buffer, sizeof uart_message_buffer);\r
-  }\r
+  if (huart != UART_MESSANGER_HANDLE) { return; }\r
+  FMW_Message response = {0};\r
+  response.header.type = FMW_MessageType_Response;\r
+  response.response = message_handler((FMW_Message*)&uart_message_buffer, &hcrc);\r
+  fmw_message_uart_send(UART_MESSANGER_HANDLE, &hcrc, &response, HAL_MAX_DELAY);\r
+  // NOTE(lb): listen for the next message.\r
+  HAL_UART_Receive_DMA(UART_MESSANGER_HANDLE, (uint8_t*)&uart_message_buffer, sizeof uart_message_buffer);\r
 }\r
 \r
 void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart) {\r
-  FMW_ASSERT(false);\r
+  if (huart != UART_MESSANGER_HANDLE) { return; }\r
+  FMW_Message response = fmw_message_from_uart_error(huart);\r
+  fmw_message_uart_send(UART_MESSANGER_HANDLE, &hcrc, &response, HAL_MAX_DELAY);\r
+\r
+  HAL_UART_AbortReceive(huart);\r
+  HAL_UART_Receive_DMA(UART_MESSANGER_HANDLE, (uint8_t*)&uart_message_buffer, sizeof uart_message_buffer);\r
 }\r
 \r
 void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) {\r
index ab3cea3c836832ee18c15a87484b94bf5ef6580c..175b7bc088fe85837b5e7919ca31fb07915107ac 100644 (file)
@@ -243,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,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
+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,0-MX_CORTEX_M7_Init-CORTEX_M7-false-HAL-true,0-MX_DMA_Init-DMA-false-HAL-true
 RCC.48MHZClocksFreq_Value=24000000
 RCC.ADC12outputFreq_Value=72000000
 RCC.ADC34outputFreq_Value=72000000
index 5bdf32ff029f374ac388858bf01f93f3648d0aa5..5ff24c8aa262fd2fd4e286e3b59574aa9435d47b 100644 (file)
@@ -39,6 +39,35 @@ static int serial_open(char *portname) {
   return fd;
 }
 
+static void pprint_message(const FMW_Message *msg) {
+  static const char *message_types[] = {
+#define X(Variant) #Variant,
+    FMW_MESSAGE_TYPE_VARIANTS(X)
+#undef X
+  };
+
+  static const char *result_types[] = {
+#define X(Variant) #Variant,
+    FMW_RESULT_VARIANTS(X)
+#undef X
+  };
+
+  printf("FMW_Message {"
+         "\n  header.type = %s"
+         "\n  header.crc  = %u",
+         message_types[msg->header.type],
+         msg->header.crc);
+  switch (msg->header.type) {
+  case FMW_MessageType_Response: {
+    printf("\n  response: %s", result_types[msg->response]);
+  } break;
+  default: {
+    assert(0 && "unreachable");
+  } break;
+  }
+  printf("\n}\n");
+}
+
 int main(void) {
   int fd = serial_open("/dev/ttyACM0");
   assert(fd);
@@ -64,7 +93,8 @@ int main(void) {
     if (n >= 0) { bytes_read += (uint32_t)n; }
   }
   assert(response.header.type == FMW_MessageType_Response);
-  assert(response.result == FMW_Result_Ok);
+  pprint_message(&response);
+  assert(response.response == FMW_Result_Ok);
 
   FMW_Message msg_config_pid = {
     .header = {
@@ -95,7 +125,8 @@ int main(void) {
     if (n >= 0) { bytes_read += (uint32_t)n; }
   }
   assert(response.header.type == FMW_MessageType_Response);
-  assert(response.result == FMW_Result_Ok);
+  pprint_message(&response);
+  assert(response.response == FMW_Result_Ok);
 
   FMW_Message msg_run = {
     .header = {
@@ -109,7 +140,8 @@ int main(void) {
     if (n >= 0) { bytes_read += (uint32_t)n; }
   }
   assert(response.header.type == FMW_MessageType_Response);
-  assert(response.result == FMW_Result_Ok);
+  pprint_message(&response);
+  assert(response.response == FMW_Result_Ok);
 
   close(fd);
 }