mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF : Additional flash logging
This commit is contained in:
parent
d6ead64083
commit
6b9733c013
|
@ -6,10 +6,10 @@
|
||||||
|
|
||||||
// uncomment this to force the optimisation of this code, note that
|
// uncomment this to force the optimisation of this code, note that
|
||||||
// this makes debugging harder
|
// this makes debugging harder
|
||||||
// #pragma GCC optimize("O3")
|
#pragma GCC optimize("O3")
|
||||||
|
|
||||||
#include "AP_NavEKF.h"
|
#include "AP_NavEKF.h"
|
||||||
#include <stdio.h>
|
//#include <stdio.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
@ -1923,6 +1923,13 @@ void NavEKF::getAccelBias(Vector3f &accelBias)
|
||||||
accelBias.z = states[15]*dtIMUAvgInv;
|
accelBias.z = states[15]*dtIMUAvgInv;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void NavEKF::getWind(Vector3f &wind)
|
||||||
|
{
|
||||||
|
wind.x = states[16];
|
||||||
|
wind.y = states[17];
|
||||||
|
wind.z = 0.0f; // curently don't estimate this
|
||||||
|
}
|
||||||
|
|
||||||
void NavEKF::getMagNED(Vector3f &magNED)
|
void NavEKF::getMagNED(Vector3f &magNED)
|
||||||
{
|
{
|
||||||
magNED.x = states[18]*1000.0f;
|
magNED.x = states[18]*1000.0f;
|
||||||
|
|
|
@ -92,6 +92,9 @@ public:
|
||||||
// return delta velocity bias estimates
|
// return delta velocity bias estimates
|
||||||
void getAccelBias(Vector3f &accelBias);
|
void getAccelBias(Vector3f &accelBias);
|
||||||
|
|
||||||
|
// return the NE wind speed estimates
|
||||||
|
void getWind(Vector3f &wind);
|
||||||
|
|
||||||
// return earth magnetic field estimates
|
// return earth magnetic field estimates
|
||||||
void getMagNED(Vector3f &magNED);
|
void getMagNED(Vector3f &magNED);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue