<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="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 "${INPUTS}"" prefer-non-shared="true">
+ <provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="304593234891920611" 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 "${INPUTS}"" prefer-non-shared="true">
<language-scope id="org.eclipse.cdt.core.gcc"/>
<language-scope id="org.eclipse.cdt.core.g++"/>
</provider>
<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="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 "${INPUTS}"" prefer-non-shared="true">
+ <provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="233681210147110467" 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 "${INPUTS}"" prefer-non-shared="true">
<language-scope id="org.eclipse.cdt.core.gcc"/>
<language-scope id="org.eclipse.cdt.core.g++"/>
</provider>
typedef uint8_t FMW_Mode;
enum {
- FMW_Mode_None = 0,
- FMW_Mode_Config = 1,
- FMW_Mode_Run = 2,
- FMW_Mode_COUNT = 3,
+ FMW_Mode_None = 0,
+ FMW_Mode_Config = 1,
+ FMW_Mode_Run = 2,
+ FMW_Mode_Emergency = 3,
+ FMW_Mode_COUNT = 4,
};
typedef struct FMW_Encoder {
void *args;
} FMW_Hook;
+typedef struct FMW_InitInfo {
+ struct {
+ UART_HandleTypeDef *huart;
+ CRC_HandleTypeDef *hcrc;
+ void (*handler)(FMW_Message *msg, CRC_HandleTypeDef *hcrc);
+ } message_exchange;
+
+ struct {
+ TIM_HandleTypeDef *timer;
+ void (*on_begin)(void);
+ void (*on_end)(void);
+ uint32_t wait_at_most_ms_before_emergency;
+ } emergency;
+
+ FMW_Motor *motors;
+ int32_t motors_count;
+} FMW_InitInfo;
+
+void fmw_init(const FMW_InitInfo *info) __attribute__((nonnull));
+
+void fmw_uart_message_dispatch(void);
+void fmw_uart_message_send(FMW_Message *msg) __attribute__((nonnull));
+void fmw_uart_error(void);
+
+void fmw_emergency_begin(void);
+void fmw_emergency_end(void);
+void fmw_emergency_timer_update(void);
+
+FMW_Mode fmw_mode_current(void);
+FMW_Mode fmw_mode_transition(FMW_Mode mode);
+
+FMW_Result fmw_result_from_uart_error(void) __attribute__((nonnull, warn_unused_result));
+
void fmw_motors_init(FMW_Motor motors[], int32_t count) __attribute__((nonnull));
void fmw_motors_deinit(FMW_Motor motors[], int32_t count) __attribute__((nonnull));
void fmw_motors_stop(FMW_Motor motors[], int32_t count) __attribute__((nonnull));
void fmw_buzzers_set(FMW_Buzzer buzzer[], int32_t count, bool on) __attribute__((nonnull));
-FMW_Result fmw_message_uart_receive(UART_HandleTypeDef *huart, FMW_Message *msg, int32_t wait_ms) __attribute__((warn_unused_result, nonnull));
-HAL_StatusTypeDef fmw_message_uart_send(UART_HandleTypeDef *huart, CRC_HandleTypeDef *hcrc,
- FMW_Message *msg, int32_t wait_ms) __attribute__((nonnull, warn_unused_result));
-FMW_Message fmw_message_from_uart_error(const UART_HandleTypeDef *huart) __attribute__((nonnull, warn_unused_result));
-
Vec2Float fmw_setpoint_from_velocities(const FMW_Odometry *odometry, float linear, float angular) __attribute__((nonnull));
#define FMW_LED_UPDATE_PERIOD 200
#define FMW_DEBOUNCE_DELAY 200
+#define FMW_EMERGENCY_MODE_EXIT_BUTTON_HOLD_DURATION_MS 2000
#define FMW_V_REF 3.3f
#define FMW_ADC_RESOLUTION 4095.0f
X(FMW_MessageType_Config_LED, 6) \
X(FMW_MessageType_Run_GetStatus, 7) \
X(FMW_MessageType_Run_SetVelocity, 8) \
- X(FMW_MessageType_COUNT, 9)
+ X(FMW_MessageType_Emergency_Begin, 9) \
+ X(FMW_MessageType_Emergency_End, 10) \
+ X(FMW_MessageType_COUNT, 11)
// 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.
void ADC_IRQHandler(void);\r
void USART3_IRQHandler(void);\r
void EXTI15_10_IRQHandler(void);\r
+void TIM6_DAC_IRQHandler(void);\r
+void TIM7_IRQHandler(void);\r
/* USER CODE BEGIN EFP */\r
\r
/* USER CODE END EFP */\r
#include <math.h>
static struct {
+ void (*callback_message_handler)(FMW_Message *msg, CRC_HandleTypeDef *hcrc);
+ void (*callback_emergency_begin)(void);
+ void (*callback_emergency_end)(void);
+
+ TIM_HandleTypeDef *emergency_timer;
+ uint32_t emergency_mode_grace_period_ms;
+ volatile uint32_t emergency_last_message_received_time;
+
FMW_Motor *motors;
int32_t motors_count;
-} fmw_state;
+ bool motors_active;
+ bool motors_active_before_emergency;
+
+ UART_HandleTypeDef *huart;
+ CRC_HandleTypeDef *hcrc;
+
+ volatile FMW_Message uart_buffer;
+ volatile FMW_Mode mode_current;
+ volatile FMW_Mode mode_previous;
+} fmw_state = {
+ .emergency_mode_grace_period_ms = 1000,
+ .mode_current = FMW_Mode_Config,
+ .mode_previous = FMW_Mode_None,
+};
static void fmw_hook_assert_fail(void *_) {
if (fmw_state.motors != NULL) {
}
}
+// ============================================================
+// Firmware initialization
+void fmw_init(const FMW_InitInfo *info) {
+ FMW_ASSERT(info->message_exchange.huart != NULL);
+ FMW_ASSERT(info->message_exchange.hcrc != NULL);
+ FMW_ASSERT(info->message_exchange.handler != NULL);
+ FMW_ASSERT(info->emergency.on_begin != NULL);
+ FMW_ASSERT(info->emergency.on_end != NULL);
+ FMW_ASSERT(info->motors_count >= 0);
+ if (info->motors_count > 0) { FMW_ASSERT(info->motors != NULL); }
+
+ fmw_state.motors = info->motors;
+ fmw_state.motors_count = info->motors_count;
+ fmw_state.huart = info->message_exchange.huart;
+ fmw_state.hcrc = info->message_exchange.hcrc;
+ fmw_state.emergency_mode_grace_period_ms = info->emergency.wait_at_most_ms_before_emergency;
+ fmw_state.callback_message_handler = info->message_exchange.handler;
+ fmw_state.callback_emergency_begin = info->emergency.on_begin;
+ fmw_state.callback_emergency_end = info->emergency.on_end;
+ fmw_state.emergency_timer = info->emergency.timer;
+
+ HAL_StatusTypeDef timer_init_res = HAL_TIM_Base_Start_IT(info->emergency.timer);
+ FMW_ASSERT(timer_init_res == HAL_OK);
+
+ HAL_StatusTypeDef dma_init_res = HAL_UART_Receive_DMA(fmw_state.huart, (uint8_t*)&fmw_state.uart_buffer, sizeof fmw_state.uart_buffer);
+ FMW_ASSERT(dma_init_res == HAL_OK);
+}
+
+void fmw_uart_message_dispatch(void) {
+ fmw_state.emergency_last_message_received_time = HAL_GetTick();
+ fmw_state.callback_message_handler((FMW_Message*)&fmw_state.uart_buffer, fmw_state.hcrc);
+ // NOTE(lb): listen for the next message "recursively".
+ HAL_UART_Receive_DMA(fmw_state.huart, (uint8_t*)&fmw_state.uart_buffer, sizeof fmw_state.uart_buffer);
+}
+
+void fmw_uart_error(void) {
+ // NOTE(lb): i don't know how to determine if the error that cause the jump here
+ // was during a receive or a send of a message over UART, so i'm just
+ // going to stop the motors and abort the receive just in case.
+ fmw_motors_stop(fmw_state.motors, fmw_state.motors_count);
+ HAL_UART_AbortReceive(fmw_state.huart);
+
+ FMW_Message response = {0};
+ response.response.result = fmw_result_from_uart_error();
+ fmw_uart_message_send(&response);
+ HAL_UART_Receive_DMA(fmw_state.huart, (uint8_t*)&fmw_state.uart_buffer, sizeof fmw_state.uart_buffer);
+}
+
+void fmw_emergency_begin(void) {
+ if (fmw_state.mode_current == FMW_Mode_Emergency) { return; }
+ if (fmw_state.motors_count > 0) {
+ fmw_state.motors_active_before_emergency = fmw_state.motors[0].active;
+ if (fmw_state.motors[0].active) {
+ fmw_motors_stop(fmw_state.motors, fmw_state.motors_count);
+ fmw_motors_disable(fmw_state.motors, fmw_state.motors_count);
+ }
+ }
+
+ fmw_state.mode_previous = fmw_state.mode_current;
+ fmw_state.mode_current = FMW_Mode_Emergency;
+
+ if (fmw_state.callback_emergency_begin) { fmw_state.callback_emergency_begin(); }
+}
+
+void fmw_emergency_end(void) {
+ if (fmw_state.mode_previous == FMW_Mode_None) { return; }
+ fmw_state.mode_current = fmw_state.mode_previous;
+ fmw_state.mode_previous = FMW_Mode_None;
+ if (fmw_state.motors_count > 0 && fmw_state.motors_active_before_emergency) {
+ fmw_motors_enable(fmw_state.motors, fmw_state.motors_count);
+ }
+ if (fmw_state.callback_emergency_end) { fmw_state.callback_emergency_end(); }
+}
+
+void fmw_emergency_timer_update(void) {
+ if (fmw_state.mode_current != FMW_Mode_Run) { return; }
+ uint32_t time_now = HAL_GetTick();
+ if (time_now - fmw_state.emergency_last_message_received_time > fmw_state.emergency_mode_grace_period_ms) {
+ fmw_emergency_begin();
+ }
+}
+
+FMW_Mode fmw_mode_current(void) {
+ return fmw_state.mode_current;
+}
+
+FMW_Mode fmw_mode_transition(FMW_Mode mode) {
+ FMW_ASSERT(mode > FMW_Mode_None);
+ FMW_ASSERT(mode < FMW_Mode_COUNT);
+ FMW_Mode old = fmw_state.mode_previous;
+ fmw_state.mode_previous = fmw_state.mode_current;
+ fmw_state.mode_current = mode;
+ return old;
+}
+
+// ============================================================
+// Misc
FMW_Result fmw_message_uart_receive(UART_HandleTypeDef *huart, FMW_Message *msg, int32_t wait_ms) {
FMW_ASSERT(wait_ms >= 0, .callback = fmw_hook_assert_fail);
memset(msg, 0, sizeof *msg);
return FMW_Result_Ok;
}
-HAL_StatusTypeDef fmw_message_uart_send(UART_HandleTypeDef *huart, CRC_HandleTypeDef *hcrc, FMW_Message *msg, int32_t wait_ms) {
- msg->header.crc = HAL_CRC_Calculate(hcrc, (uint32_t*)msg, sizeof *msg);
- HAL_StatusTypeDef res = HAL_UART_Transmit(huart, (uint8_t*)msg, sizeof *msg, wait_ms);
- return res;
+void fmw_uart_message_send(FMW_Message *msg) {
+ msg->header.crc = HAL_CRC_Calculate(fmw_state.hcrc, (uint32_t*)msg, sizeof *msg);
+ HAL_StatusTypeDef res = HAL_UART_Transmit(fmw_state.huart, (uint8_t*)msg, sizeof *msg, fmw_state.emergency_mode_grace_period_ms);
+ if (res != HAL_OK) { fmw_emergency_begin(); }
}
-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) {
+FMW_Result fmw_result_from_uart_error(void) {
+ FMW_ASSERT(fmw_state.huart->ErrorCode != HAL_UART_ERROR_NONE, .callback = fmw_hook_assert_fail);
+ switch (fmw_state.huart->ErrorCode) {
case HAL_UART_ERROR_PE: {
- res.response.result = FMW_Result_Error_UART_Parity;
+ return FMW_Result_Error_UART_Parity;
} break;
case HAL_UART_ERROR_FE: {
- res.response.result = FMW_Result_Error_UART_Frame;
+ return FMW_Result_Error_UART_Frame;
} break;
case HAL_UART_ERROR_NE: {
- res.response.result = FMW_Result_Error_UART_Noise;
+ return FMW_Result_Error_UART_Noise;
} break;
case HAL_UART_ERROR_ORE: {
- res.response.result = FMW_Result_Error_UART_Overrun;
+ return FMW_Result_Error_UART_Overrun;
} break;
case HAL_UART_ERROR_RTO: {
- res.response.result = FMW_Result_Error_UART_ReceiveTimeoutElapsed;
+ return FMW_Result_Error_UART_ReceiveTimeoutElapsed;
} break;
default: { // NOTE(lb): unreachable
FMW_ASSERT(false, .callback = fmw_hook_assert_fail);
} break;
}
- return res;
+ return FMW_Result_Ok;
}
Vec2Float fmw_setpoint_from_velocities(const FMW_Odometry *odometry, float linear, float angular) {
float fmw_encoder_get_linear_velocity(const FMW_Encoder *encoder, float meters_traveled) {
float deltatime = encoder->current_millis - encoder->previous_millis;
- FMW_ASSERT(deltatime > 0.f, .callback = fmw_hook_assert_fail);
+ if (deltatime == 0.f) { return 0.f; }
float linear_velocity = meters_traveled / (deltatime / 1000.f);
return linear_velocity;
}
\r
/* Private typedef -----------------------------------------------------------*/\r
/* USER CODE BEGIN PTD */\r
-FMW_Result message_handler(FMW_Message *msg, CRC_HandleTypeDef *hcrc)\r
- __attribute__((nonnull));\r
+void message_handler(FMW_Message *msg, CRC_HandleTypeDef *hcrc) __attribute__((nonnull));\r
+\r
+void emergency_mode_begin(void);\r
+void emergency_mode_end(void);\r
/* USER CODE END PTD */\r
\r
/* Private define ------------------------------------------------------------*/\r
TIM_HandleTypeDef htim3;\r
TIM_HandleTypeDef htim4;\r
TIM_HandleTypeDef htim6;\r
+TIM_HandleTypeDef htim7;\r
\r
UART_HandleTypeDef huart3;\r
DMA_HandleTypeDef hdma_usart3_rx;\r
\r
static volatile int32_t ticks_left = 0;\r
static volatile int32_t ticks_right = 0;\r
-static volatile FMW_Message uart_message_buffer = {0};\r
-static volatile uint32_t time_last_motors = 0;\r
-static volatile FMW_Mode current_mode = FMW_Mode_Config;\r
\r
/* USER CODE END PV */\r
\r
static void MX_TIM3_Init(void);\r
static void MX_TIM6_Init(void);\r
static void MX_CRC_Init(void);\r
+static void MX_TIM7_Init(void);\r
/* USER CODE BEGIN PFP */\r
\r
/* USER CODE END PFP */\r
MX_TIM3_Init();\r
MX_TIM6_Init();\r
MX_CRC_Init();\r
+ MX_TIM7_Init();\r
/* USER CODE BEGIN 2 */\r
\r
start();\r
\r
}\r
\r
+/**\r
+ * @brief TIM7 Initialization Function\r
+ * @param None\r
+ * @retval None\r
+ */\r
+static void MX_TIM7_Init(void)\r
+{\r
+\r
+ /* USER CODE BEGIN TIM7_Init 0 */\r
+\r
+ /* USER CODE END TIM7_Init 0 */\r
+\r
+ TIM_MasterConfigTypeDef sMasterConfig = {0};\r
+\r
+ /* USER CODE BEGIN TIM7_Init 1 */\r
+\r
+ /* USER CODE END TIM7_Init 1 */\r
+ htim7.Instance = TIM7;\r
+ htim7.Init.Prescaler = 10799;\r
+ htim7.Init.CounterMode = TIM_COUNTERMODE_UP;\r
+ htim7.Init.Period = 9999;\r
+ htim7.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;\r
+ if (HAL_TIM_Base_Init(&htim7) != HAL_OK)\r
+ {\r
+ Error_Handler();\r
+ }\r
+ sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;\r
+ sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;\r
+ if (HAL_TIMEx_MasterConfigSynchronization(&htim7, &sMasterConfig) != HAL_OK)\r
+ {\r
+ Error_Handler();\r
+ }\r
+ /* USER CODE BEGIN TIM7_Init 2 */\r
+\r
+ /* USER CODE END TIM7_Init 2 */\r
+\r
+}\r
+\r
/**\r
* @brief USART3 Initialization Function\r
* @param None\r
\r
/*Configure GPIO pin : USER_Btn_Pin */\r
GPIO_InitStruct.Pin = USER_Btn_Pin;\r
- GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;\r
+ GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING_FALLING;\r
GPIO_InitStruct.Pull = GPIO_NOPULL;\r
HAL_GPIO_Init(USER_Btn_GPIO_Port, &GPIO_InitStruct);\r
\r
\r
/* USER CODE BEGIN 4 */\r
void start(void) {\r
- // Enables UART RX interrupt\r
- HAL_UART_Receive_DMA(UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL, (uint8_t*)&uart_message_buffer, sizeof uart_message_buffer);\r
+ FMW_InitInfo fmw_info = {\r
+ .motors = motors.values,\r
+ .motors_count = ARRLENGTH(motors.values),\r
+ .emergency = {\r
+ .timer = &htim7,\r
+ .on_begin = emergency_mode_begin,\r
+ .on_end = emergency_mode_end,\r
+ .wait_at_most_ms_before_emergency = 2000,\r
+ },\r
+ .message_exchange = {\r
+ .huart = UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL,\r
+ .hcrc = &hcrc,\r
+ .handler = message_handler,\r
+ },\r
+ };\r
+ fmw_init(&fmw_info);\r
\r
for (;;) {\r
- switch (current_mode) {\r
+ switch (fmw_mode_current()) {\r
case FMW_Mode_Config: {\r
} break;\r
case FMW_Mode_Run: {\r
return output;\r
}\r
\r
-FMW_Result message_handler(FMW_Message *msg, CRC_HandleTypeDef *hcrc) {\r
+void emergency_mode_begin(void) {\r
+ HAL_GPIO_TogglePin(GPIOB, LD1_Pin | LD2_Pin | LD3_Pin);\r
+ fmw_encoder_count_reset(&encoders.left);\r
+ fmw_encoder_count_reset(&encoders.right);\r
+}\r
+\r
+void emergency_mode_end(void) {\r
+ HAL_GPIO_TogglePin(GPIOB, LD1_Pin | LD2_Pin | LD3_Pin);\r
+}\r
+\r
+void message_handler(FMW_Message *msg, CRC_HandleTypeDef *hcrc) {\r
// NOTE(lb): the `msg->header.crc != -1` checks are just because i haven't\r
// implemented CRC into the program that sends these messages.\r
// i also don't know if the code to calculate CRC is correct (probably isn't).\r
+\r
+ FMW_Result result = FMW_Result_Ok;\r
if (msg->header.crc != -1) {\r
uint32_t crc_received = msg->header.crc;\r
msg->header.crc = 0;\r
uint32_t crc_computed = HAL_CRC_Calculate(hcrc, (uint32_t*)msg, sizeof *msg);\r
- if (!(crc_computed == crc_received)) { return FMW_Result_Error_UART_Crc; }\r
+ if (crc_computed != crc_received) {\r
+ result = FMW_Result_Error_UART_Crc;\r
+ goto msg_contains_error;\r
+ }\r
}\r
\r
- FMW_Result result = FMW_Result_Ok;\r
- switch (current_mode) {\r
+ switch (fmw_mode_current()) {\r
case FMW_Mode_Config: {\r
switch (msg->header.type) {\r
case FMW_MessageType_ModeChange_Run: {\r
HAL_StatusTypeDef timer_status = HAL_TIM_Base_Start_IT(&htim6);\r
FMW_ASSERT(timer_status == HAL_OK);\r
\r
- current_mode = FMW_Mode_Run;\r
+ fmw_mode_transition(FMW_Mode_Run);\r
} break;\r
case FMW_MessageType_Config_Robot: {\r
if (!(msg->config_robot.baseline > 0.f)) {\r
pled.voltage_hysteresis = msg->config_led.voltage_hysteresis;\r
led_update_period = msg->config_led.update_period;\r
} break;\r
+ case FMW_MessageType_Emergency_Begin: {\r
+ fmw_emergency_begin();\r
+ } break;\r
+ case FMW_MessageType_Emergency_End:\r
case FMW_MessageType_ModeChange_Config:\r
case FMW_MessageType_Run_GetStatus:\r
case FMW_MessageType_Run_SetVelocity: {\r
msg.response.orientation_y = odometry.orientation.y;\r
msg.response.velocity_linear = (odometry.velocity_linear.left + odometry.velocity_linear.right) / 2.f;\r
msg.response.velocity_angular = odometry.velocity_angular;\r
- msg.header.crc = HAL_CRC_Calculate(hcrc, (uint32_t*)&msg, sizeof msg);\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
+ fmw_uart_message_send(&msg);\r
+ return;\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
HAL_StatusTypeDef timer_status = HAL_TIM_Base_Stop_IT(&htim6);\r
FMW_ASSERT(timer_status == HAL_OK);\r
\r
- current_mode = FMW_Mode_Config;\r
+ fmw_mode_transition(FMW_Mode_Config);\r
+ } break;\r
+ case FMW_MessageType_Emergency_Begin: {\r
+ fmw_emergency_begin();\r
} break;\r
+ case FMW_MessageType_Emergency_End:\r
case FMW_MessageType_ModeChange_Run:\r
case FMW_MessageType_Config_Robot:\r
case FMW_MessageType_Config_PID:\r
} break;\r
}\r
} break;\r
+ case FMW_Mode_Emergency: {\r
+ switch (msg->header.type) {\r
+ case FMW_MessageType_Emergency_End: {\r
+ fmw_emergency_end();\r
+ } break;\r
+ default: {\r
+ result = FMW_Result_Error_Command_NotAvailable;\r
+ } break;\r
+ }\r
+ } 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_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL, hcrc, &response, 1);\r
- FMW_ASSERT(send_res == HAL_OK);\r
- return result;\r
+ FMW_Message msg_response = {0};\r
+ msg_response.header.type = FMW_MessageType_Response;\r
+ msg_response.response.result = result;\r
+ fmw_uart_message_send(&msg_response);\r
}\r
\r
-// TIMER 100Hz PID control\r
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {\r
- if (htim != &htim6) { return; }\r
-\r
- { // PID control\r
+ if (htim == &htim7) { // TIMER 1Hz no message exchange check\r
+ fmw_emergency_timer_update();\r
+ } else if (htim == &htim6) { // TIMER 100Hz PID control\r
fmw_encoders_update(encoders.values, ARRLENGTH(encoders.values));\r
ticks_left += encoders.left.ticks;\r
ticks_right += encoders.right.ticks;\r
}\r
\r
void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart) {\r
- if (huart != UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL) { return; }\r
- (void)message_handler((FMW_Message*)&uart_message_buffer, &hcrc);\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
+ if (huart == UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL) {\r
+ fmw_uart_message_dispatch();\r
+ return;\r
+ }\r
}\r
\r
void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart) {\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
- 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_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
+ if (huart == UART_HANDLE_PTR_USED_FOR_MESSAGE_EXCHANGE_PROTOCOL) {\r
+ fmw_uart_error();\r
+ return;\r
}\r
- fmw_buzzers_set(&buzzer, 1, false);\r
-\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
uint32_t time_now = HAL_GetTick();\r
\r
switch (GPIO_Pin) {\r
+ case USER_Btn_Pin: {\r
+ static uint32_t time_btn_press_start = 0;\r
+ static uint32_t time_last_emergency = 0;\r
+ if (time_now - time_last_emergency <= FMW_DEBOUNCE_DELAY) { return; }\r
+ time_last_emergency = time_now;\r
+ GPIO_PinState btn_state = HAL_GPIO_ReadPin(USER_Btn_GPIO_Port, USER_Btn_Pin);\r
+ if (btn_state == GPIO_PIN_SET) {\r
+ time_btn_press_start = time_now;\r
+ } else {\r
+ uint32_t btn_held_duration = time_now - time_btn_press_start;\r
+ if (btn_held_duration >= FMW_EMERGENCY_MODE_EXIT_BUTTON_HOLD_DURATION_MS) {\r
+ fmw_emergency_end();\r
+ } else {\r
+ fmw_emergency_begin();\r
+ }\r
+ }\r
+ } break;\r
case motors_btn_Pin: {\r
+ static uint32_t time_last_motors = 0;\r
if (time_now - time_last_motors > FMW_DEBOUNCE_DELAY) {\r
time_last_motors = time_now;\r
if (motors.left.active && motors.right.active) {\r
response.header.type = FMW_MessageType_Response;\r
response.response.result = FMW_Result_Error_FaultPinTriggered;\r
\r
- retry:;\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
- }\r
+ fmw_uart_message_send(&response);\r
\r
HAL_TIM_Base_Stop_IT(&htim6);\r
} break;\r
/* USER CODE END TIM6_MspInit 0 */\r
/* Peripheral clock enable */\r
__HAL_RCC_TIM6_CLK_ENABLE();\r
+ /* TIM6 interrupt Init */\r
+ HAL_NVIC_SetPriority(TIM6_DAC_IRQn, 0, 0);\r
+ HAL_NVIC_EnableIRQ(TIM6_DAC_IRQn);\r
/* USER CODE BEGIN TIM6_MspInit 1 */\r
\r
/* USER CODE END TIM6_MspInit 1 */\r
+ }\r
+ else if(htim_base->Instance==TIM7)\r
+ {\r
+ /* USER CODE BEGIN TIM7_MspInit 0 */\r
+\r
+ /* USER CODE END TIM7_MspInit 0 */\r
+ /* Peripheral clock enable */\r
+ __HAL_RCC_TIM7_CLK_ENABLE();\r
+ /* TIM7 interrupt Init */\r
+ HAL_NVIC_SetPriority(TIM7_IRQn, 0, 0);\r
+ HAL_NVIC_EnableIRQ(TIM7_IRQn);\r
+ /* USER CODE BEGIN TIM7_MspInit 1 */\r
\r
+ /* USER CODE END TIM7_MspInit 1 */\r
}\r
\r
}\r
/* USER CODE END TIM6_MspDeInit 0 */\r
/* Peripheral clock disable */\r
__HAL_RCC_TIM6_CLK_DISABLE();\r
+\r
+ /* TIM6 interrupt DeInit */\r
+ HAL_NVIC_DisableIRQ(TIM6_DAC_IRQn);\r
/* USER CODE BEGIN TIM6_MspDeInit 1 */\r
\r
/* USER CODE END TIM6_MspDeInit 1 */\r
}\r
+ else if(htim_base->Instance==TIM7)\r
+ {\r
+ /* USER CODE BEGIN TIM7_MspDeInit 0 */\r
+\r
+ /* USER CODE END TIM7_MspDeInit 0 */\r
+ /* Peripheral clock disable */\r
+ __HAL_RCC_TIM7_CLK_DISABLE();\r
+\r
+ /* TIM7 interrupt DeInit */\r
+ HAL_NVIC_DisableIRQ(TIM7_IRQn);\r
+ /* USER CODE BEGIN TIM7_MspDeInit 1 */\r
+\r
+ /* USER CODE END TIM7_MspDeInit 1 */\r
+ }\r
\r
}\r
\r
\r
/* External variables --------------------------------------------------------*/\r
extern ADC_HandleTypeDef hadc1;\r
+extern TIM_HandleTypeDef htim6;\r
+extern TIM_HandleTypeDef htim7;\r
extern DMA_HandleTypeDef hdma_usart3_rx;\r
extern UART_HandleTypeDef huart3;\r
/* USER CODE BEGIN EV */\r
/* USER CODE END EXTI15_10_IRQn 1 */\r
}\r
\r
+/**\r
+ * @brief This function handles TIM6 global interrupt, DAC1 and DAC2 underrun error interrupts.\r
+ */\r
+void TIM6_DAC_IRQHandler(void)\r
+{\r
+ /* USER CODE BEGIN TIM6_DAC_IRQn 0 */\r
+\r
+ /* USER CODE END TIM6_DAC_IRQn 0 */\r
+ HAL_TIM_IRQHandler(&htim6);\r
+ /* USER CODE BEGIN TIM6_DAC_IRQn 1 */\r
+\r
+ /* USER CODE END TIM6_DAC_IRQn 1 */\r
+}\r
+\r
+/**\r
+ * @brief This function handles TIM7 global interrupt.\r
+ */\r
+void TIM7_IRQHandler(void)\r
+{\r
+ /* USER CODE BEGIN TIM7_IRQn 0 */\r
+\r
+ /* USER CODE END TIM7_IRQn 0 */\r
+ HAL_TIM_IRQHandler(&htim7);\r
+ /* USER CODE BEGIN TIM7_IRQn 1 */\r
+\r
+ /* USER CODE END TIM7_IRQn 1 */\r
+}\r
+\r
/* USER CODE BEGIN 1 */\r
\r
/* USER CODE END 1 */\r
Mcu.IP1=CORTEX_M7
Mcu.IP10=TIM4
Mcu.IP11=TIM6
-Mcu.IP12=USART3
+Mcu.IP12=TIM7
+Mcu.IP13=USART3
Mcu.IP2=CRC
Mcu.IP3=DMA
Mcu.IP4=NVIC
Mcu.IP7=TIM1
Mcu.IP8=TIM2
Mcu.IP9=TIM3
-Mcu.IPNb=13
+Mcu.IPNb=14
Mcu.Name=STM32F767ZITx
Mcu.Package=LQFP144
Mcu.Pin0=PC13
Mcu.Pin3=PH0/OSC_IN
Mcu.Pin30=VP_SYS_VS_Systick
Mcu.Pin31=VP_TIM6_VS_ClockSourceINT
+Mcu.Pin32=VP_TIM7_VS_ClockSourceINT
Mcu.Pin4=PH1/OSC_OUT
Mcu.Pin5=PC0
Mcu.Pin6=PA0/WKUP
Mcu.Pin7=PA1
Mcu.Pin8=PA2
Mcu.Pin9=PA3
-Mcu.PinsNb=32
+Mcu.PinsNb=33
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F767ZITx
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.TIM6_DAC_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
+NVIC.TIM7_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
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
PC0.Signal=GPIO_Output
PC13.GPIOParameters=GPIO_Label,GPIO_ModeDefaultEXTI
PC13.GPIO_Label=USER_Btn [B1]
-PC13.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_RISING
+PC13.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_RISING_FALLING
PC13.Locked=true
PC13.Signal=GPXTI13
PC14/OSC32_IN.Locked=true
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,3-MX_DMA_Init-DMA-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,12-MX_TIM7_Init-TIM7-false-HAL-true,0-MX_CORTEX_M7_Init-CORTEX_M7-false-HAL-true
RCC.48MHZClocksFreq_Value=24000000
RCC.ADC12outputFreq_Value=72000000
RCC.ADC34outputFreq_Value=72000000
TIM4.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
TIM4.IPParameters=Channel-PWM Generation3 CH3,Channel-PWM Generation4 CH4,Period
TIM4.Period=3840
+TIM7.AutoReloadPreload=TIM_AUTORELOAD_PRELOAD_DISABLE
+TIM7.IPParameters=Prescaler,AutoReloadPreload,Period
+TIM7.Period=9999
+TIM7.Prescaler=10799
USART3.IPParameters=VirtualMode-Asynchronous
USART3.VirtualMode-Asynchronous=VM_ASYNC
VP_CRC_VS_CRC.Mode=CRC_Activate
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
VP_TIM6_VS_ClockSourceINT.Mode=Enable_Timer
VP_TIM6_VS_ClockSourceINT.Signal=TIM6_VS_ClockSourceINT
+VP_TIM7_VS_ClockSourceINT.Mode=Enable_Timer
+VP_TIM7_VS_ClockSourceINT.Signal=TIM7_VS_ClockSourceINT
board=NUCLEO-F767ZI
boardIOC=true
isbadioc=false
"messages/ConfigLed.msg"
"messages/ConfigPid.msg"
"messages/ConfigRobot.msg"
+ "messages/EmergencyMode.msg"
"services/ChangeMode.srv"
"services/ConfigLed.srv"
"services/ConfigPid.srv"
"services/ConfigRobot.srv"
+ "services/EmergencyMode.srv"
DEPENDENCIES service_msgs
)
-byte mode
\ No newline at end of file
+uint8 mode
\ No newline at end of file
P3DX_Controller_Node::P3DX_Controller_Node(int32_t serial_fd) :
rclcpp::Node("P3DX_Controller_Node"),
serial_fd(serial_fd),
- stm32_config_mode(false),
publisher_odometry(this->create_publisher<nav_msgs::msg::Odometry>("odometry", 10)),
subscriber_velocity(this->create_subscription<geometry_msgs::msg::Twist>("p3dx_command_velocity", 10,
std::bind(&P3DX_Controller_Node::callback_subscribe_command_velocity,
&P3DX_Controller_Node::callback_service_command_config_robot_s)),
service_config_led(this->create_service<pioneer3dx_controller::srv::ConfigLed>("p3dx_command_config_led",
&P3DX_Controller_Node::callback_service_command_config_led_s)),
+ service_emergency_mode(this->create_service<pioneer3dx_controller::srv::EmergencyMode>("p3dx_command_emergency_mode",
+ &P3DX_Controller_Node::callback_service_command_emergency_mode_s)),
timer_publisher_odometry(this->create_wall_timer(50ms, std::bind(&P3DX_Controller_Node::callback_publish_odometry, this)))
{
assert(this->serial_fd != -1);
void P3DX_Controller_Node::callback_publish_odometry(void)
{
- if (this->stm32_config_mode) { return; }
-
FMW_Message msg_get_status;
msg_get_status.header.type = FMW_MessageType_Run_GetStatus;
msg_get_status.header.crc = (uint32_t)-1;
FMW_Message response = this->stm32_message_send(&msg_get_status);
assert(response.header.type == FMW_MessageType_Response);
- this->stm32_message_print(&response);
if (response.response.result == FMW_Result_Error_Command_NotAvailable) {
- this->stm32_config_mode = true;
return;
- } else {
- this->stm32_config_mode = false;
}
+ this->stm32_message_print(&response);
nav_msgs::msg::Odometry output;
output.header.frame_id = this->get_parameter("frame_id_odometry").as_string();
void P3DX_Controller_Node::callback_subscribe_command_velocity(const geometry_msgs::msg::Twist::SharedPtr cmd)
{
- if (this->stm32_config_mode) { return; }
-
FMW_Message msg;
::memset(&msg, 0, sizeof(msg));
msg.header.type = FMW_MessageType_Run_SetVelocity;
msg.run_set_velocity.angular = cmd->angular.x;
FMW_Message response_msg = this->stm32_message_send(&msg);
+ this->stm32_message_print(&response_msg);
assert(response_msg.header.type == FMW_MessageType_Response);
assert(response_msg.response.result == FMW_Result_Ok);
}
msg.header.crc = (uint32_t)-1;
FMW_Message response_msg = p3dx_controller->stm32_message_send(&msg);
+ p3dx_controller->stm32_message_print(&response_msg);
assert(response_msg.header.type == FMW_MessageType_Response);
response->status_response = (uint8_t)response_msg.response.result;
- if (response_msg.response.result == FMW_Result_Ok) {
- p3dx_controller->stm32_config_mode = (mode == P3DX_Cmd_ChangeMode_Kind::Config);
- }
}
}
::memcpy(msg.config_pid.cross.values, request->cross.data(), sizeof(msg.config_pid.left.values));
FMW_Message response_msg = p3dx_controller->stm32_message_send(&msg);
+ p3dx_controller->stm32_message_print(&response_msg);
assert(response_msg.header.type == FMW_MessageType_Response);
response->status_response = (uint8_t)response_msg.response.result;
}
msg.config_robot.ticks_per_revolution_right = request->ticks_per_revolution_right;
FMW_Message response_msg = p3dx_controller->stm32_message_send(&msg);
+ p3dx_controller->stm32_message_print(&response_msg);
assert(response_msg.header.type == FMW_MessageType_Response);
response->status_response = (uint8_t)response_msg.response.result;
}
msg.config_led.update_period = request->update_period;
FMW_Message response_msg = p3dx_controller->stm32_message_send(&msg);
+ p3dx_controller->stm32_message_print(&response_msg);
+ assert(response_msg.header.type == FMW_MessageType_Response);
+ response->status_response = (uint8_t)response_msg.response.result;
+}
+
+void P3DX_Controller_Node::callback_service_command_emergency_mode_s(const std::shared_ptr<pioneer3dx_controller::srv::EmergencyMode::Request> request,
+ std::shared_ptr<pioneer3dx_controller::srv::EmergencyMode::Response> response)
+{
+ RCLCPP_INFO(p3dx_controller->get_logger(), "emergency-mode %s", (request->enable ? "entered" : "exit"));
+
+ FMW_Message msg;
+ ::memset(&msg, 0, sizeof(msg));
+ msg.header.type = (request->enable ? FMW_MessageType_Emergency_Begin : FMW_MessageType_Emergency_End);
+ msg.header.crc = (uint32_t)-1;
+
+ FMW_Message response_msg = p3dx_controller->stm32_message_send(&msg);
+ p3dx_controller->stm32_message_print(&response_msg);
assert(response_msg.header.type == FMW_MessageType_Response);
response->status_response = (uint8_t)response_msg.response.result;
}
assert(bytes_written != -1);
assert(bytes_written > 0);
assert(bytes_written == sizeof(FMW_Message));
- RCLCPP_INFO(this->get_logger(), "message sent to stm32");
for (uint32_t bytes_read = 0; bytes_read < sizeof(*msg);) {
ssize_t n = ::read(this->serial_fd, ((uint8_t*)&res) + bytes_read, sizeof(res) - bytes_read);
assert(n != -1);
}
}
this->serial_mutex.unlock();
- this->stm32_message_print(&res);
assert(res.header.type == FMW_MessageType_Response);
return res;
}
#include <pioneer3dx_controller/srv/config_pid.hpp>
#include <pioneer3dx_controller/srv/config_led.hpp>
#include <pioneer3dx_controller/srv/config_robot.hpp>
+#include <pioneer3dx_controller/srv/emergency_mode.hpp>
extern "C" {
#include "stm32_messages.h"
None = 0,
Config = 1,
Run = 2,
- COUNT = 3,
+ Emergency = 3,
+ COUNT = 4,
};
struct P3DX_Controller_Node: public rclcpp::Node {
const int32_t serial_fd;
- bool stm32_config_mode;
std::mutex serial_mutex;
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr publisher_odometry;
rclcpp::Service<pioneer3dx_controller::srv::ConfigPid>::SharedPtr service_config_pid;
rclcpp::Service<pioneer3dx_controller::srv::ConfigRobot>::SharedPtr service_config_robot;
rclcpp::Service<pioneer3dx_controller::srv::ConfigLed>::SharedPtr service_config_led;
+ rclcpp::Service<pioneer3dx_controller::srv::EmergencyMode>::SharedPtr service_emergency_mode;
rclcpp::TimerBase::SharedPtr timer_publisher_odometry;
P3DX_Controller_Node(int32_t serial_fd);
std::shared_ptr<pioneer3dx_controller::srv::ConfigRobot::Response> response);
static void callback_service_command_config_led_s(const std::shared_ptr<pioneer3dx_controller::srv::ConfigLed::Request> request,
std::shared_ptr<pioneer3dx_controller::srv::ConfigLed::Response> response);
+ static void callback_service_command_emergency_mode_s(const std::shared_ptr<pioneer3dx_controller::srv::EmergencyMode::Request> request,
+ std::shared_ptr<pioneer3dx_controller::srv::EmergencyMode::Response> response);
FMW_Message stm32_message_send(const FMW_Message *msg);
void stm32_message_print(const FMW_Message *msg);
X(FMW_MessageType_Config_LED, 6) \
X(FMW_MessageType_Run_GetStatus, 7) \
X(FMW_MessageType_Run_SetVelocity, 8) \
- X(FMW_MessageType_COUNT, 9)
+ X(FMW_MessageType_Emergency_Begin, 9) \
+ X(FMW_MessageType_Emergency_End, 10) \
+ X(FMW_MessageType_COUNT, 11)
// 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.