ardupilot/libraries/AP_Math/polyfit.h

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

28 lines
595 B
C
Raw Permalink Normal View History

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>
/*
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:
void update(xtype x, vtype y);
bool get_polynomial(vtype res[order]) const;
2021-01-09 01:22:29 -04:00
private:
xtype mat[order][order];
vtype vec[order];
2021-01-09 01:22:29 -04:00
};