forked from Archive/PX4-Autopilot
Switching back to 23 states, fixed mag update logic
This commit is contained in:
parent
b9a3fa60bc
commit
f4075b5623
|
@ -83,7 +83,7 @@
|
|||
#include <mathlib/mathlib.h>
|
||||
#include <mavlink/mavlink_log.h>
|
||||
|
||||
#include "estimator_21states.h"
|
||||
#include "estimator_23states.h"
|
||||
|
||||
|
||||
|
||||
|
@ -451,6 +451,8 @@ FixedwingEstimator::~FixedwingEstimator()
|
|||
} while (_estimator_task != -1);
|
||||
}
|
||||
|
||||
delete _ekf;
|
||||
|
||||
estimator::g_estimator = nullptr;
|
||||
}
|
||||
|
||||
|
@ -564,7 +566,7 @@ FixedwingEstimator::task_main()
|
|||
#else
|
||||
_sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
|
||||
/* XXX remove this!, BUT increase the data buffer size! */
|
||||
orb_set_interval(_sensor_combined_sub, 4);
|
||||
orb_set_interval(_sensor_combined_sub, 9);
|
||||
#endif
|
||||
|
||||
/* sets also parameters in the EKF object */
|
||||
|
@ -809,6 +811,8 @@ FixedwingEstimator::task_main()
|
|||
|
||||
#endif
|
||||
|
||||
//warnx("dang: %8.4f %8.4f dvel: %8.4f %8.4f", _ekf->dAngIMU.x, _ekf->dAngIMU.z, _ekf->dVelIMU.x, _ekf->dVelIMU.z);
|
||||
|
||||
bool airspeed_updated;
|
||||
orb_check(_airspeed_sub, &airspeed_updated);
|
||||
|
||||
|
@ -1247,12 +1251,15 @@ FixedwingEstimator::task_main()
|
|||
_ekf->fuseMagData = true;
|
||||
_ekf->RecallStates(_ekf->statesAtMagMeasTime, (IMUmsec - _parameters.mag_delay_ms)); // Assume 50 msec avg delay for magnetometer data
|
||||
|
||||
_ekf->magstate.obsIndex = 0;
|
||||
_ekf->FuseMagnetometer();
|
||||
_ekf->FuseMagnetometer();
|
||||
_ekf->FuseMagnetometer();
|
||||
|
||||
} else {
|
||||
_ekf->fuseMagData = false;
|
||||
}
|
||||
|
||||
if (_ekf->statesInitialised) _ekf->FuseMagnetometer();
|
||||
|
||||
// Fuse Airspeed Measurements
|
||||
if (newAdsData && _ekf->statesInitialised && _ekf->VtasMeas > 8.0f) {
|
||||
_ekf->fuseVtasData = true;
|
||||
|
|
|
@ -61,8 +61,8 @@ void AttPosEKF::UpdateStrapdownEquationsNED()
|
|||
|
||||
// Apply corrections for earths rotation rate and coning errors
|
||||
// * and + operators have been overloaded
|
||||
correctedDelAng = correctedDelAng - Tnb*earthRateNED*dtIMU + 8.333333333333333e-2f*(prevDelAng % correctedDelAng);
|
||||
|
||||
correctedDelAng = dAngIMU;//correctedDelAng - Tnb*earthRateNED*dtIMU + 8.333333333333333e-2f*(prevDelAng % correctedDelAng);
|
||||
correctedDelAng.z = 0;
|
||||
// Convert the rotation vector to its equivalent quaternion
|
||||
rotationMag = correctedDelAng.length();
|
||||
if (rotationMag < 1e-12f)
|
||||
|
@ -151,7 +151,7 @@ void AttPosEKF::UpdateStrapdownEquationsNED()
|
|||
states[9] = states[9] + 0.5f*(states[6] + lastVelocity[2])*dtIMU;
|
||||
|
||||
// Constrain states (to protect against filter divergence)
|
||||
ConstrainStates();
|
||||
//ConstrainStates();
|
||||
}
|
||||
|
||||
void AttPosEKF::CovariancePrediction(float dt)
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
#include "estimator.h"
|
||||
#include "estimator_23states.h"
|
||||
#include <string.h>
|
||||
#include <stdarg.h>
|
||||
|
||||
|
@ -1140,7 +1140,7 @@ void AttPosEKF::FuseMagnetometer()
|
|||
// data fit is the only assumption we can make
|
||||
// so we might as well take advantage of the computational efficiencies
|
||||
// associated with sequential fusion
|
||||
if (useCompass && (fuseMagData || obsIndex == 1 || obsIndex == 2))
|
||||
if (useCompass && fuseMagData && (obsIndex < 3))
|
||||
{
|
||||
// Limit range of states modified when on ground
|
||||
if(!onGround)
|
||||
|
@ -1156,7 +1156,7 @@ void AttPosEKF::FuseMagnetometer()
|
|||
// three prediction time steps.
|
||||
|
||||
// Calculate observation jacobians and Kalman gains
|
||||
if (fuseMagData)
|
||||
if (obsIndex == 0)
|
||||
{
|
||||
// Copy required states to local variable names
|
||||
q0 = statesAtMagMeasTime[0];
|
||||
|
@ -1251,11 +1251,6 @@ void AttPosEKF::FuseMagnetometer()
|
|||
Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][1]*SH_MAG[0] + P[22][3]*SH_MAG[2] + P[22][0]*SK_MX[3] - P[22][2]*SK_MX[2] - P[22][16]*SK_MX[1] + P[22][17]*SK_MX[5] - P[22][18]*SK_MX[4]);
|
||||
varInnovMag[0] = 1.0f/SK_MX[0];
|
||||
innovMag[0] = MagPred[0] - magData.x;
|
||||
|
||||
// reset the observation index to 0 (we start by fusing the X
|
||||
// measurement)
|
||||
obsIndex = 0;
|
||||
fuseMagData = false;
|
||||
}
|
||||
else if (obsIndex == 1) // we are now fusing the Y measurement
|
||||
{
|
||||
|
|
|
@ -229,7 +229,7 @@ static void quat2eul(float (&eul)[3], const float (&quat)[4]);
|
|||
|
||||
static void calcvelNED(float (&velNED)[3], float gpsCourse, float gpsGndSpd, float gpsVelD);
|
||||
|
||||
static void calcposNED(float (&posNED)[3], double lat, double lon, float hgt, double latRef, double lonRef, float hgtRef);
|
||||
void calcposNED(float (&posNED)[3], double lat, double lon, float hgt, double latRef, double lonRef, float hgtRef);
|
||||
|
||||
static void calcLLH(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef);
|
||||
|
||||
|
|
|
@ -46,7 +46,7 @@ Vector3f operator*(Vector3f vecIn1, float sclIn1);
|
|||
|
||||
void swap_var(float &d1, float &d2);
|
||||
|
||||
const unsigned int n_states = 21;
|
||||
const unsigned int n_states = 23;
|
||||
const unsigned int data_buffer_size = 50;
|
||||
|
||||
enum GPS_FIX {
|
||||
|
|
|
@ -39,5 +39,5 @@ MODULE_COMMAND = ekf_att_pos_estimator
|
|||
|
||||
SRCS = ekf_att_pos_estimator_main.cpp \
|
||||
ekf_att_pos_estimator_params.c \
|
||||
estimator_21states.cpp \
|
||||
estimator_23states.cpp \
|
||||
estimator_utilities.cpp
|
||||
|
|
Loading…
Reference in New Issue