34#include "generated/airframe.h" 
   38#define eigen_assert(_cond) { if (!(_cond)) { while(1) ; } } 
   42#pragma GCC diagnostic ignored "-Wint-in-bool-context" 
   43#pragma GCC diagnostic ignored "-Wshadow" 
   45#pragma GCC diagnostic pop 
  140#ifndef INS_MEKF_WIND_P0_QUAT 
  141#define INS_MEKF_WIND_P0_QUAT       0.007615f 
  143#ifndef INS_MEKF_WIND_P0_SPEED 
  144#define INS_MEKF_WIND_P0_SPEED      1.E+2f 
  146#ifndef INS_MEKF_WIND_P0_POS 
  147#define INS_MEKF_WIND_P0_POS        1.E+1f 
  149#ifndef INS_MEKF_WIND_P0_RATES_BIAS 
  150#define INS_MEKF_WIND_P0_RATES_BIAS 1.E-3f 
  152#ifndef INS_MEKF_WIND_P0_ACCEL_BIAS 
  153#define INS_MEKF_WIND_P0_ACCEL_BIAS 1.E-3f 
  155#ifndef INS_MEKF_WIND_P0_BARO_BIAS 
  156#define INS_MEKF_WIND_P0_BARO_BIAS  1.E-3f 
  158#ifndef INS_MEKF_WIND_P0_WIND 
  159#define INS_MEKF_WIND_P0_WIND       1.E-0f 
  163#ifndef INS_MEKF_WIND_Q_GYRO 
  164#define INS_MEKF_WIND_Q_GYRO        1.E-2f 
  166#ifndef INS_MEKF_WIND_Q_ACCEL 
  167#define INS_MEKF_WIND_Q_ACCEL       1.E-2f 
  169#ifndef INS_MEKF_WIND_Q_RATES_BIAS 
  170#define INS_MEKF_WIND_Q_RATES_BIAS  1.E-6f 
  172#ifndef INS_MEKF_WIND_Q_ACCEL_BIAS 
  173#define INS_MEKF_WIND_Q_ACCEL_BIAS  1.E-6f 
  175#ifndef INS_MEKF_WIND_Q_BARO_BIAS 
  176#define INS_MEKF_WIND_Q_BARO_BIAS   1.E-3f 
  178#ifndef INS_MEKF_WIND_Q_WIND 
  179#define INS_MEKF_WIND_Q_WIND        1.E+1f 
  183#ifndef INS_MEKF_WIND_R_SPEED 
  184#define INS_MEKF_WIND_R_SPEED       0.1f 
  186#ifndef INS_MEKF_WIND_R_SPEED_Z 
  187#define INS_MEKF_WIND_R_SPEED_Z     0.2f 
  189#ifndef INS_MEKF_WIND_R_POS 
  190#define INS_MEKF_WIND_R_POS         2.0f 
  192#ifndef INS_MEKF_WIND_R_POS_Z 
  193#define INS_MEKF_WIND_R_POS_Z       4.0f 
  195#ifndef INS_MEKF_WIND_R_MAG 
  196#define INS_MEKF_WIND_R_MAG         1.f 
  198#ifndef INS_MEKF_WIND_R_BARO 
  199#define INS_MEKF_WIND_R_BARO        2.f 
  201#ifndef INS_MEKF_WIND_R_AIRSPEED 
  202#define INS_MEKF_WIND_R_AIRSPEED    0.1f 
  204#ifndef INS_MEKF_WIND_R_AOA 
  205#define INS_MEKF_WIND_R_AOA         0.1f 
  207#ifndef INS_MEKF_WIND_R_AOS 
  208#define INS_MEKF_WIND_R_AOS         0.1f 
  212#ifndef INS_MEKF_WIND_DISABLE_WIND 
  213#define INS_MEKF_WIND_DISABLE_WIND true 
  222#define mwp mekf_wind_private 
  373  mwp.state.quat.normalize();
 
  374  mwp.state.speed = 
