AP_GPS: log ublox sw and hw versions on dataflash log start

This burns 41 bytes of RAM for each u-Blox GPS.
This commit is contained in:
Peter Barker 2016-08-02 15:48:16 +10:00 committed by Francisco Ferreira
parent b7baca8d43
commit 1ba59b446c
2 changed files with 18 additions and 2 deletions

View File

@ -810,11 +810,13 @@ AP_GPS_UBLOX::_parse_gps(void)
break; break;
case MSG_MON_VER: case MSG_MON_VER:
_have_version = true; _have_version = true;
strncpy(_version.hwVersion, _buffer.mon_ver.hwVersion, sizeof(_version.hwVersion));
strncpy(_version.swVersion, _buffer.mon_ver.swVersion, sizeof(_version.swVersion));
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO,
"u-blox %d HW: %s SW: %s", "u-blox %d HW: %s SW: %s",
state.instance + 1, state.instance + 1,
_buffer.mon_ver.hwVersion, _version.hwVersion,
_buffer.mon_ver.swVersion); _version.swVersion);
break; break;
default: default:
unexpected_message(); unexpected_message();
@ -1319,3 +1321,15 @@ float AP_GPS_UBLOX::get_lag(void) const
break; break;
}; };
} }
void AP_GPS_UBLOX::Write_DataFlash_Log_Startup_messages() const
{
AP_GPS_Backend::Write_DataFlash_Log_Startup_messages();
if (_have_version) {
gps._DataFlash->Log_Write_MessageF("u-blox %d HW: %s SW: %s",
state.instance+1,
_version.hwVersion,
_version.swVersion);
}
}

View File

@ -114,6 +114,7 @@ public:
} }
void broadcast_configuration_failure_reason(void) const override; void broadcast_configuration_failure_reason(void) const override;
void Write_DataFlash_Log_Startup_messages() const override;
// return velocity lag // return velocity lag
float get_lag(void) const override; float get_lag(void) const override;
@ -522,6 +523,7 @@ private:
uint8_t _next_message; uint8_t _next_message;
uint8_t _ublox_port; uint8_t _ublox_port;
bool _have_version; bool _have_version;
struct ubx_mon_ver _version;
uint32_t _unconfigured_messages; uint32_t _unconfigured_messages;
uint8_t _hardware_generation; uint8_t _hardware_generation;