37 #include "generated/airframe.h"
38 #include "generated/flight_plan.h"
51 #if SEND_INVARIANT_FILTER || PERIODIC_TELEMETRY
55 #if LOG_INVARIANT_FILTER
98 #define INS_INV_MVZ 15.
102 #define INS_INV_MH 0.2
106 #define INS_INV_NX 0.8
110 #define INS_INV_NXZ 0.5
114 #define INS_INV_NH 1.2
118 #define INS_INV_OV 1.2
122 #define INS_INV_OB 1.
126 #define INS_INV_RV 4.
130 #define INS_INV_RH 8.
134 #define INS_INV_SH 0.01
145 #define B ins_float_inv.mag_h
157 static inline void invariant_model(
float *o,
const float *
x,
const int n,
const float *u,
const int m);
188 #if SEND_INVARIANT_FILTER || PERIODIC_TELEMETRY
193 pprz_msg_send_INV_FILTER(trans, dev,
223 utm0.
alt = GROUND_ALT;
229 llh_nav0.
lat = NAV_LAT0;
230 llh_nav0.
lon = NAV_LON0;
232 llh_nav0.
alt = NAV_ALT0 + NAV_MSL0;
237 ltp_def.
hmsl = NAV_ALT0;
266 #if PERIODIC_TELEMETRY
370 #if SEND_INVARIANT_FILTER
374 #if LOG_INVARIANT_FILTER
379 "p q r ax ay az gx gy gz gvx gvy gvz mx my mz b qi qx qy qz bp bq br vx vy vz px py pz hb as\n");
383 "%.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f\n",
440 struct NedCoor_i gps_pos_cm_ned, ned_pos;
456 static float ins_qfe = 101325.0f;
457 static float alpha = 10.0f;
459 static float baro_moy = 0.0f;
460 static float baro_prev = 0.0f;
467 baro_prev = pressure;
469 baro_moy = (baro_moy * (i - 1) + pressure) / i;
470 alpha = (10.*alpha + (baro_moy - baro_prev)) / (11.0f);
471 baro_prev = baro_moy;
473 if (fabs(alpha) < 0.005f) {
488 #define MAG_FROZEN_COUNT 30
495 if (last_mx == mag->
x) {
497 if (mag_frozen_count == 0) {
518 static inline void invariant_model(
float *o,
const float *x,
const int n,
const float *u,
519 const int m __attribute__((unused)))
522 #pragma GCC diagnostic push // require GCC 4.6
523 #pragma GCC diagnostic ignored "-Wcast-qual"
526 #pragma GCC diagnostic pop // require GCC 4.6
533 if (fabs(s->
as) < 0.1) {
574 memcpy(o, &s_dot, n *
sizeof(
float));
584 struct FloatVect3 YBt, I, Ev, Eb, Ex, Itemp, Ebtemp, Evtemp;
589 if (fabs(_ins->
state.
as) < 0.1) {
634 temp = (_ins->
gains.
lb / 100.) * temp;
656 temp = (-_ins->
gains.
ob / 1000.) * temp;
#define VECT3_CROSS_PRODUCT(_vo, _v1, _v2)
#define VECT3_DOT_PRODUCT(_v1, _v2)
#define INT32_VECT3_SCALE_2(_a, _b, _num, _den)
float nxz
Tuning parameter of vertical position error on position.
Interface to align the AHRS via low-passed measurements at startup.
#define INV_STATE_DIM
Invariant filter state dimension.
bool utm_initialized_f
True if utm origin (float) coordinate frame is initialsed.
struct VehicleInterface vi
static void orientationSetQuat_f(struct OrientationReps *orientation, struct FloatQuat *quat)
Set vehicle body attitude from quaternion (float).
#define INV_COMMAND_DIM
Invariant filter command vector dimension.
#define VECT3_ADD(_a, _b)
struct NedCoor_f speed_gps
Measured gps speed.
struct FloatVect3 ME
Correction gains on gyro biases.
float mv
Tuning parameter of horizontal speed error on speed.
float OE
Correction gains on magnetometer sensitivity.
definition of the local (flat earth) coordinate system
static const struct FloatVect3 A
float alt
in meters (above WGS84 reference ellipsoid or above MSL)
float ov
Tuning parameter of speed error on gyro biases.
Periodic telemetry system header (includes downlink utility and generated code).
void ins_float_invariant_update_mag(struct FloatVect3 *mag)
#define NED_FLOAT_OF_BFP(_o, _i)
float rh
Tuning parameter of baro error on accel biases (vertical projection)
vector in EarthCenteredEarthFixed coordinates
vector in EarthCenteredEarthFixed coordinates
void ned_of_ecef_vect_f(struct NedCoor_f *ned, struct LtpDef_f *def, struct EcefCoor_f *ecef)
#define QUAT_SMUL(_qo, _qi, _s)
struct LtpDef_f ned_origin_f
Definition of the local (flat earth) coordinate system.
static void float_quat_identity(struct FloatQuat *q)
initialises a quaternion to identity
bool reset
flag to request reset/reinit the filter
struct FloatVect3 accel
Input accelerometers.
float RE
Correction gains on accel bias.
struct inv_command cmd
command vector
struct FloatQuat quat
Estimated attitude (quaternion)
#define VECT3_COPY(_a, _b)
static struct FloatRMat * orientationGetRMat_f(struct OrientationReps *orientation)
Get vehicle body attitude rotation matrix (float).
bool ned_initialized_f
True if local float coordinate frame is initialsed.
#define VECT3_DIFF(_c, _a, _b)
#define RATES_ASSIGN(_ra, _p, _q, _r)
#define FLOAT_RATES_ZERO(_r)
static void stateSetNedToBodyQuat_f(struct FloatQuat *ned_to_body_quat)
Set vehicle body attitude from quaternion (float).
Integrated Navigation System interface.
#define VECT3_SUM(_c, _a, _b)
position in UTM coordinates Units: meters
float mh
Tuning parameter of baro error on vertical speed.
Invariant filter command vector.
vector in Latitude, Longitude and Altitude
#define GPS_FIX_3D
3D GPS fix
void ltp_def_from_lla_i(struct LtpDef_i *def, struct LlaCoor_i *lla)
#define RATES_DIFF(_c, _a, _b)
void ins_float_invariant_update_gps(struct GpsState *gps_s)
float baro_alt
Measured barometric altitude.
void ins_reset_altitude_ref(void)
INS altitude reference reset.
int32_t hmsl
Height above mean sea level in mm.
struct FloatVect3 LE
Correction gains on attitude.
int32_t alt
in millimeters above WGS84 reference ellipsoid
static void error_output(struct InsFloatInv *_ins)
Compute correction vectors E = ( ลท - y ) LE, ME, NE, OE : ( gain matrix * error ) ...
struct OrientationReps body_to_imu
body_to_imu rotation
float ob
Tuning parameter of mag error on gyro biases.
static void stateSetPositionUtm_f(struct UtmCoor_f *utm_pos)
Set position from UTM coordinates (float).
#define FLOAT_VECT3_ZERO(_v)
static void stateSetSpeedNed_f(struct NedCoor_f *ned_speed)
Set ground speed in local NED coordinates (float).
float mvz
Tuning parameter of vertical speed error on speed.
int32_t hmsl
height above mean sea level (MSL) in mm
void float_rmat_transp_vmult(struct FloatVect3 *vb, struct FloatRMat *m_b2a, struct FloatVect3 *va)
rotate 3D vector by transposed rotation matrix.
vector in North East Down coordinates Units: meters
Paparazzi floating point algebra.
data structure for GPS information
float NE
Correction gains on accel bias.
static void invariant_model(float *o, const float *x, const int n, const float *u, const int m)
Compute dynamic mode.
#define INT32_POS_OF_CM_NUM
static void stateSetLocalOrigin_i(struct LtpDef_i *ltp_def)
Set the local (flat earth) coordinate frame origin (int).
Device independent GPS code (interface)
Paparazzi atmospheric pressure conversion utilities.
#define FLOAT_QUAT_NORM2(_q)
static void init_invariant_state(void)
struct inv_state state
state vector
static void float_vect_zero(float *a, const int n)
a = 0
struct EcefCoor_i ecef_pos
position in ECEF in cm
static void send_inv_filter(struct transport_tx *trans, struct link_device *dev)
#define QUAT_ASSIGN(_q, _i, _x, _y, _z)
struct FloatRates rates
Input gyro rates.
void float_quat_vmul_right(struct FloatQuat *mright, const struct FloatQuat *q, struct FloatVect3 *vi)
Right multiplication by a quaternion.
float lb
Tuning parameter of mag error on attitude.
struct LlaCoor_i lla
Reference point in lla.
#define DefaultPeriodic
Set default periodic telemetry.
int32_t lon
in degrees*1e7
void float_quat_vmult(struct FloatVect3 *v_out, struct FloatQuat *q, const struct FloatVect3 *v_in)
rotate 3D vector by quaternion.
static void float_quat_normalize(struct FloatQuat *q)
static void float_quat_invert(struct FloatQuat *qo, struct FloatQuat *qi)
struct inv_gains gains
tuning gains
float lv
Tuning parameter of speed error on attitude.
uint8_t zone
UTM zone number.
static void stateSetPositionNed_f(struct NedCoor_f *ned_pos)
Set position from local NED coordinates (float).
struct UtmCoor_f utm_origin_f
Definition of the origin of Utm coordinate system.
struct FloatVect3 mag
Measured magnetic field.
struct FloatRates bias
Estimated gyro biases.
void float_quat_derivative(struct FloatQuat *qd, struct FloatRates *r, struct FloatQuat *q)
Quaternion derivative from rotational velocity.
Utility functions for fixed point AHRS implementations.
static const struct usb_device_descriptor dev
struct LtpDef_i ned_origin_i
Definition of the local (flat earth) coordinate system.
#define DefaultChannel
SITL.
void ins_float_invariant_update_baro(float pressure)
static void ahrs_float_get_quat_from_accel_mag(struct FloatQuat *q, struct FloatVect3 *accel, struct FloatVect3 *mag)
#define VECT3_SMUL(_vo, _vi, _s)
void ins_float_inv_set_body_to_imu_quat(struct FloatQuat *q_b2i)
#define FLOAT_QUAT_EXTRACT(_vo, _qi)
#define INT32_POS_OF_CM_DEN
struct inv_measures meas
measurement vector
struct UtmCoor_f utm_float_from_gps(struct GpsState *gps_s, uint8_t zone)
Convenience functions to get utm position from GPS state.
API to get/set the generic vehicle states.
void float_rmat_transp_ratemult(struct FloatRates *rb, struct FloatRMat *m_b2a, struct FloatRates *ra)
rotate anglular rates by transposed rotation matrix.
void ned_of_ecef_point_i(struct NedCoor_i *ned, struct LtpDef_i *def, struct EcefCoor_i *ecef)
Convert a point from ECEF to local NED.
vector in North East Down coordinates
float sh
Tuning parameter of baro error on baro bias.
float nh
Tuning parameter of baro error on vertical position.
struct NedCoor_f speed
Estimates speed.
float SE
Correction gains on barometer bias.
void ecef_of_lla_i(struct EcefCoor_i *out, struct LlaCoor_i *in)
Convert a LLA to ECEF.
struct EcefCoor_i ecef_vel
speed ECEF in cm/s
float rv
Tuning parameter of speed error on accel biases.
INS using invariant filter.
void ins_float_invariant_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel, struct FloatVect3 *lp_mag)
float hb
Estimates barometers bias.
struct LlaCoor_i lla_pos
position in LLA (lat,lon: deg*1e7; alt: mm over ellipsoid)
static float pprz_isa_height_of_pressure(float pressure, float ref_p)
Get relative altitude from pressure (using simplified equation).
#define QUAT_ADD(_qo, _qi)
#define ECEF_FLOAT_OF_BFP(_o, _i)
Invariant filter structure.
void ins_reset_local_origin(void)
INS local origin reset.
Runge-Kutta library (float version)
Fixedwing Navigation library.
int32_t lat
in degrees*1e7
static void stateSetBodyRates_f(struct FloatRates *body_rate)
Set vehicle body angular rate (float).
struct NedCoor_f pos
Estimates position.
struct InsFloatInv ins_float_inv
void float_eulers_of_quat(struct FloatEulers *e, struct FloatQuat *q)
void ins_float_invariant_propagate(struct FloatRates *gyro, struct FloatVect3 *accel, float dt)
struct NedCoor_i ned_vel
speed NED in cm/s
static void stateSetAccelNed_f(struct NedCoor_f *ned_accel)
Set acceleration in NED coordinates (float).
static void stateSetLocalUtmOrigin_f(struct UtmCoor_f *utm_def)
Set the local (flat earth) coordinate frame origin from UTM (float).
struct GpsState gps
global GPS state
void ins_float_invariant_init(void)
float as
Estimated accelerometer sensitivity.
struct NedCoor_f pos_gps
Measured gps position.
float nx
Tuning parameter of horizontal position error on position.
void ltp_def_from_ecef_i(struct LtpDef_i *def, struct EcefCoor_i *ecef)
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Paparazzi fixed point algebra.
static void runge_kutta_4_float(float *xo, const float *x, const int n, const float *u, const int m, void(*f)(float *o, const float *x, const int n, const float *u, const int m), const float dt)
Fourth-Order Runge-Kutta.
struct inv_correction_gains corr
correction gains
bool ins_baro_initialized