mwp.state.speed + 
mwp.state.accel * dt;
 
  375  mwp.state.pos = 
mwp.state.pos + 
mwp.state.speed * dt;
 
  404  At.transposeInPlace();
 
  406  Ant = 
An.transpose();
 
  416    mwp.state.wind = Vector3f::Zero();
 
 
  441  mwp.state.quat.normalize();
 
  458  At.transposeInPlace();
 
  460  Ant = 
An.transpose();
 
  480  mwp.state.quat.normalize();
 
  483  mwp.P = (MEKFWCov::Identity() - 
K * 
H) * 
mwp.P;
 
 
  490  mwp.state.quat.w() = quat->
qi;
 
  491  mwp.state.quat.x() = quat->
qx;
 
  492  mwp.state.quat.y() = quat->
qy;
 
  493  mwp.state.quat.z() = quat->
qz;
 
  496  mwp.state.rates_bias(0) = gyro_bias->
p;
 
  497  mwp.state.rates_bias(1) = gyro_bias->
q;
 
  498  mwp.state.rates_bias(2) = gyro_bias->
r;
 
 
  503  mwp.measurements.mag(0) = mag->
x;
 
  504  mwp.measurements.mag(1) = mag->
y;
 
  505  mwp.measurements.mag(2) = mag->
z;
 
  508  const Matrix3f Rqt = 
mwp.state.quat.toRotationMatrix().transpose();
 
  524  mwp.state.quat.normalize();
 
  538  mwp.P = (MEKFWCov::Identity() - 
K * 
H) * 
mwp.P;
 
 
  555  float res = 
mwp.measurements.baro_alt - (
mwp.state.pos(2) - 
mwp.state.baro_bias);
 
  562  mwp.state.quat.normalize();
 
  572  mwp.P = (MEKFWCov::Identity() - 
K * 
H) * 
mwp.P;
 
 
  577  mwp.measurements.pos(0) = pos->
x;
 
  578  mwp.measurements.pos(1) = pos->
y;
 
  579  mwp.measurements.pos(2) = pos->
z;
 
  580  mwp.measurements.speed(0) = speed->
x;
 
  581  mwp.measurements.speed(1) = speed->
y;
 
  582  mwp.measurements.speed(2) = speed->
z;
 
  586  H.block<6,6>(0,
MEKF_WIND_vx) = Matrix<float,6,6>::Identity();
 
  594  res.block<3,1>(0,0) = 
mwp.measurements.speed - 
mwp.state.speed;
 
  595  res.block<3,1>(3,0) = 
mwp.measurements.pos - 
mwp.state.pos;
 
  611  mwp.P = (MEKFWCov::Identity() - 
K * 
H) * 
mwp.P;
 
 
  616  mwp.measurements.airspeed = airspeed;
 
  632  float res = 
mwp.measurements.airspeed - 
IuRqt * va;
 
  639  mwp.state.quat.normalize();
 
  649  mwp.P = (MEKFWCov::Identity() - 
K * 
H) * 
mwp.P;
 
 
  654  mwp.measurements.aoa = aoa;
 
  655  mwp.measurements.aos = aos;
 
  659  const Matrix3f Rqt = 
mwp.state.quat.toRotationMatrix().transpose();
 
  662  const float van = va.norm();
 
  667      || 
