mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Filter: validity of array index was checked AFTER accessing the element.
(correction decreased Program size by 12 bytes)
This commit is contained in:
parent
d3ea88e8c7
commit
338c054da2
@ -111,7 +111,7 @@ void ModeFilter<T,FILTER_SIZE>:: isort(T new_sample, bool drop_high)
|
||||
i = FilterWithBuffer<T,FILTER_SIZE>::sample_index-1;
|
||||
|
||||
// if the next element is higher than our new sample, push it up one position
|
||||
while( FilterWithBuffer<T,FILTER_SIZE>::samples[i-1] > new_sample && i > 0 ) {
|
||||
while(i > 0 && FilterWithBuffer<T,FILTER_SIZE>::samples[i-1] > new_sample) {
|
||||
FilterWithBuffer<T,FILTER_SIZE>::samples[i] = FilterWithBuffer<T,FILTER_SIZE>::samples[i-1];
|
||||
i--;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user