GCS_MAVLink: increase statustext queue size to 7 on low-mem boards

... and SITL....

Copter currently spits out so many messages on a banner-send (e.g what
we do when parameters are fetched) that it puses the first sent message
straight out of the queue before it gets a chance to be sent from the
queue.
This commit is contained in:
Peter Barker 2021-05-25 16:54:21 +10:00 committed by Peter Barker
parent e7ca9d8e83
commit 09f4961a63
2 changed files with 9 additions and 2 deletions

View File

@ -12,6 +12,12 @@
extern const AP_HAL::HAL& hal; 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<GCS::statustext_t, 58> _assert_statustext_t_size;
#endif
void GCS::get_sensor_status_flags(uint32_t &present, void GCS::get_sensor_status_flags(uint32_t &present,
uint32_t &enabled, uint32_t &enabled,
uint32_t &health) uint32_t &health)

View File

@ -1035,12 +1035,13 @@ private:
void service_statustext(void); void service_statustext(void);
#if HAL_MEM_CLASS <= HAL_MEM_CLASS_192 || CONFIG_HAL_BOARD == HAL_BOARD_SITL #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 #else
static const uint8_t _status_capacity = 30; static const uint8_t _status_capacity = 30;
#endif #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}; StatusTextQueue _statustext_queue{_status_capacity};
// true if we have already allocated protocol objects: // true if we have already allocated protocol objects: