mirror of https://github.com/ArduPilot/ardupilot
Copter: Reenable PID logging in SystemID mode
This commit is contained in:
parent
5b0a2334e3
commit
d67e67965f
|
@ -519,7 +519,7 @@ void Copter::ten_hz_logging_loop()
|
||||||
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
|
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
|
||||||
Log_Write_Attitude();
|
Log_Write_Attitude();
|
||||||
}
|
}
|
||||||
if (!should_log(MASK_LOG_ATTITUDE_FAST)) {
|
if (!should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
|
||||||
// log at 10Hz if PIDS bitmask is selected, even if no ATT bitmask is selected; logs at looprate if ATT_FAST and PIDS bitmask set
|
// log at 10Hz if PIDS bitmask is selected, even if no ATT bitmask is selected; logs at looprate if ATT_FAST and PIDS bitmask set
|
||||||
Log_Write_PIDS();
|
Log_Write_PIDS();
|
||||||
}
|
}
|
||||||
|
|
|
@ -299,6 +299,7 @@ void ModeSystemId::log_data() const
|
||||||
|
|
||||||
// Full rate logging of attitude, rate and pid loops
|
// Full rate logging of attitude, rate and pid loops
|
||||||
copter.Log_Write_Attitude();
|
copter.Log_Write_Attitude();
|
||||||
|
copter.Log_Write_PIDS();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue