Copter: increase sonar timeout to 1sec

Contributed by Julien Dubois.
This commit is contained in:
Randy Mackay 2014-08-14 19:37:00 +09:00
parent fd5dee96e4
commit 6fc5014a84
2 changed files with 5 additions and 1 deletions

View File

@ -234,7 +234,7 @@ static float get_throttle_surface_tracking(int16_t target_rate, float current_al
uint32_t now = millis();
// reset target altitude if this controller has just been engaged
if( now - last_call_ms > 200 ) {
if (now - last_call_ms > SONAR_TIMEOUT_MS) {
target_sonar_alt = sonar_alt + current_alt_target - current_loc.alt;
}
last_call_ms = now;

View File

@ -199,6 +199,10 @@
# define THR_SURFACE_TRACKING_VELZ_MAX 150 // max vertical speed change while surface tracking with sonar
#endif
#ifndef SONAR_TIMEOUT_MS
# define SONAR_TIMEOUT_MS 1000 // desired sonar alt will reset to current sonar alt after this many milliseconds without a good sonar alt
#endif
//////////////////////////////////////////////////////////////////////////////
// Channel 7 and 8 default options
//