From 6fc5014a84ad016edc9df4635c78c574adcca410 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 14 Aug 2014 19:37:00 +0900 Subject: [PATCH] Copter: increase sonar timeout to 1sec Contributed by Julien Dubois. --- ArduCopter/Attitude.pde | 2 +- ArduCopter/config.h | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index a496cc49c8..4daefa0fa0 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -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; diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 7293119e8a..eae4043fc8 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -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 //