AP_GPS: fix dereference-of-nullptr warning from scan-build

This is kind-of a false positive as this in practise could never be
nullptr.
This commit is contained in:
Peter Barker 2020-03-28 11:21:07 +11:00 committed by Andrew Tridgell
parent 18baf18041
commit 2b08af69bc
2 changed files with 10 additions and 8 deletions

View File

@ -51,6 +51,15 @@ AP_GPS_NOVA::AP_GPS_NOVA(AP_GPS &_gps, AP_GPS::GPS_State &_state,
port->write((const uint8_t*)init_str1, strlen(init_str1));
}
const char* const AP_GPS_NOVA::_initialisation_blob[6] {
"\r\n\r\nunlogall\r\n", // cleanup enviroment
"log bestposb ontime 0.2 0 nohold\r\n", // get bestpos
"log bestvelb ontime 0.2 0 nohold\r\n", // get bestvel
"log psrdopb onchanged\r\n", // tersus
"log psrdopb ontime 0.2\r\n", // comnav
"log psrdopb\r\n" // poll message, as dop only changes when a sat is dropped/added to the visible list
};
// Process all bytes available from the stream
//
bool

View File

@ -56,14 +56,7 @@ private:
uint8_t _init_blob_index = 0;
uint32_t _init_blob_time = 0;
const char* _initialisation_blob[6] = {
"\r\n\r\nunlogall\r\n", // cleanup enviroment
"log bestposb ontime 0.2 0 nohold\r\n", // get bestpos
"log bestvelb ontime 0.2 0 nohold\r\n", // get bestvel
"log psrdopb onchanged\r\n", // tersus
"log psrdopb ontime 0.2\r\n", // comnav
"log psrdopb\r\n" // poll message, as dop only changes when a sat is dropped/added to the visible list
};
static const char* const _initialisation_blob[6];
uint32_t crc_error_counter = 0;
uint32_t last_injected_data_ms = 0;