mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-10 18:03:56 -04:00
AP_GPS: log received data
Also log a set of flag values if a driver is deleted
This commit is contained in:
parent
8648db06b4
commit
643e7e039a
@ -585,6 +585,22 @@ AP_GPS::GPS_Status AP_GPS::highest_supported_status(uint8_t instance) const
|
|||||||
return AP_GPS::GPS_OK_FIX_3D;
|
return AP_GPS::GPS_OK_FIX_3D;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool AP_GPS::should_df_log() const
|
||||||
|
{
|
||||||
|
DataFlash_Class *instance = DataFlash_Class::instance();
|
||||||
|
if (instance == nullptr) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (_log_gps_bit == (uint32_t)-1) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (!instance->should_log(_log_gps_bit)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
update one GPS instance. This should be called at 10Hz or greater
|
update one GPS instance. This should be called at 10Hz or greater
|
||||||
*/
|
*/
|
||||||
@ -624,6 +640,7 @@ void AP_GPS::update_instance(uint8_t instance)
|
|||||||
// if we did not get a message, and the idle timer of 2 seconds
|
// if we did not get a message, and the idle timer of 2 seconds
|
||||||
// has expired, re-initialise the GPS. This will cause GPS
|
// has expired, re-initialise the GPS. This will cause GPS
|
||||||
// detection to run again
|
// detection to run again
|
||||||
|
bool data_should_be_logged = false;
|
||||||
if (!result) {
|
if (!result) {
|
||||||
if (tnow - timing[instance].last_message_time_ms > GPS_TIMEOUT_MS) {
|
if (tnow - timing[instance].last_message_time_ms > GPS_TIMEOUT_MS) {
|
||||||
memset(&state[instance], 0, sizeof(state[instance]));
|
memset(&state[instance], 0, sizeof(state[instance]));
|
||||||
@ -642,6 +659,9 @@ void AP_GPS::update_instance(uint8_t instance)
|
|||||||
drivers[instance] = nullptr;
|
drivers[instance] = nullptr;
|
||||||
state[instance].status = NO_GPS;
|
state[instance].status = NO_GPS;
|
||||||
}
|
}
|
||||||
|
// log this data as a "flag" that the GPS is no longer
|
||||||
|
// valid (see PR#8144)
|
||||||
|
data_should_be_logged = true;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// delta will only be correct after parsing two messages
|
// delta will only be correct after parsing two messages
|
||||||
@ -650,6 +670,14 @@ void AP_GPS::update_instance(uint8_t instance)
|
|||||||
if (state[instance].status >= GPS_OK_FIX_2D) {
|
if (state[instance].status >= GPS_OK_FIX_2D) {
|
||||||
timing[instance].last_fix_time_ms = tnow;
|
timing[instance].last_fix_time_ms = tnow;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
data_should_be_logged = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (data_should_be_logged &&
|
||||||
|
should_df_log() &&
|
||||||
|
!AP::ahrs().have_ekf_logging()) {
|
||||||
|
DataFlash_Class::instance()->Log_Write_GPS(instance);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -551,6 +551,8 @@ private:
|
|||||||
// calculate the blended state
|
// calculate the blended state
|
||||||
void calc_blended_state(void);
|
void calc_blended_state(void);
|
||||||
|
|
||||||
|
bool should_df_log() const;
|
||||||
|
|
||||||
// Auto configure types
|
// Auto configure types
|
||||||
enum GPS_AUTO_CONFIG {
|
enum GPS_AUTO_CONFIG {
|
||||||
GPS_AUTO_CONFIG_DISABLE = 0,
|
GPS_AUTO_CONFIG_DISABLE = 0,
|
||||||
|
@ -172,17 +172,7 @@ void AP_GPS_Backend::Write_DataFlash_Log_Startup_messages() const
|
|||||||
|
|
||||||
bool AP_GPS_Backend::should_df_log() const
|
bool AP_GPS_Backend::should_df_log() const
|
||||||
{
|
{
|
||||||
DataFlash_Class *instance = DataFlash_Class::instance();
|
return gps.should_df_log();
|
||||||
if (instance == nullptr) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
if (gps._log_gps_bit == (uint32_t)-1) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
if (!instance->should_log(gps._log_gps_bit)) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user