Browse Source

ArduCopter: log GPS primary change event in GPS library

gps-1.3.1
Peter Barker 4 years ago committed by Peter Barker
parent
commit
14e5c99b0c
  1. 1
      ArduCopter/Copter.h
  2. 6
      ArduCopter/Log.cpp

1
ArduCopter/Copter.h

@ -405,7 +405,6 @@ private: @@ -405,7 +405,6 @@ private:
struct {
uint8_t baro : 1; // true if baro is healthy
uint8_t compass : 1; // true if compass is healthy
uint8_t primary_gps : 2; // primary gps index
} sensor_health;
// Motor Output

6
ArduCopter/Log.cpp

@ -265,12 +265,6 @@ void Copter::Log_Sensor_Health() @@ -265,12 +265,6 @@ void Copter::Log_Sensor_Health()
sensor_health.compass = compass.healthy();
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 {

Loading…
Cancel
Save