mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: added GPYW logging for GPS yaw
this makes it much easier to debug GPS yaw issues, by logging the raw data even if the yaw is rejected
This commit is contained in:
parent
c453ff1ce2
commit
29f1c31854
@ -470,7 +470,9 @@ bool AP_GPS_NMEA::_term_complete()
|
||||
const float dist = state.location.get_distance_NED(slave).length();
|
||||
const float bearing = degrees(state.location.get_bearing(slave));
|
||||
const float alt_diff = (state.location.alt - slave.alt)*0.01;
|
||||
calculate_moving_base_yaw(bearing, dist, alt_diff);
|
||||
if (calculate_moving_base_yaw(bearing, dist, alt_diff)) {
|
||||
_last_yaw_ms = now;
|
||||
}
|
||||
state.gps_yaw_configured = true;
|
||||
#endif
|
||||
} else {
|
||||
|
@ -425,13 +425,29 @@ bool AP_GPS_Backend::calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state,
|
||||
interim_state.have_gps_yaw = true;
|
||||
interim_state.gps_yaw_time_ms = AP_HAL::millis();
|
||||
}
|
||||
goto good_yaw;
|
||||
}
|
||||
|
||||
return true;
|
||||
|
||||
bad_yaw:
|
||||
interim_state.have_gps_yaw = false;
|
||||
return false;
|
||||
|
||||
good_yaw:
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// this log message helps diagnose GPS yaw issues
|
||||
AP::logger().WriteStreaming("GPYW", "TimeUS,Id,RHD,RDist,RDown,OK",
|
||||
"s#dmm-",
|
||||
"F-----",
|
||||
"QBfffB",
|
||||
AP_HAL::micros64(),
|
||||
state.instance,
|
||||
reported_heading_deg,
|
||||
reported_distance,
|
||||
reported_D,
|
||||
interim_state.have_gps_yaw);
|
||||
#endif
|
||||
|
||||
return interim_state.have_gps_yaw;
|
||||
}
|
||||
#endif // GPS_MOVING_BASELINE
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user