Added a slew rate limit

reworked filter, same results, just wanted to get rid of modulus.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2900 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-07-17 19:05:18 +00:00
parent 6b0c938176
commit a1733ee901
1 changed files with 43 additions and 70 deletions

View File

@ -16,6 +16,7 @@
#include "WConstants.h"
#include "RangeFinder.h"
// Constructor /////////////////////////////////////////////////////////////////
RangeFinder::RangeFinder() :
_ap_adc(NULL),
@ -65,88 +66,60 @@ int RangeFinder::read()
// local variables
int temp_dist;
int total = 0;
int i;
// read from the analog port or pitot tube
if( _analogPort == AP_RANGEFINDER_PITOT_TUBE ) {
if( _ap_adc != NULL )
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;
}else{
raw_value = 0;
}
}else{
// read raw sensor value and convert to distance
raw_value = analogRead(_analogPort);
// 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);
raw_value = convert_raw_to_distance(raw_value);
// ensure distance is within min and max
distance = constrain(temp_dist, min_distance, max_distance);
raw_value = constrain(raw_value, 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;
}
//distance = raw_value;
// slew rate
if(raw_value > distance){
temp_dist = min(distance + 10, raw_value);
}else{
temp_dist = max(distance - 10, raw_value);
}
if(_num_averages > 0){
// filter the results
// ------------------
// add to filter
_history[_history_ptr] = temp_dist;
// increment our filter
_history_ptr++;
// loop our filter
if(_history_ptr == AP_RANGEFINDER_NUM_AVERAGES)
_history_ptr = 0;
// sum our filter
for(uint8_t i = 0; i < AP_RANGEFINDER_NUM_AVERAGES; i++){
total += _history[i];
}
// average our sampels
distance = total / AP_RANGEFINDER_NUM_AVERAGES;
}else{
distance = temp_dist;
}
// return distance
return distance;
}
/*
// Read Sensor data - only the raw_value is filled in by this parent class
int RangeFinder::read()
{
// local variables
int temp_dist;
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;
}
// 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;
}
}
*/