removed duplicate filter from ADC based input

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2562 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-06-16 16:30:37 +00:00
parent ea728060f3
commit e2d5f7bf82
2 changed files with 51 additions and 40 deletions

View File

@ -1,6 +1,6 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 3; indent-tabs-mode: t -*-
/*
AP_RangeFinder.cpp - Arduino Library for Sharpe GP2Y0A02YK0F
AP_RangeFinder.cpp - Arduino Library for Sharpe GP2Y0A02YK0F
infrared proximity sensor
Code by Jose Julio and Randy Mackay. DIYDrones.com
@ -29,34 +29,33 @@ void RangeFinder::init(int analogPort, AP_ADC *ap_adc)
{
// local variables
int i;
// store the analog port to be used
_analogPort = analogPort;
// set the given analog port to an input
if( analogPort != AP_RANGEFINDER_PITOT_TUBE )
{
if( analogPort != AP_RANGEFINDER_PITOT_TUBE ){
pinMode(analogPort, INPUT);
}else{
_num_averages = 0; // turn off averaging for pitot tube because AP_ADC does this for us
}
// capture the AP_ADC object if passed in
if( ap_adc != NULL )
_ap_adc = ap_adc;
_ap_adc = ap_adc;
// make first call to read to get initial distance
read();
// initialise history
for( i=0; i<AP_RANGEFINDER_NUM_AVERAGES; i++ )
_history[i] = distance;
for(i = 0; i < AP_RANGEFINDER_NUM_AVERAGES; i++)
_history[i] = distance;
}
void RangeFinder::set_orientation(int x, int y, int z)
{
orientation_x = x;
orientation_y = y;
orientation_x = x;
orientation_y = y;
orientation_z = z;
}
@ -65,36 +64,48 @@ int RangeFinder::read()
{
// local variables
int temp_dist;
int total = 0;
int total = 0;
int i;
// read from the analog port or pitot tube
if( _analogPort == AP_RANGEFINDER_PITOT_TUBE ) {
if( _ap_adc != NULL )
raw_value = _ap_adc->Ch(AP_RANGEFINDER_PITOT_TUBE_ADC_CHANNEL) >> 2; // values from ADC are twice as big as you'd expect
else
raw_value = 0;
if(_analogPort == AP_RANGEFINDER_PITOT_TUBE){
if(_ap_adc != NULL){
raw_value = _ap_adc->Ch(AP_RANGEFINDER_PITOT_TUBE_ADC_CHANNEL) >> 2; // values from ADC are twice as big as you'd expect
}else{
raw_value = 0;
}
// convert analog value to distance in cm (using child implementation most likely)
temp_dist = convert_raw_to_distance(raw_value);
// ensure distance is within min and max
distance = constrain(temp_dist, min_distance, max_distance);
// return distance
return distance;
}else{
// read raw sensor value and convert to distance
raw_value = analogRead(_analogPort);
// convert analog value to distance in cm (using child implementation most likely)
temp_dist = convert_raw_to_distance(raw_value);
// ensure distance is within min and max
distance = constrain(temp_dist, min_distance, max_distance);
// filter the results
if( _num_averages > 1 ){
_history_ptr = (_history_ptr + 1) % _num_averages;
_history[_history_ptr] = distance;
for(i = 0; i < _num_averages; i++ ) total += _history[i];
distance = total / _num_averages;
}
// return distance
return distance;
}
// convert analog value to distance in cm (using child implementation most likely)
temp_dist = convert_raw_to_distance(raw_value);
// ensure distance is within min and max
distance = constrain(temp_dist, min_distance, max_distance);
// filter the results
if( _num_averages > 1 )
{
_history_ptr = (_history_ptr + 1) % _num_averages;
_history[_history_ptr] = distance;
for(i=0; i<_num_averages; i++ )
total += _history[i];
distance = total / _num_averages;
}
// return distance
return distance;
}

View File

@ -36,10 +36,10 @@ class RangeFinder
int max_distance; // maximum measurable distance (in cm) - should be set in child's constructor
int min_distance; // minimum measurable distance (in cm) - should be set in child's constructor
int orientation_x, orientation_y, orientation_z;
virtual void init(int analogPort, AP_ADC *adc = (AP_ADC*)NULL);
virtual void set_orientation(int x, int y, int z);
virtual void set_filter(int num_averages) { _num_averages = num_averages; } // allows control of amount of filtering done
virtual void set_filter(int num_averages) { _num_averages = num_averages; } // allows control of amount of filtering done
virtual int convert_raw_to_distance(int _raw_value) { return _raw_value; } // function that each child class should override to convert voltage to distance
virtual int read(); // read value from sensor and return distance in cm
};