mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
ACM: Fixed Baro rate patch to work with Sonar and added simple filter
This commit is contained in:
parent
b6f45bb188
commit
9cf36c553c
@ -2113,10 +2113,18 @@ static void update_altitude()
|
||||
baro_alt = read_barometer();
|
||||
|
||||
// calc the vertical accel rate
|
||||
/*
|
||||
// 2.6 way
|
||||
int temp = (baro_alt - old_baro_alt) * 10;
|
||||
baro_rate = (temp + baro_rate) >> 1;
|
||||
baro_rate = constrain(baro_rate, -300, 300);
|
||||
old_baro_alt = baro_alt;
|
||||
*/
|
||||
|
||||
// Using Tridge's new clamb rate calc
|
||||
int temp = barometer.get_climb_rate() * 100;
|
||||
baro_rate = (temp + baro_rate) >> 1;
|
||||
baro_rate = constrain(baro_rate, -300, 300);
|
||||
#endif
|
||||
|
||||
// Note: sonar_alt is calculated in a faster loop and filtered with a mode filter
|
||||
@ -2160,9 +2168,7 @@ static void update_altitude()
|
||||
current_loc.alt = baro_alt;
|
||||
// dont blend, go straight baro
|
||||
|
||||
//climb_rate_actual = baro_rate;
|
||||
// Tridge's cool Baro patch
|
||||
climb_rate_actual = barometer.get_climb_rate() * 100;
|
||||
climb_rate_actual = baro_rate;
|
||||
}
|
||||
|
||||
}else{
|
||||
|
Loading…
Reference in New Issue
Block a user