2021-01-09 01:22:29 -04:00
|
|
|
/*
|
|
|
|
polynomial fitting class, originally written by Siddharth Bharat Purohit
|
|
|
|
re-worked for ArduPilot by Andrew Tridgell
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "polyfit.h"
|
|
|
|
#include "AP_Math.h"
|
2021-01-17 21:28:32 -04:00
|
|
|
#include "vector3.h"
|
2021-01-09 01:22:29 -04:00
|
|
|
|
2021-01-17 21:28:32 -04:00
|
|
|
template <uint8_t order, typename xtype, typename vtype>
|
|
|
|
void PolyFit<order,xtype,vtype>::update(xtype x, vtype y)
|
2021-01-09 01:22:29 -04:00
|
|
|
{
|
2021-01-17 21:28:32 -04:00
|
|
|
xtype temp = 1;
|
2021-01-09 01:22:29 -04:00
|
|
|
|
|
|
|
for (int8_t i = 2*(order-1); i >= 0; i--) {
|
|
|
|
int8_t k = (i<order)?0:i - order + 1;
|
|
|
|
for (int8_t j = i - k; j >= k; j--) {
|
|
|
|
mat[j][i-j] += temp;
|
|
|
|
}
|
|
|
|
temp *= x;
|
|
|
|
}
|
2021-01-17 21:28:32 -04:00
|
|
|
|
2021-01-09 01:22:29 -04:00
|
|
|
temp = 1;
|
|
|
|
for (int8_t i = order-1; i >= 0; i--) {
|
|
|
|
vec[i] += y * temp;
|
|
|
|
temp *= x;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2021-01-17 21:28:32 -04:00
|
|
|
template <uint8_t order, typename xtype, typename vtype>
|
|
|
|
bool PolyFit<order,xtype,vtype>::get_polynomial(vtype res[order]) const
|
2021-01-09 01:22:29 -04:00
|
|
|
{
|
2021-01-17 21:28:32 -04:00
|
|
|
// we dynamically allocate the inverse matrix to keep stack usage low
|
2024-05-26 22:24:12 -03:00
|
|
|
xtype *inv_mat = NEW_NOTHROW xtype[order*order];
|
2021-01-17 21:28:32 -04:00
|
|
|
if (inv_mat == nullptr) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (!mat_inverse(&mat[0][0], inv_mat, order)) {
|
|
|
|
delete[] inv_mat;
|
2021-01-09 01:22:29 -04:00
|
|
|
return false;
|
|
|
|
}
|
2021-01-17 21:28:32 -04:00
|
|
|
// the summation must be done with double precision to get
|
|
|
|
// good accuracy
|
|
|
|
Vector3d resd[order] {};
|
2021-01-09 01:22:29 -04:00
|
|
|
for (uint8_t i = 0; i < order; i++) {
|
|
|
|
for (uint8_t j = 0; j < order; j++) {
|
2021-01-17 21:28:32 -04:00
|
|
|
resd[i].x += vec[j].x * inv_mat[i*order+j];
|
|
|
|
resd[i].y += vec[j].y * inv_mat[i*order+j];
|
|
|
|
resd[i].z += vec[j].z * inv_mat[i*order+j];
|
2021-01-09 01:22:29 -04:00
|
|
|
}
|
|
|
|
}
|
2021-01-17 21:28:32 -04:00
|
|
|
for (uint8_t j = 0; j < order; j++) {
|
|
|
|
res[j].x = resd[j].x;
|
|
|
|
res[j].y = resd[j].y;
|
|
|
|
res[j].z = resd[j].z;
|
|
|
|
}
|
|
|
|
delete[] inv_mat;
|
2021-01-09 01:22:29 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2021-01-17 21:28:32 -04:00
|
|
|
// instantiate for order 4 double with Vector3f
|
|
|
|
template class PolyFit<4, double, Vector3f>;
|