2021-01-09 01:22:29 -04:00
|
|
|
/*
|
|
|
|
polynomial fitting class, originally written by Siddharth Bharat Purohit
|
|
|
|
re-written for ArduPilot by Andrew Tridgell
|
|
|
|
|
|
|
|
This fits a polynomial of a given order to a set of data, running as
|
|
|
|
an online algorithm with minimal storage
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <stdint.h>
|
|
|
|
|
2021-01-17 21:28:32 -04:00
|
|
|
/*
|
|
|
|
polynomial fit with X axis type xtype and yaxis type vtype (must be a vector)
|
|
|
|
*/
|
|
|
|
template <uint8_t order, typename xtype, typename vtype>
|
|
|
|
class PolyFit
|
|
|
|
{
|
2021-01-09 01:22:29 -04:00
|
|
|
public:
|
2021-01-17 21:28:32 -04:00
|
|
|
void update(xtype x, vtype y);
|
|
|
|
bool get_polynomial(vtype res[order]) const;
|
2021-01-09 01:22:29 -04:00
|
|
|
|
|
|
|
private:
|
2021-01-17 21:28:32 -04:00
|
|
|
xtype mat[order][order];
|
|
|
|
vtype vec[order];
|
2021-01-09 01:22:29 -04:00
|
|
|
};
|
|
|
|
|