From acb4538073cb3988b7dcda265c20626f0341f611 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 15 Sep 2011 13:06:04 +1000 Subject: [PATCH] RangeFinder: use new ADC interface the new interface gives values 8 times as large as previously --- libraries/AP_RangeFinder/RangeFinder.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/libraries/AP_RangeFinder/RangeFinder.cpp b/libraries/AP_RangeFinder/RangeFinder.cpp index 4621a90be8..5a53183c17 100644 --- a/libraries/AP_RangeFinder/RangeFinder.cpp +++ b/libraries/AP_RangeFinder/RangeFinder.cpp @@ -37,8 +37,9 @@ void RangeFinder::set_orientation(int x, int y, int z) int RangeFinder::read() { // read from the analog port or pitot tube - if( _ap_adc != NULL ){ - raw_value = _ap_adc->Ch_raw(AP_RANGEFINDER_PITOT_TUBE_ADC_CHANNEL) >> 2; // values from ADC are twice as big as you'd expect + if( _ap_adc != NULL ){ + // values from ADC are twice as big as you'd expect + raw_value = _ap_adc->Ch(AP_RANGEFINDER_PITOT_TUBE_ADC_CHANNEL) >> 2; }else{ // read raw sensor value and convert to distance raw_value = analogRead(_analogPort);