mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_ICEngine: fixed RPM filter rate and plane.G_Dt
AP_ICEngine runs at 10Hz, so we need to use 10 for the filter. As this runs in a constructor it also caused memoisation of the wrong AP_Scheduler _loop_period_s which resulted in plane.G_Dt always being 1/50, which is a much more serious issue this is a temporary fix, we need a better one soon
This commit is contained in:
parent
b59a2143ae
commit
0731b5cfa0
@ -168,7 +168,8 @@ AP_ICEngine::AP_ICEngine(const AP_RPM &_rpm) :
|
|||||||
}
|
}
|
||||||
_singleton = this;
|
_singleton = this;
|
||||||
|
|
||||||
_rpm_filter.set_cutoff_frequency(1 / AP::scheduler().get_loop_period_s(), 0.5f);
|
// ICEngine runs at 10Hz
|
||||||
|
_rpm_filter.set_cutoff_frequency(10, 0.5f);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user