mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-19 23:28:32 -04:00
24 lines
476 B
C++
24 lines
476 B
C++
/*
|
|
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>
|
|
|
|
template <uint8_t order>
|
|
class PolyFit {
|
|
public:
|
|
void update(float x, float y);
|
|
bool get_polynomial(float res[order]) const;
|
|
|
|
private:
|
|
float mat[order][order];
|
|
float vec[order];
|
|
};
|
|
|