mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: fix duplicate IMU logging
IMU logs could be written at FULL rate and at lower rates leading to duplicates
This commit is contained in:
parent
9d81856580
commit
5644dd8620
@ -390,7 +390,7 @@ void Copter::fifty_hz_logging_loop()
|
||||
}
|
||||
|
||||
// log IMU data if we're not already logging at the higher rate
|
||||
if (should_log(MASK_LOG_IMU) && !should_log(MASK_LOG_IMU_FAST)) {
|
||||
if (should_log(MASK_LOG_IMU) && !(should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW))) {
|
||||
DataFlash.Log_Write_IMU(ins);
|
||||
}
|
||||
#endif
|
||||
@ -400,7 +400,7 @@ void Copter::fifty_hz_logging_loop()
|
||||
// should be run at the MAIN_LOOP_RATE
|
||||
void Copter::full_rate_logging_loop()
|
||||
{
|
||||
if (should_log(MASK_LOG_IMU_FAST)) {
|
||||
if (should_log(MASK_LOG_IMU_FAST) && !should_log(MASK_LOG_IMU_RAW)) {
|
||||
DataFlash.Log_Write_IMU(ins);
|
||||
DataFlash.Log_Write_IMUDT(ins);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user