Browse Source

AP_Notify: remove non-required initialisation of variables

These objects are dynamically allocated, and we zero the memory
as we allocate them
mission-4.1.18
Peter Barker 8 years ago committed by Randy Mackay
parent
commit
57c0551260
  1. 3
      libraries/AP_Notify/Display.cpp
  2. 4
      libraries/AP_Notify/Display.h

3
libraries/AP_Notify/Display.cpp

@ -324,9 +324,6 @@ bool Display::init(void) @@ -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))) {

4
libraries/AP_Notify/Display.h

@ -34,8 +34,8 @@ private: @@ -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…
Cancel
Save