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

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

View File

@ -195,7 +195,7 @@ void Sub::ten_hz_logging_loop()
if (should_log(MASK_LOG_RCOUT)) {
logger.Write_RCOUT();
}
if (should_log(MASK_LOG_NTUN) && mode_requires_GPS(control_mode)) {
if (should_log(MASK_LOG_NTUN) && (mode_requires_GPS(control_mode) || !mode_has_manual_throttle(control_mode))) {
pos_control.write_log();
}
if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {