mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
moved to 200hz update
Zccel Z updates from Aurelio in attitude.pde lowered baro_alt sanity check moved user hooks to the medium 10hz loop.
This commit is contained in:
parent
d1431f1070
commit
a37fadbedb
@ -508,7 +508,7 @@ void loop()
|
|||||||
long timer = micros();
|
long timer = micros();
|
||||||
// We want this to execute fast
|
// We want this to execute fast
|
||||||
// ----------------------------
|
// ----------------------------
|
||||||
if ((timer - fast_loopTimer) >= 4000) {
|
if ((timer - fast_loopTimer) >= 5000) {
|
||||||
//PORTK |= B00010000;
|
//PORTK |= B00010000;
|
||||||
G_Dt = (float)(timer - fast_loopTimer) / 1000000.f; // used by PI Loops
|
G_Dt = (float)(timer - fast_loopTimer) / 1000000.f; // used by PI Loops
|
||||||
fast_loopTimer = timer;
|
fast_loopTimer = timer;
|
||||||
@ -734,6 +734,11 @@ static void medium_loop()
|
|||||||
barometer.Read();
|
barometer.Read();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// agmatthews - USERHOOKS
|
||||||
|
#ifdef USERHOOK_MEDIUMLOOP
|
||||||
|
USERHOOK_MEDIUMLOOP
|
||||||
|
#endif
|
||||||
|
|
||||||
slow_loop();
|
slow_loop();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -743,11 +748,6 @@ static void medium_loop()
|
|||||||
medium_loopCounter = 0;
|
medium_loopCounter = 0;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
// agmatthews - USERHOOKS
|
|
||||||
#ifdef USERHOOK_MEDIUMLOOP
|
|
||||||
USERHOOK_MEDIUMLOOP
|
|
||||||
#endif
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// stuff that happens at 50 hz
|
// stuff that happens at 50 hz
|
||||||
@ -1228,7 +1228,7 @@ static void update_altitude()
|
|||||||
sonar_rate = (sonar_alt - old_sonar_alt) * 10;
|
sonar_rate = (sonar_alt - old_sonar_alt) * 10;
|
||||||
old_sonar_alt = sonar_alt;
|
old_sonar_alt = sonar_alt;
|
||||||
|
|
||||||
if(baro_alt < 1000){
|
if(baro_alt < 700){
|
||||||
|
|
||||||
#if SONAR_TILT_CORRECTION == 1
|
#if SONAR_TILT_CORRECTION == 1
|
||||||
// correct alt for angle of the sonar
|
// correct alt for angle of the sonar
|
||||||
|
Loading…
Reference in New Issue
Block a user