diff --git a/libraries/GCS_MAVLink/GCS.cpp b/libraries/GCS_MAVLink/GCS.cpp index 5a2084a84c..71ef48b456 100644 --- a/libraries/GCS_MAVLink/GCS.cpp +++ b/libraries/GCS_MAVLink/GCS.cpp @@ -12,6 +12,12 @@ extern const AP_HAL::HAL& hal; +// if this assert fails then fix it and the comment in GCS.h where +// _statustext_queue is declared +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +assert_storage_size _assert_statustext_t_size; +#endif + void GCS::get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 7af291627a..9a0232ce97 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -1035,12 +1035,13 @@ private: void service_statustext(void); #if HAL_MEM_CLASS <= HAL_MEM_CLASS_192 || CONFIG_HAL_BOARD == HAL_BOARD_SITL - static const uint8_t _status_capacity = 5; + static const uint8_t _status_capacity = 7; #else static const uint8_t _status_capacity = 30; #endif - // queue of outgoing statustext messages + // queue of outgoing statustext messages. Each entry consumes 58 + // bytes of RAM on stm32 StatusTextQueue _statustext_queue{_status_capacity}; // true if we have already allocated protocol objects: