AP_GPS: prevent writing GPS log headings multiple times

This commit is contained in:
Andrew Tridgell 2014-04-20 21:44:14 +10:00
parent b9845047f4
commit 5a7afbf2cd
4 changed files with 6 additions and 4 deletions

View File

@ -47,6 +47,7 @@ extern const AP_HAL::HAL& hal;
#define SBP_HW_LOGGING 0 #define SBP_HW_LOGGING 0
#endif #endif
bool AP_GPS_SBP::logging_started = false;
AP_GPS_SBP::AP_GPS_SBP(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : AP_GPS_SBP::AP_GPS_SBP(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
AP_GPS_Backend(_gps, _state, _port), AP_GPS_Backend(_gps, _state, _port),
@ -57,8 +58,7 @@ AP_GPS_SBP::AP_GPS_SBP(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriv
dops_msg_counter(0), dops_msg_counter(0),
baseline_msg_counter(0), baseline_msg_counter(0),
crc_error_counter(0), crc_error_counter(0),
last_healthcheck_millis(0), last_healthcheck_millis(0)
logging_started(false)
{ {
Debug("Initializing SBP Driver"); Debug("Initializing SBP Driver");

View File

@ -216,7 +216,7 @@ private:
// ************************************************************************ // ************************************************************************
// have we written the logging headers to DataFlash? // have we written the logging headers to DataFlash?
bool logging_started:1; static bool logging_started;
void logging_write_headers(); void logging_write_headers();
void logging_log_health(float pos_msg_hz, float vel_msg_hz, float dops_msg_hz, float baseline_msg_hz, float crc_error_hz); void logging_log_health(float pos_msg_hz, float vel_msg_hz, float dops_msg_hz, float baseline_msg_hz, float crc_error_hz);

View File

@ -44,6 +44,8 @@ extern const AP_HAL::HAL& hal;
#define UBLOX_HW_LOGGING 0 #define UBLOX_HW_LOGGING 0
#endif #endif
bool AP_GPS_UBLOX::logging_started = false;
AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
AP_GPS_Backend(_gps, _state, _port), AP_GPS_Backend(_gps, _state, _port),
_step(0), _step(0),

View File

@ -254,7 +254,7 @@ private:
bool need_rate_update:1; bool need_rate_update:1;
// have we written the logging headers to DataFlash? // have we written the logging headers to DataFlash?
bool logging_started:1; static bool logging_started;
uint8_t _disable_counter; uint8_t _disable_counter;