mirror of https://github.com/ArduPilot/ardupilot
AP_Notify: remove non-required initialisation of variables
These objects are dynamically allocated, and we zero the memory as we allocate them
This commit is contained in:
parent
49b8d8319c
commit
4adf8a83a6
|
@ -324,9 +324,6 @@ bool Display::init(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
_mstartpos = 0; // ticker shift position
|
||||
_movedelay = 4; // ticker delay before shifting after new message displayed
|
||||
|
||||
// initialise driver
|
||||
for(uint8_t i=0; i<8 && _driver == nullptr; i++) {
|
||||
if (! (I2C_BUS_PROBE_MASK & (1<<i))) {
|
||||
|
|
|
@ -34,8 +34,8 @@ private:
|
|||
|
||||
bool _healthy;
|
||||
|
||||
uint8_t _mstartpos;
|
||||
uint8_t _movedelay;
|
||||
uint8_t _mstartpos; // ticker shift position
|
||||
uint8_t _movedelay; // ticker delay before shifting after new message displayed
|
||||
uint8_t _screenpage;
|
||||
|
||||
// stop showing text in display after this many millis:
|
||||
|
|
Loading…
Reference in New Issue