|
Paparazzi UAS
v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
|
Go to the documentation of this file.
33 #include "generated/airframe.h"
39 #if SEND_INVARIANT_FILTER
64 #define AHRS_INV_LX 2. * (0.06 + 0.1)
68 #define AHRS_INV_LY 2. * (0.06 + 0.06)
72 #define AHRS_INV_LZ 2. * (0.1 + 0.06)
76 #define AHRS_INV_MX 2. * 0.05 * (0.06 + 0.1)
80 #define AHRS_INV_MY 2. * 0.05 * (0.06 + 0.06)
84 #define AHRS_INV_MZ 2. * 0.05 * (0.1 + 0.06)
88 #define AHRS_INV_N 0.25
92 #define AHRS_INV_O 0.5
101 #define B ahrs_float_inv.mag_h
107 static inline void invariant_model(
float *o,
const float *
x,
const int n,
const float *u,
const int m);
202 #if SEND_INVARIANT_FILTER
237 #define MAG_FROZEN_COUNT 30
244 if (last_mx == mag->
x) {
246 if (mag_frozen_count == 0) {
266 static inline void invariant_model(
float *o,
const float *x,
const int n,
const float *u,
267 const int m __attribute__((unused)))
270 #pragma GCC diagnostic push // require GCC 4.6
271 #pragma GCC diagnostic ignored "-Wcast-qual"
274 #pragma GCC diagnostic pop // require GCC 4.6
281 if (fabs(
s->as) < 0.1) {
311 memcpy(o, &s_dot, n *
sizeof(
float));
324 if (fabs(_ahrs->
state.
as) < 0.1) {
VIC slots used for the LPC2148 define name e g gps UART1_VIC_SLOT e g modem SPI1_VIC_SLOT SPI1 in mcu_periph spi_arch c or spi_slave_hs_arch c(and some others not using the SPI peripheral yet..) I2C0_VIC_SLOT 8 mcu_periph/i2c_arch.c I2C1_VIC_SLOT 9 mcu_periph/i2c_arch.c USB_VIC_SLOT 10 usb
struct FloatVect3 ME
Correction gains on gyro biases.
void ahrs_float_invariant_update_mag(struct FloatVect3 *mag)
void ahrs_float_inv_set_body_to_imu_quat(struct FloatQuat *q_b2i)
void float_quat_vmul_right(struct FloatQuat *mright, const struct FloatQuat *q, struct FloatVect3 *vi)
Right multiplication by a quaternion.
static const struct FloatVect3 A
#define VECT3_SMUL(_vo, _vi, _s)
struct inv_gains gains
tuning gains
static void float_quat_identity(struct FloatQuat *q)
initialises a quaternion to identity
void ahrs_float_invariant_propagate(struct FloatRates *gyro, float dt)
struct VehicleInterface vi
#define FLOAT_RATES_ZERO(_r)
struct FloatRates rates
Input gyro rates.
#define VECT3_CROSS_PRODUCT(_vo, _v1, _v2)
#define VECT3_DIFF(_c, _a, _b)
#define VECT3_DOT_PRODUCT(_v1, _v2)
struct FloatVect3 accel
Measured accelerometers.
Paparazzi floating point algebra.
struct FloatRates bias
Estimated gyro biases.
#define VECT3_ADD(_a, _b)
static void error_output(struct AhrsFloatInv *_ins)
Compute correction vectors E = ( ŷ - y ) LE, ME, NE, OE : ( gain matrix * error )
Runge-Kutta library (float version)
static struct FloatRMat * orientationGetRMat_f(struct OrientationReps *orientation)
Get vehicle body attitude rotation matrix (float).
Paparazzi fixed point algebra.
void ahrs_float_invariant_update_accel(struct FloatVect3 *accel)
float ly
Tuning parameter of accel and mag on attitude (lateral subsystem)
static void init_invariant_state(void)
void float_rmat_transp_vmult(struct FloatVect3 *vb, struct FloatRMat *m_b2a, struct FloatVect3 *va)
rotate 3D vector by transposed rotation matrix.
#define RATES_ASSIGN(_ra, _p, _q, _r)
#define INV_STATE_DIM
Invariant filter state dimension.
float lx
Tuning parameter of accel and mag on attitude (longitudinal subsystem)
struct inv_state state
state vector
#define RATES_DIFF(_c, _a, _b)
#define FLOAT_VECT3_ZERO(_v)
static void orientationSetQuat_f(struct OrientationReps *orientation, struct FloatQuat *quat)
Set vehicle body attitude from quaternion (float).
float n
Tuning parameter of accel and mag on accel bias (scaling subsystem)
static void float_vect_zero(float *a, const int n)
a = 0
bool reset
flag to request reset/reinit the filter
float my
Tuning parameter of accel and mag on gyro bias (lateral subsystem)
static void float_quat_normalize(struct FloatQuat *q)
static void float_quat_invert(struct FloatQuat *qo, struct FloatQuat *qi)
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.
#define FLOAT_QUAT_NORM2(_q)
float NE
Correction gains on accel bias.
uint16_t f
Camera baseline, in meters (i.e. horizontal distance between the two cameras of the stereo setup)
void float_quat_vmult(struct FloatVect3 *v_out, struct FloatQuat *q, const struct FloatVect3 *v_in)
rotate 3D vector by quaternion.
struct OrientationReps body_to_imu
body_to_imu rotation
#define QUAT_SMUL(_qo, _qi, _s)
Invariant filter command vector.
float OE
Correction gains on magnetometer sensitivity.
#define INV_COMMAND_DIM
Invariant filter command vector dimension.
struct FloatVect3 LE
Correction gains on attitude.
void float_quat_derivative(struct FloatQuat *qd, struct FloatRates *r, struct FloatQuat *q)
Quaternion derivative from rotational velocity.
#define QUAT_ADD(_qo, _qi)
static void invariant_model(float *o, const float *x, const int n, const float *u, const int m)
Compute dynamic mode.
float o
Tuning parameter of accel and mag on mag bias (scaling subsystem)
#define QUAT_ASSIGN(_q, _i, _x, _y, _z)
float mx
Tuning parameter of accel and mag on gyro bias (longitudinal subsystem)
#define FLOAT_QUAT_EXTRACT(_vo, _qi)
struct AhrsFloatInv ahrs_float_inv
void float_rmat_transp_ratemult(struct FloatRates *rb, struct FloatRMat *m_b2a, struct FloatRates *ra)
rotate anglular rates by transposed rotation matrix.
float cs
Estimates magnetometer sensitivity.
float as
Estimated accelerometer sensitivity.
static void ahrs_float_get_quat_from_accel_mag(struct FloatQuat *q, struct FloatVect3 *accel, struct FloatVect3 *mag)
struct inv_command cmd
command vector
struct FloatVect3 mag
Measured magnetic field.
struct inv_measures meas
measurement vector
void float_eulers_of_quat(struct FloatEulers *e, struct FloatQuat *q)
euler rotation 'ZYX'
Invariant filter structure.
float lz
Tuning parameter of accel and mag on attitude (heading subsystem)
void ahrs_float_invariant_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel, struct FloatVect3 *lp_mag)
void ahrs_float_invariant_init(void)
float mz
Tuning parameter of accel and mag on gyro bias (heading subsystem)
struct inv_correction_gains corr
correction gains
struct FloatQuat quat
Estimated attitude (quaternion)