mirror of https://github.com/ArduPilot/ardupilot
Sub: call AC_PosControl::write_log in modes with only vertical control like AltHold
This commit is contained in:
parent
9a363e9e15
commit
05d74ba50d
|
@ -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)) {
|
||||
|
|
Loading…
Reference in New Issue