From b1df1d1843c44fc1d5ba1faa1e30cfc415e3f103 Mon Sep 17 00:00:00 2001 From: "tridge60@gmail.com" Date: Sat, 13 Aug 2011 04:46:10 +0000 Subject: [PATCH] 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 --- libraries/ModeFilter/ModeFilter.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/ModeFilter/ModeFilter.cpp b/libraries/ModeFilter/ModeFilter.cpp index 771ebc4f4a..15e8d9b825 100644 --- a/libraries/ModeFilter/ModeFilter.cpp +++ b/libraries/ModeFilter/ModeFilter.cpp @@ -57,14 +57,14 @@ void ModeFilter::isort() //Mode function, returning the mode or median. int ModeFilter::mode(){ - int mode = 0; + int fmode = 0; byte i = 0; byte count = 0; byte maxCount = 0; byte bimodal = 0; while(count > maxCount){ - mode = _samples[i]; + fmode = _samples[i]; maxCount = count; bimodal = 0; } @@ -75,9 +75,9 @@ int ModeFilter::mode(){ bimodal = 1; } - if(mode == 0 || bimodal == 1){ //Return the median if there is no mode. - mode = _samples[(MOD_FILTER_SIZE / 2)]; + if(fmode == 0 || bimodal == 1){ //Return the median if there is no mode. + fmode = _samples[(MOD_FILTER_SIZE / 2)]; } - return mode; + return fmode; }