mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
ACM: change DCM loop to 100Hz
On my APM2 quad this seems to give better results
This commit is contained in:
parent
045b49c4c4
commit
69c29d35ce
@ -856,7 +856,7 @@ void loop()
|
||||
|
||||
// We want this to execute fast
|
||||
// ----------------------------
|
||||
if ((timer - fast_loopTimer) >= 4000 && imu.new_data_available()) {
|
||||
if ((timer - fast_loopTimer) >= 10000 && imu.new_data_available()) {
|
||||
//Log_Write_Data(13, (int32_t)(timer - fast_loopTimer));
|
||||
|
||||
//PORTK |= B00010000;
|
||||
|
Loading…
Reference in New Issue
Block a user