mwp.state.pos(2) > -10.f) {
 
  687  Hn(0,0) = C(2) * va(0) - C(0) * va(2);
 
  698  res(1) = - va.transpose() * 
B * va;
 
  705  mwp.state.quat.normalize();
 
  715  mwp.P = (MEKFWCov::Identity() - 
K * 
H) * 
mwp.P;
 
 
  724    .
x = 
mwp.state.pos(0),
 
  725    .y = 
mwp.state.pos(1),
 
  726    .z = 
mwp.state.pos(2)
 
 
  733  mwp.state.pos(0) = 
p->x;
 
  734  mwp.state.pos(1) = 
p->y;
 
  735  mwp.state.pos(2) = 
p->z;
 
 
  741    .
x = 
mwp.state.speed(0),
 
  742    .y = 
mwp.state.speed(1),
 
  743    .z = 
mwp.state.speed(2)
 
 
  750  mwp.state.speed(0) = 
s->x;
 
  751  mwp.state.speed(1) = 
s->y;
 
  752  mwp.state.speed(2) = 
s->z;
 
 
  758    .
x = 
mwp.state.accel(0),
 
  759    .y = 
mwp.state.accel(1),
 
  760    .z = 
mwp.state.accel(2)
 
 
  768    .
qi = 
mwp.state.quat.w(),
 
  769    .qx = 
mwp.state.quat.x(),
 
  770    .qy = 
mwp.state.quat.y(),
 
  771    .qz = 
mwp.state.quat.z()
 
 
  778  mwp.state.quat.w() = quat->
qi;
 
  779  mwp.state.quat.x() = quat->
qx;
 
  780  mwp.state.quat.y() = quat->
qy;
 
  781  mwp.state.quat.z() = quat->
qz;
 
 
  787    .
p = 
mwp.inputs.rates(0) - 
mwp.state.rates_bias(0),
 
  788    .q = 
mwp.inputs.rates(1) - 
mwp.state.rates_bias(1),
 
  789    .r = 
mwp.inputs.rates(2) - 
mwp.state.rates_bias(2)
 
 
  797    .
x = 
mwp.state.wind(0),
 
  798    .y = 
mwp.state.wind(1),
 
  799    .z = 
mwp.state.wind(2)
 
 
  806  const Matrix3f Rqt = 
mwp.state.quat.toRotationMatrix().transpose();
 
 
  818  return (
mwp.state.speed - 
mwp.state.wind).norm();
 
 
  824    .
x = 
mwp.state.accel_bias(0),
 
  825    .y = 
mwp.state.accel_bias(1),
 
  826    .z = 
mwp.state.accel_bias(2)
 
 
  834    .
p = 
mwp.state.rates_bias(0),
 
  835    .q = 
mwp.state.rates_bias(1),
 
  836    .r = 
mwp.state.rates_bias(2)
 
 
  843  return mwp.state.baro_bias;
 
 
MekfWindPNoiseVar
Process noise elements and size.
@ MEKF_WIND_PROC_NOISE_SIZE
Matrix< float, MEKF_WIND_MEAS_NOISE_SIZE, MEKF_WIND_MEAS_NOISE_SIZE > MEKFWMNoise
#define INS_MEKF_WIND_R_SPEED_Z
#define INS_MEKF_WIND_P0_RATES_BIAS
float ins_mekf_wind_get_baro_bias(void)
void ins_mekf_wind_set_quat(struct FloatQuat *quat)
struct NedCoor_f ins_mekf_wind_get_wind_ned(void)
void ins_mekf_wind_update_incidence(float aoa, float aos)
#define INS_MEKF_WIND_R_AOA
#define INS_MEKF_WIND_R_MAG
void ins_mekf_wind_set_pos_ned(struct NedCoor_f *p)
#define INS_MEKF_WIND_Q_ACCEL_BIAS
static void init_mekf_state(void)
#define INS_MEKF_WIND_Q_GYRO
float ins_mekf_wind_get_airspeed_norm(void)
static const Vector3f gravity(0.f, 0.f, 9.81f)
#define INS_MEKF_WIND_Q_BARO_BIAS
void ins_mekf_wind_update_baro(float baro_alt)
static Quaternionf quat_add(const Quaternionf &q1, const Quaternionf &q2)
#define INS_MEKF_WIND_Q_RATES_BIAS
#define INS_MEKF_WIND_P0_QUAT
#define INS_MEKF_WIND_R_AIRSPEED
#define INS_MEKF_WIND_R_POS_Z
struct MekfWindInputs inputs
struct NedCoor_f ins_mekf_wind_get_accel_ned(void)
#define INS_MEKF_WIND_Q_WIND
void ins_mekf_wind_update_params(void)
#define INS_MEKF_WIND_R_AOS
static struct InsMekfWindPrivate mekf_wind_private
void ins_mekf_wind_init(void)
Init function.
void ins_mekf_wind_set_mag_h(const struct FloatVect3 *mag_h)
struct NedCoor_f ins_mekf_wind_get_pos_ned(void)
Getter/Setter functions.
static Quaternionf quat_smul(const Quaternionf &q1, float scal)
MekfWindCovVar
Covariance matrix elements and size.
#define INS_MEKF_WIND_P0_ACCEL_BIAS
struct FloatRates ins_mekf_wind_get_body_rates(void)
static Matrix3f skew_sym(const Vector3f &v)
build skew symetric matrix from vector m = [ 0, -v(2), v(1) ] [ v(2), 0, -v(0) ] [ -v(1),...
void ins_mekf_wind_set_speed_ned(struct NedCoor_f *s)
void ins_mekf_wind_update_mag(struct FloatVect3 *mag, bool attitude_only)
#define INS_MEKF_WIND_R_BARO
Matrix< float, MEKF_WIND_PROC_NOISE_SIZE, MEKF_WIND_PROC_NOISE_SIZE > MEKFWPNoise
struct ins_mekf_wind_parameters ins_mekf_wind_params
struct FloatVect3 ins_mekf_wind_get_accel_bias(void)
struct NedCoor_f ins_mekf_wind_get_airspeed_body(void)
#define INS_MEKF_WIND_P0_BARO_BIAS
struct FloatQuat ins_mekf_wind_get_quat(void)
void ins_mekf_wind_propagate(struct FloatRates *gyro, struct FloatVect3 *acc, float dt)
Full INS propagation.
#define INS_MEKF_WIND_P0_POS
#define INS_MEKF_WIND_P0_WIND
void ins_mekf_wind_align(struct FloatRates *gyro_bias, struct FloatQuat *quat)
void ins_mekf_wind_reset(void)
MekfWindMNoiseVar
Measurement noise elements and size.
@ MEKF_WIND_MEAS_NOISE_SIZE
#define INS_MEKF_WIND_R_SPEED
void ins_mekf_wind_propagate_ahrs(struct FloatRates *gyro, struct FloatVect3 *acc, float dt)
AHRS-only propagation + accel correction.
#define INS_MEKF_WIND_Q_ACCEL
#define INS_MEKF_WIND_DISABLE_WIND
struct FloatRates ins_mekf_wind_get_rates_bias(void)
struct MekfWindMeasurements measurements
#define INS_MEKF_WIND_R_POS
struct NedCoor_f ins_mekf_wind_get_speed_ned(void)
struct MekfWindState state
#define INS_MEKF_WIND_P0_SPEED
Matrix< float, MEKF_WIND_COV_SIZE, MEKF_WIND_COV_SIZE > MEKFWCov
void ins_mekf_wind_update_airspeed(float airspeed)
void ins_mekf_wind_update_pos_speed(struct FloatVect3 *pos, struct FloatVect3 *speed)
filter measurement vector
Multiplicative Extended Kalman Filter in rotation matrix formulation.
float Q_accel
accel process noise
float Q_wind
wind process noise
float R_aos
sideslip angle measurement noise
float R_baro
baro measurement noise
float R_mag
mag measurement noise
bool disable_wind
disable wind estimation
float R_aoa
angle of attack measurement noise
float R_pos_z
vertical pos measurement noise
float Q_rates_bias
rates bias process noise
float R_airspeed
airspeed measurement noise
float Q_baro_bias
baro bias process noise
float Q_accel_bias
accel bias process noise
float R_pos
pos measurement noise
float R_speed
speed measurement noise
float R_speed_z
vertical speed measurement noise
float Q_gyro
gyro process noise
static struct FloatVect3 H
vector in North East Down coordinates Units: meters