From ba38b0234fcf633ddee71db5e0b3bdc31f3667ed Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 27 Apr 2016 21:20:03 +0900 Subject: [PATCH] Copter: use rangefinder class's valid_range_count Also read_rangefinder directly updates rangefinder_alt variable instead of returning distance No functional change --- ArduCopter/ArduCopter.cpp | 2 +- ArduCopter/Copter.h | 2 +- ArduCopter/sensors.cpp | 20 +++++++------------- 3 files changed, 9 insertions(+), 15 deletions(-) diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index 18bbc4da0d..a37af9ec29 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -614,7 +614,7 @@ void Copter::update_altitude() read_barometer(); // read in rangefinder altitude - rangefinder_alt = read_rangefinder(); + read_rangefinder(); // write altitude info to dataflash logs if (should_log(MASK_LOG_CTUN)) { diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index d064038934..5e96a91e16 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -946,7 +946,7 @@ private: void init_barometer(bool full_calibration); void read_barometer(void); void init_rangefinder(void); - int16_t read_rangefinder(void); + void read_rangefinder(void); bool rangefinder_alt_ok(); void init_compass(); void init_optflow(); diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index d782153ebf..4bff7ff16a 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -34,7 +34,7 @@ void Copter::init_rangefinder(void) } // return rangefinder altitude in centimeters -int16_t Copter::read_rangefinder(void) +void Copter::read_rangefinder(void) { #if RANGEFINDER_ENABLED == ENABLED rangefinder.update(); @@ -42,20 +42,13 @@ int16_t Copter::read_rangefinder(void) // exit immediately if rangefinder is disabled if (rangefinder.status() != RangeFinder::RangeFinder_Good) { rangefinder_alt_health = 0; - return 0; + return; } + rangefinder_alt_health = rangefinder.range_valid_count(); + int16_t temp_alt = rangefinder.distance_cm(); - if (temp_alt >= rangefinder.min_distance_cm() && - temp_alt <= rangefinder.max_distance_cm() * RANGEFINDER_RELIABLE_DISTANCE_PCT) { - if (rangefinder_alt_health < RANGEFINDER_HEALTH_MAX) { - rangefinder_alt_health++; - } - }else{ - rangefinder_alt_health = 0; - } - #if RANGEFINDER_TILT_CORRECTION == 1 // correct alt for angle of the rangefinder float temp = ahrs.cos_pitch() * ahrs.cos_roll(); @@ -63,9 +56,10 @@ int16_t Copter::read_rangefinder(void) temp_alt = (float)temp_alt * temp; #endif - return temp_alt; + rangefinder_alt = temp_alt; #else - return 0; + rangefinder_alt_health = 0; + rangefinder_alt = 0; #endif }