ArduCopter: log GPS primary change event in GPS library
This commit is contained in:
parent
c9699d7ce4
commit
14e5c99b0c
@ -405,7 +405,6 @@ private:
|
|||||||
struct {
|
struct {
|
||||||
uint8_t baro : 1; // true if baro is healthy
|
uint8_t baro : 1; // true if baro is healthy
|
||||||
uint8_t compass : 1; // true if compass is healthy
|
uint8_t compass : 1; // true if compass is healthy
|
||||||
uint8_t primary_gps : 2; // primary gps index
|
|
||||||
} sensor_health;
|
} sensor_health;
|
||||||
|
|
||||||
// Motor Output
|
// Motor Output
|
||||||
|
@ -265,12 +265,6 @@ void Copter::Log_Sensor_Health()
|
|||||||
sensor_health.compass = compass.healthy();
|
sensor_health.compass = compass.healthy();
|
||||||
AP::logger().Write_Error(LogErrorSubsystem::COMPASS, (sensor_health.compass ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY));
|
AP::logger().Write_Error(LogErrorSubsystem::COMPASS, (sensor_health.compass ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY));
|
||||||
}
|
}
|
||||||
|
|
||||||
// check primary GPS
|
|
||||||
if (sensor_health.primary_gps != gps.primary_sensor()) {
|
|
||||||
sensor_health.primary_gps = gps.primary_sensor();
|
|
||||||
AP::logger().Write_Event(LogEvent::GPS_PRIMARY_CHANGED);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
struct PACKED log_SysIdD {
|
struct PACKED log_SysIdD {
|
||||||
|
Loading…
Reference in New Issue
Block a user