AP_FrSky_Telem: Don't statically allocate the statustext_queue

This saves 280 bytes of RAM
This commit is contained in:
Michael du Breuil 2019-06-18 00:39:56 -07:00 committed by Andrew Tridgell
parent f955a4e4d5
commit 67898d7320
2 changed files with 8 additions and 4 deletions

View File

@ -33,7 +33,10 @@
extern const AP_HAL::HAL& hal;
ObjectArray<mavlink_statustext_t> AP_Frsky_Telem::_statustext_queue(FRSKY_TELEM_PAYLOAD_STATUS_CAPACITY);
AP_Frsky_Telem::AP_Frsky_Telem(void) :
_statustext_queue(FRSKY_TELEM_PAYLOAD_STATUS_CAPACITY)
{
}
/*
* init - perform required initialisation

View File

@ -112,7 +112,7 @@ for FrSky SPort Passthrough
class AP_Frsky_Telem {
public:
AP_Frsky_Telem() {}
AP_Frsky_Telem();
/* Do not allow copies */
AP_Frsky_Telem(const AP_Frsky_Telem &other) = delete;
@ -130,8 +130,6 @@ public:
// functioning correctly
uint32_t sensor_status_flags() const;
static ObjectArray<mavlink_statustext_t> _statustext_queue;
private:
AP_HAL::UARTDriver *_port; // UART used to send data to FrSky receiver
AP_SerialManager::SerialProtocol _protocol; // protocol used - detected using SerialManager's SERIAL#_PROTOCOL parameter
@ -141,6 +139,9 @@ private:
uint32_t check_sensor_status_timer;
uint32_t check_ekf_status_timer;
uint8_t _paramID;
ObjectArray<mavlink_statustext_t> _statustext_queue;
struct
{