]> git.leonardobizzoni.com Git - pioneer-stm32/commitdiff
explicit enum variant values + comments
authorLeonardoBizzoni <leo2002714@gmail.com>
Thu, 12 Mar 2026 19:24:43 +0000 (20:24 +0100)
committerLeonardoBizzoni <leo2002714@gmail.com>
Thu, 12 Mar 2026 19:24:43 +0000 (20:24 +0100)
pioneer_controller/Core/Inc/firmware/fmw_core.h
pioneer_controller/Core/Inc/firmware/fmw_messages.h
pioneer_controller/Core/Src/main.c

index 16baa05092d573363864c6b4ead79e93290f0402..87a1fc8fca1833afb2ca9296324849f1aed3059c 100644 (file)
@@ -3,10 +3,10 @@
 
 typedef uint8_t FMW_Mode;
 enum {
-  FMW_Mode_None,
-  FMW_Mode_Config,
-  FMW_Mode_Run,
-  FMW_Mode_COUNT,
+  FMW_Mode_None = 0,
+  FMW_Mode_Config = 1,
+  FMW_Mode_Run = 2,
+  FMW_Mode_COUNT = 3,
 };
 
 typedef struct FMW_Encoder {
@@ -119,6 +119,12 @@ FMW_Message fmw_message_from_uart_error(const UART_HandleTypeDef *huart);
 #define FMW_METERS_FROM_TICKS(Ticks, WheelCircumference, TicksPerRevolution) \
   ((Ticks * WheelCircumference) / TicksPerRevolution)
 
+// NOTE(lb): The variadic arguments are the fields of FMW_Hook, so you can just type
+//           `.callback = your_function_pointer, .args = your_pointer_to_args`.
+//           Calling this macro with the condition argument is GCC extension.
+//           I don't use `assert` because i never figured out how to make it trigger
+//           a debug breakpoint inside the STM32 ide debugger (and also because having a
+//           on-failure callback is handy).
 #define FMW_ASSERT(Cond, ...)           \
   do {                                  \
     FMW_Hook hook = { __VA_ARGS__ };    \
index 2a833d8e356bedc011390db633a1291c6ec24ae9..295ec40d0af6ff404fa4fc7ea835d569e7a4b6b4 100644 (file)
@@ -10,54 +10,66 @@ typedef union {
   float values[3];
 } FMW_PidConstants;
 
-#define FMW_MESSAGE_TYPE_VARIANTS(X)            \
-  X(FMW_MessageType_None)                       \
-  X(FMW_MessageType_Response)                   \
-  X(FMW_MessageType_ModeChange_Config)          \
-  X(FMW_MessageType_ModeChange_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_SetVelocity)            \
-  X(FMW_MessageType_COUNT)
+// NOTE(lb): The expansion of this macro relies on another macro called "X" (hence the name X-macro).
+//           X isn't define yet but, for it to work with this macro expansion, it must be a function-like macro
+//           with exactly 2 arguemnts: 1) the enumation variant name. 2) the corresponding numerical id.
+#define FMW_MESSAGE_TYPE_VARIANTS()             \
+  X(FMW_MessageType_None, 0)                    \
+  X(FMW_MessageType_Response, 1)                \
+  X(FMW_MessageType_ModeChange_Config, 2)       \
+  X(FMW_MessageType_ModeChange_Run, 3)          \
+  X(FMW_MessageType_Config_Robot, 4)            \
+  X(FMW_MessageType_Config_PID, 5)              \
+  X(FMW_MessageType_Config_LED, 6)              \
+  X(FMW_MessageType_Run_GetStatus, 7)           \
+  X(FMW_MessageType_Run_SetVelocity, 8)         \
+  X(FMW_MessageType_COUNT, 9)
 
+// NOTE(lb): Here i want to take all of the variants that are generated from the macro
+//           expension of FMW_MESSAGE_TYPE_VARIANTS and use them to populate the enum definition.
+//           For it to be a valid enum definition you need to take every `X(VariantName, Id)`
+//           and turn them into `VariantName = Id,`.
+//           It's important to undefine `X` after use to avoid redefinition and, more importantly,
+//           to use it in another X-macro expansion by accident.
+//           This seems pointless but when paired with `#VariantName` you can automatically
+//           turn all of the symbolic variant names into strings and now printing the variant
+//           can be done via an array lookup `[VariantName] = #VariantName` instead of a runtime check.
 typedef uint8_t FMW_MessageType;
 enum {
-#define X(Variant) Variant,
-  FMW_MESSAGE_TYPE_VARIANTS(X)
+#define X(Variant, Id) Variant = Id,
+  FMW_MESSAGE_TYPE_VARIANTS()
 #undef X
 };
 
-#define FMW_RESULT_VARIANTS(X)                                                  \
-  X(FMW_Result_Ok)                                                              \
-  X(FMW_Result_Error_InvalidArguments)                                          \
-  X(FMW_Result_Error_FaultPinTriggered)                                         \
-  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_Config_NonPositiveBaseline)                 \
-  X(FMW_Result_Error_MessageHandler_Config_NonPositiveWheelCircumference)       \
-  X(FMW_Result_Error_MessageHandler_Config_NonPositiveTicksPerRevolution)       \
-  X(FMW_Result_Error_MessageHandler_Config_NonPositiveLEDUpdatePeriod)          \
-  X(FMW_Result_Error_Command_NotRecognized)                                     \
-  X(FMW_Result_Error_Command_NotAvailable)                                      \
-  X(FMW_Result_COUNT)
+#define FMW_RESULT_VARIANTS(                                                  \
+  X(FMW_Result_Ok, 0)                                                           \
+  X(FMW_Result_Error_InvalidArguments, 1)                                       \
+  X(FMW_Result_Error_FaultPinTriggered, 2)                                      \
+  X(FMW_Result_Error_UART_Crc, 3)                                               \
+  X(FMW_Result_Error_UART_NegativeTimeout, 4)                                   \
+  X(FMW_Result_Error_UART_ReceiveTimeoutElapsed, 5)                             \
+  X(FMW_Result_Error_UART_Parity, 6)                                            \
+  X(FMW_Result_Error_UART_Frame, 7)                                             \
+  X(FMW_Result_Error_UART_Noise, 8)                                             \
+  X(FMW_Result_Error_UART_Overrun, 9)                                           \
+  X(FMW_Result_Error_Encoder_InvalidTimer, 10)                                  \
+  X(FMW_Result_Error_Encoder_NonPositiveTicksPerRevolution, 11)                 \
+  X(FMW_Result_Error_Encoder_NonPositiveWheelCircumference, 12)                 \
+  X(FMW_Result_Error_Encoder_GetTick, 13)                                       \
+  X(FMW_Result_Error_Buzzer_Timer, 14)                                          \
+  X(FMW_Result_Error_MessageHandler_InvalidState, 15)                           \
+  X(FMW_Result_Error_MessageHandler_Config_NonPositiveBaseline, 16)             \
+  X(FMW_Result_Error_MessageHandler_Config_NonPositiveWheelCircumference, 17)   \
+  X(FMW_Result_Error_MessageHandler_Config_NonPositiveTicksPerRevolution, 18)   \
+  X(FMW_Result_Error_MessageHandler_Config_NonPositiveLEDUpdatePeriod, 19)      \
+  X(FMW_Result_Error_Command_NotRecognized, 20)                                 \
+  X(FMW_Result_Error_Command_NotAvailable, 21)                                  \
+  X(FMW_Result_COUNT, 22)
 
 typedef uint8_t FMW_Result;
 enum {
-#define X(Variant) Variant,
-  FMW_RESULT_VARIANTS(X)
+#define X(Variant, Id) Variant = Id,
+  FMW_RESULT_VARIANTS()
 #undef X
 };
 
index b901b772a90e53396ada8d30bb62ae59c15240af..45104e112a4fdcf6fc6561d408944b29e2ddf23b 100644 (file)
@@ -38,7 +38,7 @@ FMW_Result message_handler(FMW_Message *msg, CRC_HandleTypeDef *hcrc)
 \r
 /* Private define ------------------------------------------------------------*/\r
 /* USER CODE BEGIN PD */\r
-#define UART_MESSANGER_HANDLE (&huart3)\r
+#define UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL (&huart3)\r
 /* USER CODE END PD */\r
 \r
 /* Private macro -------------------------------------------------------------*/\r
@@ -797,7 +797,7 @@ static void MX_GPIO_Init(void)
 /* USER CODE BEGIN 4 */\r
 void start(void) {\r
   // Enables UART RX interrupt\r
-  HAL_UART_Receive_DMA(UART_MESSANGER_HANDLE, (uint8_t*)&uart_message_buffer, sizeof uart_message_buffer);\r
+  HAL_UART_Receive_DMA(UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL, (uint8_t*)&uart_message_buffer, sizeof uart_message_buffer);\r
 \r
   for (;;) {\r
     switch (current_mode) {\r
@@ -904,6 +904,9 @@ FMW_Result message_handler(FMW_Message *msg, CRC_HandleTypeDef *hcrc) {
       pid_cross.setpoint = odometry.setpoint_left - odometry.setpoint_right;\r
     } // fallthrough\r
     case FMW_MessageType_Run_GetStatus: {\r
+      // NOTE(lb): SetVelocity continues here as well because the previous case doesn't end with a `break`.\r
+      //           order matters.\r
+\r
       int32_t current_ticks_left = ticks_left + fmw_encoder_count_get(&encoders.left);\r
       int32_t current_ticks_right = ticks_right + fmw_encoder_count_get(&encoders.right);\r
       ticks_left = ticks_right = 0;\r
@@ -920,8 +923,10 @@ FMW_Result message_handler(FMW_Message *msg, CRC_HandleTypeDef *hcrc) {
       msg.response.ticks_left = current_ticks_left;\r
       msg.response.ticks_right = current_ticks_right;\r
       msg.header.crc = HAL_CRC_Calculate(hcrc, (uint32_t*)&msg, sizeof msg);\r
-      (void)HAL_UART_Transmit(UART_MESSANGER_HANDLE, (uint8_t*)&msg, sizeof msg, HAL_MAX_DELAY);\r
+      (void)HAL_UART_Transmit(UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL, (uint8_t*)&msg, sizeof msg, HAL_MAX_DELAY);\r
       return FMW_Result_Ok;\r
+      // NOTE(lb): GetStatus&SetVelocity have to respond with the same special message format.\r
+      //           so they don't continue down to `msg_contains_error`.\r
     } break;\r
     case FMW_MessageType_ModeChange_Config: {\r
       fmw_motors_stop(motors.values, ARRLENGTH(motors.values));\r
@@ -952,11 +957,13 @@ FMW_Result message_handler(FMW_Message *msg, CRC_HandleTypeDef *hcrc) {
   } break;\r
   }\r
 \r
+  // NOTE(lb): control flow naturally converges here.\r
+  //           the symbol is used to jump here directly in case of error.\r
  msg_contains_error:;\r
   FMW_Message response = {0};\r
   response.header.type = FMW_MessageType_Response;\r
   response.response.result = result;\r
-  HAL_StatusTypeDef send_res = fmw_message_uart_send(UART_MESSANGER_HANDLE, hcrc, &response, 1);\r
+  HAL_StatusTypeDef send_res = fmw_message_uart_send(UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL, hcrc, &response, 1);\r
   FMW_ASSERT(send_res == HAL_OK);\r
   return result;\r
 }\r
@@ -988,27 +995,35 @@ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {
 }\r
 \r
 void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart) {\r
-  if (huart != UART_MESSANGER_HANDLE) { return; }\r
+  if (huart != UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL) { return; }\r
   (void)message_handler((FMW_Message*)&uart_message_buffer, &hcrc);\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
+  // NOTE(lb): listen for the next message "recursively".\r
+  HAL_UART_Receive_DMA(UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL, (uint8_t*)&uart_message_buffer, sizeof uart_message_buffer);\r
 }\r
 \r
 void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart) {\r
-  if (huart != UART_MESSANGER_HANDLE) { return; }\r
+  if (huart != UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL) { return; }\r
 \r
+  // NOTE(lb): i don't know how to determine if the error that cause the jump here\r
+  //           was during a receive or a send of a message over UART, so i'm just\r
+  //           going to stop the motors and abort the receive just in case.\r
   fmw_motors_stop(motors.values, ARRLENGTH(motors.values));\r
-  FMW_Message response = fmw_message_from_uart_error(huart);\r
+  HAL_UART_AbortReceive(huart);\r
 \r
+  FMW_Message response = fmw_message_from_uart_error(huart);\r
   retry:;\r
-  HAL_StatusTypeDef res = fmw_message_uart_send(UART_MESSANGER_HANDLE, &hcrc, &response, HAL_MAX_DELAY);\r
-  if (res != HAL_OK) { // NOTE(lb): send help\r
+  HAL_StatusTypeDef res = fmw_message_uart_send(UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL, &hcrc, &response, HAL_MAX_DELAY);\r
+  if (res != HAL_OK) {\r
+    // NOTE(lb): keep trying to send the error message even on failure until it succeeds\r
+    //           while also being extra annoying.\r
     fmw_buzzers_set(&buzzer, 1, true);\r
     goto retry;\r
   }\r
+  fmw_buzzers_set(&buzzer, 1, false);\r
 \r
-  HAL_UART_AbortReceive(huart);\r
-  HAL_UART_Receive_DMA(UART_MESSANGER_HANDLE, (uint8_t*)&uart_message_buffer, sizeof uart_message_buffer);\r
+  // NOTE(lb): go back to normal message receive after the error has been notified\r
+  HAL_UART_Receive_DMA(UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL, (uint8_t*)&uart_message_buffer, sizeof uart_message_buffer);\r
 }\r
 \r
 void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) {\r
@@ -1039,7 +1054,7 @@ void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) {
     response.response.result = FMW_Result_Error_FaultPinTriggered;\r
 \r
     retry:;\r
-    HAL_StatusTypeDef res = fmw_message_uart_send(UART_MESSANGER_HANDLE, &hcrc, &response, HAL_MAX_DELAY);\r
+    HAL_StatusTypeDef res = fmw_message_uart_send(UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL, &hcrc, &response, HAL_MAX_DELAY);\r
     if (res != HAL_OK) { // NOTE(lb): send help\r
       fmw_buzzers_set(&buzzer, 1, true);\r
       goto retry;\r