Copter: call AC_PosControl::write_log in modes with only vertical control like AltHold

This commit is contained in:
Randy Mackay 2021-05-25 13:36:58 +09:00 committed by Andrew Tridgell
parent d9c68031fa
commit 9a363e9e15
1 changed files with 1 additions and 1 deletions

View File

@ -419,7 +419,7 @@ void Copter::ten_hz_logging_loop()
if (should_log(MASK_LOG_RCOUT)) {
logger.Write_RCOUT();
}
if (should_log(MASK_LOG_NTUN) && (flightmode->requires_GPS() || landing_with_GPS())) {
if (should_log(MASK_LOG_NTUN) && (flightmode->requires_GPS() || landing_with_GPS() || !flightmode->has_manual_throttle())) {
pos_control->write_log();
}
if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {