mirror of https://github.com/ArduPilot/ardupilot
Filter: replace header guard with pragma once
This commit is contained in:
parent
f5437f30ac
commit
98904825cb
|
@ -17,9 +17,7 @@
|
|||
//
|
||||
/// @file AverageFilter.h
|
||||
/// @brief A class to provide the average of a number of samples
|
||||
|
||||
#ifndef __AVERAGE_FILTER_H__
|
||||
#define __AVERAGE_FILTER_H__
|
||||
#pragma once
|
||||
|
||||
#include "FilterClass.h"
|
||||
#include "FilterWithBuffer.h"
|
||||
|
@ -107,5 +105,3 @@ void AverageFilter<T,U,FILTER_SIZE>:: reset()
|
|||
// clear our variable
|
||||
_num_samples = 0;
|
||||
}
|
||||
|
||||
#endif // __AVERAGE_FILTER_H__
|
||||
|
|
|
@ -1,6 +1,4 @@
|
|||
|
||||
#ifndef __FILTER_BUTTER_H__
|
||||
#define __FILTER_BUTTER_H__
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
|
@ -107,5 +105,3 @@ struct butter50_8_coeffs
|
|||
};
|
||||
typedef Butter2<butter50_8_coeffs> butter50hz8_0; //50hz sample, 8hz fcut
|
||||
typedef Butter2<butter50_8_coeffs> butter10hz1_6; //10hz sample, 1.6hz fcut
|
||||
|
||||
#endif // __FILTER_BUTTER_H__
|
||||
|
|
|
@ -18,9 +18,7 @@
|
|||
/// @file Derivative.h
|
||||
/// @brief A class to implement a derivative (slope) filter
|
||||
/// See http://www.holoborodko.com/pavel/numerical-methods/numerical-derivative/smooth-low-noise-differentiators/
|
||||
|
||||
#ifndef __DERIVATIVE_FILTER_H__
|
||||
#define __DERIVATIVE_FILTER_H__
|
||||
#pragma once
|
||||
|
||||
#include "FilterClass.h"
|
||||
#include "FilterWithBuffer.h"
|
||||
|
@ -56,7 +54,3 @@ private:
|
|||
typedef DerivativeFilter<float,5> DerivativeFilterFloat_Size5;
|
||||
typedef DerivativeFilter<float,7> DerivativeFilterFloat_Size7;
|
||||
typedef DerivativeFilter<float,9> DerivativeFilterFloat_Size9;
|
||||
|
||||
|
||||
#endif // __DERIVATIVE_FILTER_H__
|
||||
|
||||
|
|
|
@ -1,6 +1,4 @@
|
|||
|
||||
#ifndef __FILTER_H__
|
||||
#define __FILTER_H__
|
||||
#pragma once
|
||||
|
||||
/* Umbrella header for the Filter library */
|
||||
|
||||
|
@ -11,6 +9,3 @@
|
|||
#include "LowPassFilter.h"
|
||||
#include "ModeFilter.h"
|
||||
#include "Butter.h"
|
||||
|
||||
#endif //__FILTER_H__
|
||||
|
||||
|
|
|
@ -18,9 +18,7 @@
|
|||
/// @file FilterClass.h
|
||||
/// @brief A pure virtual interface class
|
||||
///
|
||||
|
||||
#ifndef __FILTER_CLASS_H__
|
||||
#define __FILTER_CLASS_H__
|
||||
#pragma once
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
|
@ -43,6 +41,3 @@ typedef Filter<int16_t> FilterInt16;
|
|||
typedef Filter<uint16_t> FilterUInt16;
|
||||
typedef Filter<int32_t> FilterInt32;
|
||||
typedef Filter<uint32_t> FilterUInt32;
|
||||
|
||||
#endif // __FILTER_CLASS_H__
|
||||
|
||||
|
|
|
@ -20,9 +20,7 @@
|
|||
/// This is implemented separately to the base Filter class to get around
|
||||
/// restrictions caused by the use of templates which makes different sizes essentially
|
||||
/// completely different classes
|
||||
|
||||
#ifndef __FILTER_WITH_BUFFER_H__
|
||||
#define __FILTER_WITH_BUFFER_H__
|
||||
#pragma once
|
||||
|
||||
#include "FilterClass.h"
|
||||
|
||||
|
@ -116,8 +114,3 @@ T FilterWithBuffer<T,FILTER_SIZE>:: apply(T sample)
|
|||
// base class doesn't know what filtering to do so we just return the raw sample
|
||||
return sample;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
|
|
@ -19,9 +19,7 @@
|
|||
/// @brief A class to implement a low pass filter without losing precision even for int types
|
||||
/// the downside being that it's a little slower as it internally uses a float
|
||||
/// and it consumes an extra 4 bytes of memory to hold the constant gain
|
||||
|
||||
#ifndef __LOW_PASS_FILTER_H__
|
||||
#define __LOW_PASS_FILTER_H__
|
||||
#pragma once
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include "FilterClass.h"
|
||||
|
@ -88,6 +86,3 @@ typedef LowPassFilter<long> LowPassFilterLong;
|
|||
typedef LowPassFilter<float> LowPassFilterFloat;
|
||||
typedef LowPassFilter<Vector2f> LowPassFilterVector2f;
|
||||
typedef LowPassFilter<Vector3f> LowPassFilterVector3f;
|
||||
|
||||
#endif // __LOW_PASS_FILTER_H__
|
||||
|
||||
|
|
|
@ -14,9 +14,7 @@
|
|||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef LOWPASSFILTER2P_H
|
||||
#define LOWPASSFILTER2P_H
|
||||
#pragma once
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <math.h>
|
||||
|
@ -91,6 +89,3 @@ typedef LowPassFilter2p<long> LowPassFilter2pLong;
|
|||
typedef LowPassFilter2p<float> LowPassFilter2pFloat;
|
||||
typedef LowPassFilter2p<Vector2f> LowPassFilter2pVector2f;
|
||||
typedef LowPassFilter2p<Vector3f> LowPassFilter2pVector3f;
|
||||
|
||||
|
||||
#endif // LOWPASSFILTER2P_H
|
||||
|
|
|
@ -18,9 +18,7 @@
|
|||
/// @file ModeFilter.h
|
||||
/// @brief A class to apply a mode filter which is basically picking the median value from the last x samples
|
||||
/// the filter size (i.e buffer size) should always be an odd number
|
||||
|
||||
#ifndef __MODE_FILTER_H__
|
||||
#define __MODE_FILTER_H__
|
||||
#pragma once
|
||||
|
||||
#include <inttypes.h>
|
||||
#include "FilterClass.h"
|
||||
|
@ -154,5 +152,3 @@ void ModeFilter<T,FILTER_SIZE>:: isort(T new_sample, bool drop_high)
|
|||
FilterWithBuffer<T,FILTER_SIZE>::samples[i] = new_sample;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // __MODE_FILTER_H__
|
||||
|
|
Loading…
Reference in New Issue