mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-29 12:08:32 -04:00
ModeFilter: fixed a shadowed variable
mode is a member of the class already, so call the local variable fmode git-svn-id: https://arducopter.googlecode.com/svn/trunk@3081 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
6cf66ee773
commit
b1df1d1843
@ -57,14 +57,14 @@ void ModeFilter::isort()
|
|||||||
|
|
||||||
//Mode function, returning the mode or median.
|
//Mode function, returning the mode or median.
|
||||||
int ModeFilter::mode(){
|
int ModeFilter::mode(){
|
||||||
int mode = 0;
|
int fmode = 0;
|
||||||
byte i = 0;
|
byte i = 0;
|
||||||
byte count = 0;
|
byte count = 0;
|
||||||
byte maxCount = 0;
|
byte maxCount = 0;
|
||||||
byte bimodal = 0;
|
byte bimodal = 0;
|
||||||
|
|
||||||
while(count > maxCount){
|
while(count > maxCount){
|
||||||
mode = _samples[i];
|
fmode = _samples[i];
|
||||||
maxCount = count;
|
maxCount = count;
|
||||||
bimodal = 0;
|
bimodal = 0;
|
||||||
}
|
}
|
||||||
@ -75,9 +75,9 @@ int ModeFilter::mode(){
|
|||||||
bimodal = 1;
|
bimodal = 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(mode == 0 || bimodal == 1){ //Return the median if there is no mode.
|
if(fmode == 0 || bimodal == 1){ //Return the median if there is no mode.
|
||||||
mode = _samples[(MOD_FILTER_SIZE / 2)];
|
fmode = _samples[(MOD_FILTER_SIZE / 2)];
|
||||||
}
|
}
|
||||||
|
|
||||||
return mode;
|
return fmode;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user