mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: use ARRAY_SIZE macro
This commit is contained in:
parent
4a595bd797
commit
9d59b43920
|
@ -206,7 +206,7 @@ AP_GPS::detect_instance(uint8_t instance)
|
|||
if (now - dstate->last_baud_change_ms > 1200) {
|
||||
// try the next baud rate
|
||||
dstate->last_baud++;
|
||||
if (dstate->last_baud == sizeof(_baudrates) / sizeof(_baudrates[0])) {
|
||||
if (dstate->last_baud == ARRAY_SIZE(_baudrates)) {
|
||||
dstate->last_baud = 0;
|
||||
}
|
||||
uint32_t baudrate = pgm_read_dword(&_baudrates[dstate->last_baud]);
|
||||
|
|
|
@ -451,7 +451,7 @@ AP_GPS_SBP::logging_write_headers(void)
|
|||
{
|
||||
if (!logging_started) {
|
||||
logging_started = true;
|
||||
gps._DataFlash->AddLogFormats(sbp_log_structures, sizeof(sbp_log_structures) / sizeof(LogStructure));
|
||||
gps._DataFlash->AddLogFormats(sbp_log_structures, ARRAY_SIZE(sbp_log_structures));
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue