Browse Source

ACM: Fixed Baro rate patch to work with Sonar and added simple filter

master
Jason Short 13 years ago
parent
commit
b17eb7f768
  1. 12
      ArduCopter/ArduCopter.pde

12
ArduCopter/ArduCopter.pde

@ -2113,10 +2113,18 @@ static void update_altitude()
baro_alt = read_barometer(); baro_alt = read_barometer();
// calc the vertical accel rate // calc the vertical accel rate
/*
// 2.6 way
int temp = (baro_alt - old_baro_alt) * 10; int temp = (baro_alt - old_baro_alt) * 10;
baro_rate = (temp + baro_rate) >> 1; baro_rate = (temp + baro_rate) >> 1;
baro_rate = constrain(baro_rate, -300, 300); baro_rate = constrain(baro_rate, -300, 300);
old_baro_alt = baro_alt; 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 #endif
// Note: sonar_alt is calculated in a faster loop and filtered with a mode filter // 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; current_loc.alt = baro_alt;
// dont blend, go straight baro // dont blend, go straight baro
//climb_rate_actual = baro_rate; climb_rate_actual = baro_rate;
// Tridge's cool Baro patch
climb_rate_actual = barometer.get_climb_rate() * 100;
} }
}else{ }else{

Loading…
Cancel
Save