Paparazzi UAS v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
ins_flow.c
Go to the documentation of this file.
1/*
2 * Copyright (C) 2021 Guido de Croon <g.c.h.e.decroon@tudelft.nl>
3 *
4 * This file is part of paparazzi.
5 *
6 * paparazzi is free software; you can redistribute it and/or modify
7 * it under the terms of the GNU General Public License as published by
8 * the Free Software Foundation; either version 2, or (at your option)
9 * any later version.
10 *
11 * paparazzi is distributed in the hope that it will be useful,
12 * but WITHOUT ANY WARRANTY; without even the implied warranty of
13 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 * GNU General Public License for more details.
15 *
16 * You should have received a copy of the GNU General Public License
17 * along with paparazzi; see the file COPYING. If not, write to
18 * the Free Software Foundation, 59 Temple Place - Suite 330,
19 * Boston, MA 02111-1307, USA.
20 */
21
36#include "ins_flow.h"
37#include "modules/core/abi.h"
38#include "generated/airframe.h"
39#include "mcu_periph/sys_time.h"
40#include "autopilot.h"
42#include "generated/airframe.h"
43#include "generated/flight_plan.h"
44#include "mcu_periph/sys_time.h"
46#include "stabilization.h"
47#include <stdio.h>
48
49#define DEBUG_INS_FLOW 0
50#if DEBUG_INS_FLOW
51#include <stdio.h>
53#define DEBUG_PRINT printf
54#define DEBUG_MAT_PRINT MAT_PRINT
55//#define DEBUG_MAT_PRINT(...)
56#else
57#define DEBUG_PRINT(...)
58#define DEBUG_MAT_PRINT(...)
59#endif
60
61#ifndef AHRS_ICQ_OUTPUT_ENABLED
62#define AHRS_ICQ_OUTPUT_ENABLED TRUE
63#endif
65
66/* default Gyro to use in INS */
67#ifndef INS_FLOW_GYRO_ID
68#define INS_FLOW_GYRO_ID ABI_BROADCAST
69#endif
71
72/* default Accelerometer to use in INS */
73#ifndef INS_FLOW_ACCEL_ID
74#define INS_FLOW_ACCEL_ID ABI_BROADCAST
75#endif
77
78/* default IMU lowpass to use in INS */
79#ifndef INS_FLOW_IMU_ID
80#define INS_FLOW_IMU_ID ABI_BROADCAST
81#endif
83
84
85/* default GPS to use in INS */
86#ifndef INS_FLOW_GPS_ID
87#define INS_FLOW_GPS_ID GPS_MULTI_ID
88#endif
90
91/* Use optical flow estimates */
92#ifndef INS_OPTICAL_FLOW_ID
93#define INS_OPTICAL_FLOW_ID ABI_BROADCAST
94#endif
96
97// reading RPMs:
98#ifndef INS_RPM_ID
99#define INS_RPM_ID ABI_BROADCAST
100#endif
102
103/* All registered ABI events */
111
112/* All ABI callbacks */
117 int32_t flow_y, int32_t flow_der_x, int32_t flow_der_y, float quality, float size_divergence);
120 uint32_t stamp __attribute__((unused)),
121 struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel,
122 struct Int32Vect3 *lp_mag);
124
126static void print_true_state(void);
127/* Static local functions */
131static void ins_reset_filter(void);
132
133struct InsFlow {
134
135 // data elements for gps passthrough:
138
139 /* output LTP NED */
140 struct NedCoor_i ltp_pos;
141 struct NedCoor_i ltp_speed;
142 struct NedCoor_i ltp_accel;
143
144 // vision measurements:
148 float vision_time; // perhaps better to use microseconds (us) instead of float in seconds
150
151 // RPMs:
152 uint16_t RPM[8]; // max an octocopter
154
156 float lp_gyro_bias_pitch; // determine the bias before take-off
158 float lp_gyro_bias_roll; // determine the bias before take-off
159 float thrust_factor; // determine the additional required scale factor to have unbiased thrust estimates
162
163};
165
166// Kalman filter parameters and variables:
167
168#define MOMENT_DELAY 20
169float moments[MOMENT_DELAY] = {0.};
171
172float OF_X[N_STATES_OF_KF] = {0.};
176
177#define OF_N_ROTORS 4
179
189
190float GT_phi;
192
193
194#define USE_STANDARD_PARAMS 0
195
196#if USE_STANDARD_PARAMS
197// Note that not all of the values are used.
198// Moment of Inertia, mass, distance motors from center of gravity, 4 params for thrust and moment generation,
199// measurement noise R (2), actuation noise Q(5),
200// initial P (5), linear drag factor
201#if USE_NPS
202float parameters[20] = {0.0018244, 0.400, 0.085, 0.152163; 0.170734; 0.103436; 0.122109,
203 0.1, 0.1, 0.1, 1.0f * M_PI / 180.0f, 100.0f * M_PI / 180.0f, 0.1f, 3.0f,
204 1.0f, 10.0f * M_PI / 180.0f, 10.0f * M_PI / 180.0f, 1.0f, 1.0f, 0.5f
205 };
206#else
207float parameters[20] = {0.0018244, 0.400, 0.085, 0.108068 0.115448 0.201207 0.208834,
208 0.1, 0.1, 0.1, 1.0f * M_PI / 180.0f, 100.0f * M_PI / 180.0f, 0.1f, 3.0f,
209 1.0f, 10.0f * M_PI / 180.0f, 10.0f * M_PI / 180.0f, 1.0f, 1.0f, 0.5f
210 };
211#endif
212#else
213// Define parameters for the filter, fitted in MATLAB:
214#if USE_NPS
215#if N_MEAS_OF_KF == 3
216// with rate measurement:
217float parameters[20] = {1.234994e-01, 3.603662e-01, 8.751691e-02, 1.636867e-01, 1.561769e-01, 1.856140e-01, 1.601066e-02, 1.187989e-01, 1.507075e-01, 2.471644e-01, 7.934140e-02, 1.770048e+00, 1.345862e-01, 2.881410e+00, 1.003584e+00, 1.280523e-01, 7.549402e-02, 9.640423e-01, 1.078312e+00, 3.468849e-01};
218#else
219// without rate state / measurement:
220#if CONSTANT_ALT_FILTER
221#if OF_DRAG
222float parameters[20] = {1.396428e-01, 2.517970e-01, 3.575834e-02, 2.626194e-01, 1.078661e-01, 3.126137e-01, 4.621823e-02, 3.258048e-01, 8.456147e-02, 2.275105e-01, 2.820394e-02, 1.937395e+00, -4.259889e-02, 2.755648e+00, 1.000810e+00, -3.474577e-03, 3.146387e-01, 8.809383e-01, 9.878757e-01, 6.741976e-01};
223#else
224float parameters[20] = {3.363769e-01, 4.917425e-01, 1.903805e-01, 2.945672e-01, 1.258647e-01, 1.513736e-01, 5.894541e-01, 2.162745e-01, 5.527361e-01, 1.385623e-01, 8.307731e-01, 1.488212e+00, 2.439721e-01, 3.052758e+00, 8.246426e-01, 9.988101e-02, 1.247046e-01, 8.834364e-01, 7.971876e-01, 1.112319e+00};
225#endif
226#else
227float parameters[20] = {4.370754e-02, 3.770587e-01, 1.187542e-01, 1.174995e-01, 1.419432e-01, 6.950201e-02, 2.251078e-01, 9.113943e-02, 2.230198e-01, 5.767389e-02, 1.855676e-02, 1.676359e+00, 5.822681e-02, 2.869468e+00, 1.140625e+00, 6.831383e-02, 1.600776e-01, 9.853843e-01, 1.000381e+00, 5.081224e-01};
228#endif
229#endif
230#else
231// TODO: train constant alt filter without drag, also with and without measuring the gyro.
232#if CONSTANT_ALT_FILTER
233#if OF_DRAG
234// float parameters[20] = {1.557784e-01, 3.186275e-01, 8.341852e-02, 9.320449e-02, 1.706694e-01, 3.950497e-01, 3.338107e-01, 1.947852e-01, 2.429782e-01, 1.216562e-01, 2.885142e-01, 1.765480e+00, 2.427392e-01, 3.014556e+00, 1.004227e+00, 1.798174e-01, 2.821081e-01, 9.314043e-01, 1.005090e+00, 2.630276e-01};
235float parameters[20] = {8.407886e-03, 4.056093e-01, 1.555919e-01, 1.291584e-01, 2.594766e-01, 1.927331e-01, 9.599609e-02, 1.688265e-01, 5.589618e-02, 1.605665e-01, 1.195912e-01, 1.809532e+00, 4.268251e-02, 3.003060e+00, 1.098473e+00, 1.944433e-01, 2.363352e-01, 1.110390e+00, 1.190994e+00, 6.211962e-01};
236#endif
237#else
238#if N_MEAS_OF_KF == 3
239#if PREDICT_GYROS == 0
240// with rate measurement (last two values copied from the last condition)
241float parameters[22] = {0.041001, 1.015066, -0.058495, 0.498353, -0.156362, 0.383511, 0.924635, 0.681918, 0.318947, 0.298235, 0.224906, 1.371037, 0.008888, 3.045428, 0.893953, 0.529789, 0.295028, 1.297515, 0.767550, 0.334040, 0.192238, 0.301966};
242#else
243// Estimate gyro directly instead of moment:
244float parameters[26] = {1.065019, 0.270407, 0.164520, 0.008321, 0.083628, 0.261853, 0.210707, 0.204501, 0.164267, 0.097979, 0.053705, 1.640180, 0.151171, 3.086366, 1.025684, 0.011813, 0.177164, 0.995710, 1.050374, 0.617920, 0.028360, 0.447258, 0.077277, 0.360559, 0.555940, 0.133979};
245#endif
246#else
247// without rate measurement:
248// float parameters[20] = {4.098677e-01, 7.766318e-01, 3.614751e-01, 4.745865e-01, 5.144065e-01, 3.113647e-01, -8.737287e-03, 6.370274e-01, 3.863760e-01, -3.527670e-01, 4.873666e-01, 1.688456e+00, -6.037967e-02, 2.759148e+00, 1.385455e+00, 1.044881e-01, -1.170409e-01, 1.126136e+00, 1.097562e+00, 2.680243e-01};
249float parameters[22] = {0.219033, 0.376572, 0.184002, 0.096388, 0.240843, 0.172390, 0.133111, 0.495885, 0.357086, 0.233624, 0.125611, 1.661682, 0.136735, 2.812652, 0.715887, 0.166932, 0.371409, 1.043920, 0.840683, 0.567703, 0.192238, 0.301966};
250#endif
251#endif
252#endif
253#endif
254// parameter indices (TODO: how important are these numbers? Some are not used, others, like P may be not so important).
255#define PAR_IX 0
256#define PAR_MASS 1
257#define PAR_BASE 2
258#define PAR_K0 3
259#define PAR_K1 4
260#define PAR_K2 5
261#define PAR_K3 6
262#define PAR_R0 7
263#define PAR_R1 8
264#define PAR_Q0 9
265#define PAR_Q1 10
266#define PAR_Q2 11
267#define PAR_Q3 12
268#define PAR_Q4 13
269#define PAR_P0 14
270#define PAR_P1 15
271#define PAR_P2 16
272#define PAR_P3 17
273#define PAR_P4 18
274#define PAR_KD 19
275#define PAR_Q_TB 20
276#define PAR_P_TB 21
277#define PAR_PRED_ROLL_1 22
278#define PAR_PRED_ROLL_2 23
279#define PAR_PRED_ROLL_3 24
280
281
282
283/*
284struct InsFlowState {
285 // vector representation of state:
286 // v, angle, angle_dot, z, z_dot
287
288
289};
290struct InsFlowState ins_flow_state;
291*/
292
293#if PERIODIC_TELEMETRY
295#include "mcu_periph/sys_time.h"
296#include "state.h"
297
298// attitude part:
299static void send_quat(struct transport_tx *trans, struct link_device *dev)
300{
301 struct Int32Quat *quat = stateGetNedToBodyQuat_i();
308 &(quat->qi),
309 &(quat->qx),
310 &(quat->qy),
311 &(quat->qz),
312 &ahrs_flow_id);
313}
314
315static void send_euler(struct transport_tx *trans, struct link_device *dev)
316{
319 struct Int32Eulers *eulers = stateGetNedToBodyEulers_i();
321 &ltp_to_imu_euler.phi,
322 &ltp_to_imu_euler.theta,
323 &ltp_to_imu_euler.psi,
324 &(eulers->phi),
325 &(eulers->theta),
326 &(eulers->psi),
327 &ahrs_flow_id);
328
329}
330
337
347
348static void send_filter_status(struct transport_tx *trans, struct link_device *dev)
349{
350 uint8_t mde = 3;
351 uint16_t val = 0;
352 if (!ahrs_icq.is_aligned) { mde = 2; }
354 /* set lost if no new gyro measurements for 50ms */
355 if (t_diff > 50000) { mde = 5; }
357}
358
359// ins part
367
368/*static void send_ins_z(struct transport_tx *trans, struct link_device *dev)
369{
370 static float fake_baro_z = 0.0;
371 pprz_msg_send_INS_Z(trans, dev, AC_ID,
372 (float *)&fake_baro_z, &ins_flow.ltp_pos.z,
373 &ins_flow.ltp_speed.z, &ins_flow.ltp_accel.z);
374}*/
375
376static void send_ins_ref(struct transport_tx *trans, struct link_device *dev)
377{
378 static float fake_qfe = 0.0;
383 &ins_flow.ltp_def.hmsl, (float *)&fake_qfe);
384 }
385}
386
387
388#endif
389
390static void send_ins_flow(struct transport_tx *trans, struct link_device *dev)
391{
392 // TODO: add sending of theta:
393 struct FloatEulers *eulers = stateGetNedToBodyEulers_f();
394 struct NedCoor_f *position = stateGetPositionNed_f();
396 struct FloatRates *rates = stateGetBodyRates_f();
397
398 float phi = (180.0 / M_PI) * OF_X[OF_ANGLE_IND];
399 float theta;
400 if (OF_TWO_DIM) {
401 theta = (180.0 / M_PI) * OF_X[OF_THETA_IND];
402 } else {
403 // if not filtering the second dimension, just take the ground truth
404 theta = (180.0 / M_PI) * eulers->theta;
405 }
406
407 float phi_dot = 0.0f;
408 float z_dot = 0.0f;
409 if (!CONSTANT_ALT_FILTER) {
410 phi_dot = (180.0 / M_PI) * OF_X[OF_ANGLE_DOT_IND];
412 }
413
420
421 float vy_GT = body_velocities.y;
422
423 float phi_GT;
424 if (use_filter < USE_ANGLE) {
425 phi_GT = (180.0 / M_PI) * eulers->phi;
426 } else {
427 phi_GT = (180.0 / M_PI) * GT_phi;
428 }
429 float vx_GT = body_velocities.x;
430 float theta_GT;
431 if (use_filter < USE_ANGLE) {
432 theta_GT = (180.0 / M_PI) * eulers->theta;
433 } else if (OF_TWO_DIM) {
434 theta_GT = (180.0 / M_PI) * GT_theta;
435 }
436 float p_GT = rates->p;
437 float q_GT = rates->q;
438 float z_GT = -position->z;
439 float vz_GT = -velocities->z;
440
441 float vy = OF_X[OF_V_IND];
442 float vx;
443 if (OF_TWO_DIM) {
444 vx = OF_X[OF_VX_IND];
445 } else {
446 vx = vx_GT;
447 }
448 float z = OF_X[OF_Z_IND];
449 float p, q;
450 if (!CONSTANT_ALT_FILTER) {
451 // normally:
452 p = phi_dot;
453 // when estimating the gyros:
454 // // p = -1.8457e-04 * (stabilization.cmd[COMMAND_ROLL]-ins_flow.lp_roll_command);
455 // p = -2.0e-03 * (stabilization.cmd[COMMAND_ROLL]-ins_flow.lp_roll_command);
456 // TODO: expand the full filter later as well, to include q:
457 q = q_GT;
458 } else {
460 // p = -2.0e-03 * (stabilization.cmd[COMMAND_ROLL]-ins_flow.lp_roll_command);
462 }
463
464 float thrust_bias;
466 thrust_bias = 0.0f;
467 } else {
469 }
470 // This code is to actually compare the unbiased thrust with gravity:
471 // TODO: code copied from below, put in a function?
472 float thrust = 0.0f;
473 for (int i = 0; i < OF_N_ROTORS; i++) {
474 thrust += RPM_FACTORS[i] * ins_flow.RPM[i] * ins_flow.RPM[i];
475 }
476 thrust *= thrust_factor; // ins_flow.thrust_factor;
477 thrust -= thrust_bias;
478 float mass = parameters[PAR_MASS];
479 float g = 9.81;
480 float actual_lp_thrust = mass * g;
481 thrust_bias = thrust - actual_lp_thrust;
482
484 &vy, &phi, &p, &vx, &theta, &q, &z, &z_dot,
485 &vy_GT, &phi_GT, &p_GT, &vx_GT, &theta_GT, &q_GT,
487}
488
490{
491
492 // (re-)initialize the state:
493 for (int i = 0; i < N_STATES_OF_KF; i++) {
494 OF_X[i] = 0.0f;
495 }
496 OF_X[OF_Z_IND] = 1.0; // nonzero z
497
498 // P-matrix:
499 for (int i = 0; i < N_STATES_OF_KF; i++) {
500 for (int j = 0; j < N_STATES_OF_KF; j++) {
501 OF_P[i][j] = 0.0f;
502 }
503 }
504 if (CONSTANT_ALT_FILTER == 1) {
509 if (OF_TWO_DIM) {
512 }
513 } else {
519 if (OF_THRUST_BIAS) {
521 }
522 }
523
524 counter = 0;
525
526 // TODO: what to do with thrust, gyro bias, and low-passed roll command?
527
528}
529
530
531/* Initialize the flow ins */
533{
534
536
537 struct LlaCoor_i llh_nav0; /* Height above the ellipsoid */
539 llh_nav0.lon = NAV_LON0;
540 /* NAV_ALT0 = ground alt above msl, NAV_MSL0 = geoid-height (msl) over ellipsoid */
541 llh_nav0.alt = NAV_ALT0 + NAV_MSL0;
542 struct EcefCoor_i ecef_nav0;
544 struct LtpDef_i ltp_def;
546
552 ins_flow.lp_gyro_pitch = 0.0f;
554 ins_flow.lp_gyro_roll = 0.0f;
556 ins_flow.thrust_factor = 1.0f;
557 ins_flow.lp_thrust = 0.0f;
559
560 lp_factor = 0.95;
561 lp_factor_strong = 1 - 1E-3;
562
563 GT_phi = 0.0f;
564 GT_theta = 0.0f;
565
566 // Extended Kalman filter:
567 // reset the state and P matrix:
569
570 // R-matrix, measurement noise (TODO: make params)
573 if (OF_TWO_DIM) {
575 } else if (N_MEAS_OF_KF == 3) {
576 OF_R[OF_RATE_IND][OF_RATE_IND] = 1.0 * (M_PI / 180.0f); // not a param yet, used to be 10, but we could trust it more
577 }
578 // Q-matrix, actuation noise (TODO: make params)
583 if (!CONSTANT_ALT_FILTER) {
585 } else if (OF_TWO_DIM) {
588 }
589 if (OF_THRUST_BIAS) {
591 }
592
593
594 // based on a fit, factor * rpm^2:
595 // TODO: with the parameters, we don't need this if / else any more.
596#if USE_NPS
597 // K = [0.152163; 0.170734; 0.103436; 0.122109] * 1E-7;
598 // K = [0.222949; 0.160458; 0.114227; 0.051396] * 1E-7;
599 // rpm:
600 // [2708.807954; 2587.641476; -379.728916; -501.203388]
601 RPM_FACTORS[0] = parameters[PAR_K0] * 1E-7;
602 RPM_FACTORS[1] = parameters[PAR_K1] * 1E-7;
603 RPM_FACTORS[2] = parameters[PAR_K2] * 1E-7;
604 RPM_FACTORS[3] = parameters[PAR_K3] * 1E-7;
605#else
606 // % Bebop 2, #45
607 // From fit_TM_2 script:
608 // K = [0.108068; 0.115448; 0.201207; 0.208834] * 1E-7
609 RPM_FACTORS[0] = parameters[PAR_K0] * 1E-7;
610 RPM_FACTORS[1] = parameters[PAR_K1] * 1E-7;
611 RPM_FACTORS[2] = parameters[PAR_K2] * 1E-7;
612 RPM_FACTORS[3] = parameters[PAR_K3] * 1E-7;
613#endif
614
615 reset_filter = false;
616 use_filter = 0;
617 run_filter = false;
618
621
622 // align the AHRS:
624 // set the initial attitude:
626
627#if PERIODIC_TELEMETRY
634 //register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_INS_Z, send_ins_z);
636#endif
637
638 /*
639 * Subscribe to scaled IMU measurements and attach callbacks
640 */
641// TODO: warning: passing argument 3 of ‘AbiBindMsgIMU_GYRO_INT’ from incompatible pointer type
649
650 // Telemetry:
652
653 moment_ind = 0;
654
655}
656
667
669 int32_t flow_y UNUSED,
670 int32_t flow_der_x UNUSED, int32_t flow_der_y UNUSED, float quality UNUSED, float size_divergence)
671{
672
673 // TODO: make parameters:
674 float subpixel_factor = 10.0f;
675 float focal_x = 347.22;
676 float new_time = ((float)stamp) / 1e6;
677 float fps = 1.0f / (new_time - ins_flow.vision_time);
678 ins_flow.optical_flow_x = (((float)flow_x) * fps) / (subpixel_factor * focal_x);
679 ins_flow.optical_flow_y = (((float)flow_y) * fps) / (subpixel_factor * focal_x);
680 ins_flow.divergence = 1.27 * size_divergence * fps;
681 //printf("Reading %f, %f, %f\n", ins_flow.optical_flow_x, ins_flow.optical_flow_y, ins_flow.divergence);
684
685}
686
688{
690 if (!OF_TWO_DIM) {
691 printf("v = %f, angle = %f, angle_dot = %f, z = %f.\n",
693 } else {
694 printf("v = %f, angle = %f, angle_dot = %f, z = %f, vx = %f, theta = %f.\n",
696 }
697
698 } else {
699 if (!OF_THRUST_BIAS) {
700 printf("v = %f, angle = %f, angle_dot = %f, z = %f, z_dot = %f.\n",
702 } else {
703 printf("v = %f, angle = %f, angle_dot = %f, z = %f, z_dot = %f, thrust bias = %f.\n",
706 }
707
708 }
709
710}
711
713{
714 // TODO: rotate velocities to body frame:
715 // TODO: add also the theta axis:
716 struct FloatEulers *eulers = stateGetNedToBodyEulers_f();
717 struct NedCoor_f *position = stateGetPositionNed_f();
719 struct FloatRates *rates = stateGetBodyRates_f();
720
721 printf("True: v = %f, angle = %f, angle_dot = %f, z = %f, z_dot = %f.\n",
722 velocities->y, eulers->phi, rates->p, -position->z, -velocities->z);
723}
724
726{
727 float mass = parameters[PAR_MASS]; // 0.400;
728 float moment = 0.0f; // for now assumed to be 0
729 float Ix = parameters[PAR_IX]; // 0.0018244;
730 //float b = parameters[PAR_BASE];
731 float g = 9.81; // TODO: get a more accurate definition from pprz
732 float kd = parameters[PAR_KD]; // 0.5
733 float drag = 0.0f;
734
735 if (reset_filter) {
737 reset_filter = false;
738 }
739
740 // get ground truth data:
741 //struct FloatEulers* eulers = stateGetNedToBodyEulers_f();
742 //struct NedCoor_f* position = stateGetPositionNed_f();
743 //struct NedCoor_f *velocities = stateGetSpeedNed_f();
744 //struct FloatRates *rates = stateGetBodyRates_f();
745
746 // TODO: record when starting from the ground: does that screw up the filter? Yes it does : )
747
748
749 // assuming that the typical case is no rotation, we can estimate the (initial) bias of the gyro:
752 if (OF_TWO_DIM) {
755 }
756 // same assumption for the roll command: assuming a close-to-hover situation and roll trim for staying in place:
759
760 // only start estimation when flying (and above 1 meter: || position->z > -1.0f )
761 // I removed the condition on height, since (1) we need to start the filter anyway explicitly now, and (2) it created a dependence on GPS fix.
762 if (!autopilot_in_flight()) {
763 return;
764 }
765
766 if (!run_filter) {
767
768 // TODO: should we do this if we have a thrust bias?
769
770 // Drone is flying but not yet running the filter, in order to obtain unbiased thrust estimates we estimate an additional factor.
771 // Assumption is that the drone is hovering, which means that over a longer period of time, the thrust should equal gravity.
772 // If the low pass thrust is lower than the one expected by gravity, then it needs to be increased and viceversa.
773 float thrust = 0.0f;
774 for (int i = 0; i < OF_N_ROTORS; i++) {
775 thrust += RPM_FACTORS[i] * ins_flow.RPM[i] * ins_flow.RPM[i];
776 }
777 if (ins_flow.lp_thrust < 1E-3) {
778 // first time directly initialize with thrust to get quicker convergence:
779 ins_flow.lp_thrust = thrust;
780 } else {
782 }
783 float actual_lp_thrust = mass * g;
786 //printf("Low pass predicted thrust = %f. Expected thrust = %f. Thrust factor = %f.\n", ins_flow.lp_thrust, actual_lp_thrust, ins_flow.thrust_factor);
787 // don't run the filter just yet:
788 return;
789 }
790
792
793 // in the sim, the gyro bias wanders so fast, that this does not seem to be useful:
794 // TODO: verify how this is in reality, and if not useful, remove all code to estimate this bias (or do it differently)
795 // ins_flow.lp_gyro_bias_roll = 0.0f;
796
797 // This module needs to run at the autopilot speed when not yet using this filter. Plus it needs to estimate thrust and gyro bias at that speed.
798 // However, the updates of the filter themselves should be slower:
799 /*counter++;
800 if(counter < 5) {
801 return;
802 }
803 else {
804 counter = 0;
805 }*/
806
807 // get the new time:
809 float dt = of_time - of_prev_time;
810 //printf("dt = %f.\n", dt);
811 if (dt > 1.0f) {
812 dt = 0.01f;
813 }
814
815 // predict the thrust and moment:
816 float thrust = 0.0f;
817 for (int i = 0; i < OF_N_ROTORS; i++) {
818 thrust += RPM_FACTORS[i] * ins_flow.RPM[i] * ins_flow.RPM[i];
819 }
820 thrust *= thrust_factor; // ins_flow.thrust_factor;
822 thrust -= OF_X[OF_THRUST_BIAS_IND];
823 }
824 DEBUG_PRINT("Thrust acceleration = %f, g = %f\n", thrust / mass, g);
825
826 // TODO: do we have an optimization that used the moment?
827 /*moment = b * RPM_FACTORS[0] * ins_flow.RPM[0]*ins_flow.RPM[0] -
828 b * RPM_FACTORS[1] * ins_flow.RPM[1]*ins_flow.RPM[1] -
829 b * RPM_FACTORS[2] * ins_flow.RPM[2]*ins_flow.RPM[2] +
830 b * RPM_FACTORS[3] * ins_flow.RPM[3]*ins_flow.RPM[3];*/
831 // M_est = Ix * (-0.000553060716181365 * cmd_roll(k) -3.23315441805895 * Xe(3, k));
832#if USE_NPS
833 // TODO: moment in simulation is very easy to estimate with the roll command, so add that:
834 moment = 0;
835#else
836
837 /*
838 moments[moment_ind] = Ix *(-0.000553060716181365 * (stabilization.cmd[COMMAND_ROLL]-ins_flow.lp_roll_command) -3.23315441805895 * OF_X[OF_ANGLE_DOT_IND]);
839
840 int select_ind = moment_ind - MOMENT_DELAY;
841 if(select_ind < 0) {
842 select_ind += MOMENT_DELAY;
843 }
844
845 // current moment is a delayed version:
846 moment = moments[select_ind];
847
848 // update the moment's ind:
849 moment_ind++;
850 if(moment_ind >= MOMENT_DELAY) {
851 moment_ind = 0;
852 }
853 */
854 // moment = Ix *(-0.000553060716181365 * (stabilization.cmd[COMMAND_ROLL]-ins_flow.lp_roll_command) -3.23315441805895 * OF_X[OF_ANGLE_DOT_IND]);
855 moment = 0;
856#endif
857
858 // printf("Predicted moment = %f, gyro = %f\n", moment, dt * (ins_flow.lp_gyro_roll - ins_flow.lp_gyro_bias_roll) * (M_PI/180.0f) / 74.0f);
859
860
861 // propagate the state with Euler integration:
862 DEBUG_PRINT("Before prediction: ");
865 OF_X[OF_V_IND] += dt * (g * tan(OF_X[OF_ANGLE_IND]));
866 if (OF_DRAG) {
867 // quadratic drag acceleration:
868 drag = dt * kd * (OF_X[OF_V_IND] * OF_X[OF_V_IND]) / mass;
869 // apply it in the right direction:
870 if (OF_X[OF_V_IND] > 0) { OF_X[OF_V_IND] -= drag; }
871 else { OF_X[OF_V_IND] += drag; }
872 }
873
874 /* // if we use gyros here, the angle dot estimate is ignored:
875 * if(OF_USE_GYROS) {
876 // OF_X[OF_ANGLE_IND] += dt * (ins_flow.lp_gyro_roll - ins_flow.lp_gyro_bias_roll) * (M_PI/180.0f) / 74.0f; // Code says scaled by 12, but... that does not fit...
877 } */
878
879 // temporary insertion of gyro estimate here, for quicker effect:
880 // OF_X[OF_ANGLE_IND] += dt * -2.0e-03 * (stabilization.cmd[COMMAND_ROLL]-ins_flow.lp_roll_command);
881
883 OF_X[OF_ANGLE_DOT_IND] += dt * (moment / Ix);
884
885 if (OF_TWO_DIM) {
886 // Second axis, decoupled formulation:
887 OF_X[OF_VX_IND] += dt * (g * tan(OF_X[OF_THETA_IND]));
888 if (OF_DRAG) {
889 // quadratic drag acceleration:
890 drag = dt * kd * (OF_X[OF_VX_IND] * OF_X[OF_VX_IND]) / mass;
891 // apply it in the right direction:
892 if (OF_X[OF_VX_IND] > 0) { OF_X[OF_VX_IND] -= drag; }
893 else { OF_X[OF_VX_IND] += drag; }
894 }
895 // TODO: here also a moment estimate?
896 // TODO: add a THETA_DOT_IND
898 (M_PI / 180.0f) / 74.0f; // Code says scaled by 12, but... that does not fit...
899 }
900
901 DEBUG_PRINT("Rate p = %f, gyro p = %f\n", rates->p,
902 (ins_flow.lp_gyro_roll - ins_flow.lp_gyro_bias_roll) * (M_PI / 180.0f) / 74.0f);
903 } else {
904 // make sure that the right hand state terms appear before they change:
905 OF_X[OF_V_IND] += dt * (thrust * sinf(OF_X[OF_ANGLE_IND]) / mass);
906 OF_X[OF_Z_IND] += dt * OF_X[OF_Z_DOT_IND];
907 OF_X[OF_Z_DOT_IND] += dt * (thrust * cosf(OF_X[OF_ANGLE_IND]) / mass - g);
909 /*
910 * // TODO: We now only keep this here because it worked on the real drone. It also worked without it. So to be deleted if it works as is.
911 else {
912 OF_X[OF_ANGLE_IND] += dt * (ins_flow.lp_gyro_roll - ins_flow.lp_gyro_bias_roll) * (M_PI/180.0f) / 74.0f;
913 }*/
914 OF_X[OF_ANGLE_DOT_IND] += dt * (moment / Ix);
915
916 // thrust bias does not change over time according to our model
917
918 if (OF_DRAG) {
919 // quadratic drag acceleration:
920 drag = dt * kd * (OF_X[OF_V_IND] * OF_X[OF_V_IND]) / mass;
921 // apply it in the right direction:
922 if (OF_X[OF_V_IND] > 0) { OF_X[OF_V_IND] -= drag; }
923 else { OF_X[OF_V_IND] += drag; }
924 }
925 }
926
927 // ensure that z is not 0 (or lower)
928 if (OF_X[OF_Z_IND] < 1e-2) {
929 OF_X[OF_Z_IND] = 1e-2;
930 }
931
932 DEBUG_PRINT("After prediction: ");
934
935 // prepare the update and correction step:
936 // we have to recompute these all the time, as they depend on the state:
937 // discrete version of state transition matrix F: (ignoring t^2)
938 float F[N_STATES_OF_KF][N_STATES_OF_KF] = {{0.}};
939 for (int i = 0; i < N_STATES_OF_KF; i++) {
940 F[i][i] = 1.0f;
941 }
942
945 F[OF_ANGLE_IND][OF_ANGLE_DOT_IND] = dt * 1.0f;
946 if (OF_TWO_DIM) {
948 }
949 } else {
950 F[OF_V_IND][OF_ANGLE_IND] = dt * (thrust * cosf(OF_X[OF_ANGLE_IND]) / mass);
951 F[OF_ANGLE_IND][OF_ANGLE_DOT_IND] = dt * 1.0f;
952 F[OF_Z_IND][OF_Z_DOT_IND] = dt * 1.0f;
953 F[OF_Z_DOT_IND][OF_ANGLE_IND] = dt * (-thrust * sinf(OF_X[OF_ANGLE_IND]) / mass);
954 if (OF_THRUST_BIAS) {
957 }
958 }
959
960 if (OF_DRAG) {
961 // In MATLAB: -sign(v)*2*kd*v/m (always minus, whether v is positive or negative):
962 F[OF_V_IND][OF_V_IND] -= dt * 2 * kd * fabs(OF_X[OF_V_IND]) / mass;
963 if (OF_TWO_DIM) {
964 F[OF_VX_IND][OF_VX_IND] -= dt * 2 * kd * fabs(OF_X[OF_VX_IND]) / mass;
965 }
966 }
967
968 // G matrix (whatever it may be):
969 float G[N_STATES_OF_KF][N_STATES_OF_KF] = {{0.}};
970 // TODO: we miss an off-diagonal element here (compare with MATLAB)
971 for (int i = 0; i < N_STATES_OF_KF; i++) {
972 G[i][i] = dt;
973 }
974
975 // Jacobian observation matrix H:
976 float H[N_MEAS_OF_KF][N_STATES_OF_KF] = {{0.}};
977
979 // Hx = [-cosf(theta)^2/z, (v*sinf(theta))/ z, (v* cosf(theta)^2)/z^2];
980 // lateral flow:
986 // divergence:
991
992 if (OF_TWO_DIM) {
993 // divergence measurement couples the two axes actually...:
996
997 // lateral flow in x direction:
1001 (OF_X[OF_Z_IND] * OF_X[OF_Z_IND]);
1002 }
1003 } else {
1004 // lateral flow:
1013 // divergence:
1021 }
1022
1023 // rate measurement:
1024 if (OF_USE_GYROS) {
1025 H[OF_RATE_IND][OF_V_IND] = 0.0f;
1026 H[OF_RATE_IND][OF_ANGLE_IND] = 0.0f;
1028 H[OF_RATE_IND][OF_Z_IND] = 0.0f;
1029 H[OF_RATE_IND][OF_Z_DOT_IND] = 0.0f;
1030 }
1031
1032 // propagate uncertainty:
1033 // TODO: make pointers that don't change to init:
1040
1041 DEBUG_PRINT("Phi:\n");
1043
1044 DEBUG_PRINT("P:\n");
1046
1047 DEBUG_PRINT("Gamma:\n");
1049
1050 DEBUG_PRINT("Q:\n");
1052
1053 DEBUG_PRINT("R:\n");
1055
1056 DEBUG_PRINT("Jacobian:\n");
1058
1059 // Corresponding MATLAB statement: :O
1060 // P_k1_k = Phi_k1_k*P*Phi_k1_k' + Gamma_k1_k*Q*Gamma_k1_k';
1067
1071
1072 DEBUG_PRINT("Phi*P*PhiT:\n");
1074
1081
1085
1086 DEBUG_PRINT("Gamma*Q*GammaT:\n");
1088
1090 DEBUG_PRINT("P:\n");
1092
1093 // correct state when there is a new vision measurement:
1095
1096 DEBUG_PRINT("*********************\n");
1097 DEBUG_PRINT(" NEW MEASUREMENT \n");
1098 DEBUG_PRINT("*********************\n");
1099
1100 // determine Kalman gain:
1101 // MATLAB statement:
1102 // S_k = Hx*P_k1_k*Hx' + R;
1109
1112 DEBUG_PRINT("P*JacT:\n");
1114
1116
1117 DEBUG_PRINT("Jac*P*JacT:\n");
1119
1123
1124 DEBUG_PRINT("S:\n");
1126
1127 // MATLAB statement:
1128 // K_k1 = P_k1_k*Hx' * inv(S_k);
1134 if (DEBUG_INS_FLOW) {
1135 // This should be the identity matrix:
1139 DEBUG_PRINT("S*Inv(S):\n");
1141 }
1142
1144 DEBUG_PRINT("K:\n");
1146
1147 // Correct the state:
1148 // MATLAB:
1149 // Z_expected = [-v*cosf(theta)*cosf(theta)/z + zd*sinf(2*theta)/(2*z) + thetad;
1150 // (-v*sinf(2*theta)/(2*z)) - zd*cosf(theta)*cosf(theta)/z];
1151
1152 float Z_expected[N_MEAS_OF_KF];
1153
1154 // TODO: take this var out? It was meant for debugging...
1155 //float Z_expect_GT_angle;
1156
1157 if (CONSTANT_ALT_FILTER) {
1159 + OF_X[OF_ANGLE_DOT_IND]; // TODO: Currently, no p works better than using p here. Analyze!
1160
1161
1162 /* TODO: remove later, just for debugging:
1163 float Z_exp_no_rate = -OF_X[OF_V_IND]*cosf(OF_X[OF_ANGLE_IND])*cosf(OF_X[OF_ANGLE_IND])/OF_X[OF_Z_IND];
1164 float Z_exp_with_rate = -OF_X[OF_V_IND]*cosf(OF_X[OF_ANGLE_IND])*cosf(OF_X[OF_ANGLE_IND])/OF_X[OF_Z_IND]+OF_X[OF_ANGLE_DOT_IND];
1165 printf("Z_exp_no_rate = %f, Z_exp_with_rate = %f, measured = %f, angle dot = %f, p = %f: ", Z_exp_no_rate, Z_exp_with_rate,
1166 ins_flow.optical_flow_x, OF_X[OF_ANGLE_DOT_IND], dt * (ins_flow.lp_gyro_roll - ins_flow.lp_gyro_bias_roll) * (M_PI/180.0f) / 74.0f);
1167 if(fabs(ins_flow.optical_flow_x - Z_exp_no_rate) < fabs(ins_flow.optical_flow_x - Z_exp_with_rate)) {
1168 printf("NO RATE WINS!");
1169 }
1170 printf("\n");*/
1171
1173
1174 if (OF_TWO_DIM) {
1176 OF_X[OF_Z_IND]; // TODO: no q?
1177 }
1178
1179 //Z_expect_GT_angle = -OF_X[OF_V_IND]*cosf(eulers->phi)*cosf(eulers->phi)/OF_X[OF_Z_IND];
1180
1181 if (OF_USE_GYROS) {
1182 Z_expected[OF_RATE_IND] = OF_X[OF_ANGLE_DOT_IND]; // TODO: is this even in the right direction?
1183 }
1184 } else {
1186 + OF_X[OF_Z_DOT_IND] * sinf(2 * OF_X[OF_ANGLE_IND]) / (2 * OF_X[OF_Z_IND])
1187 + OF_X[OF_ANGLE_DOT_IND]; // TODO: We first had this rate term but not for the constant alt filter.
1188 // Simulation and data analysis from real flights shows that including it is better. CHECK IN REALITY!
1189
1192
1193 //Z_expect_GT_angle = -OF_X[OF_V_IND]*cosf(eulers->phi)*cosf(eulers->phi)/OF_X[OF_Z_IND]
1194 // + OF_X[OF_Z_DOT_IND]*sinf(2*eulers->phi)/(2*OF_X[OF_Z_IND]);
1195 //+ OF_X[OF_ANGLE_DOT_IND];
1196 if (N_MEAS_OF_KF == 3) {
1197 Z_expected[OF_RATE_IND] = OF_X[OF_ANGLE_DOT_IND]; // TODO: is this even in the right direction?
1198 }
1199
1200 /*
1201 float Z_exp_no_rate = -OF_X[OF_V_IND]*cosf(OF_X[OF_ANGLE_IND])*cosf(OF_X[OF_ANGLE_IND])/OF_X[OF_Z_IND]
1202 + OF_X[OF_Z_DOT_IND]*sinf(2*OF_X[OF_ANGLE_IND])/(2*OF_X[OF_Z_IND]);
1203 float Z_exp_with_rate = -OF_X[OF_V_IND]*cosf(OF_X[OF_ANGLE_IND])*cosf(OF_X[OF_ANGLE_IND])/OF_X[OF_Z_IND]
1204 + OF_X[OF_Z_DOT_IND]*sinf(2*OF_X[OF_ANGLE_IND])/(2*OF_X[OF_Z_IND])
1205 + OF_X[OF_ANGLE_DOT_IND];
1206 */
1207 /*
1208 printf("Z_exp_no_rate = %f, Z_exp_with_rate = %f, measured = %f, angle dot = %f, p = %f: ", Z_exp_no_rate, Z_exp_with_rate,
1209 ins_flow.optical_flow_x, OF_X[OF_ANGLE_DOT_IND], dt * (ins_flow.lp_gyro_roll - ins_flow.lp_gyro_bias_roll) * (M_PI/180.0f) / 74.0f);
1210 if(fabs(ins_flow.optical_flow_x - Z_exp_no_rate) < fabs(ins_flow.optical_flow_x - Z_exp_with_rate)) {
1211 printf("NO RATE WINS!");
1212 }
1213 printf("\n");*/
1214 }
1215
1216 // i_k1 = Z - Z_expected;
1217 float innovation[N_MEAS_OF_KF][1];
1218 //print_ins_flow_state();
1220 DEBUG_PRINT("Expected flow filter: %f, Expected flow ground truth = %f, Real flow x: %f, Real flow y: %f.\n",
1223 DEBUG_PRINT("Expected div: %f, Real div: %f.\n", Z_expected[OF_DIV_FLOW_IND], ins_flow.divergence);
1226 DEBUG_PRINT("Expected flow in body X direction filter: %f, Real flow in corresponding y direction: %f, gyro = %f, expected velocity = %f, real velocity = %f, expected theta = %f, real theta = %f.\n",
1228 OF_X[OF_VX_IND], velocities->x, OF_X[OF_THETA_IND], eulers->theta);
1229 }
1230 if (OF_USE_GYROS) {
1231 float gyro_meas_roll;
1232 if (!PREDICT_GYROS) {
1234 } else {
1235 // TODO: You can fake gyros here by estimating them as follows:
1236 // rate_p_filt_est = -1.8457e-04 * cmd_roll;
1237 // gyro_meas_roll = -1.8457e-04 * (stabilization.cmd[COMMAND_ROLL]-ins_flow.lp_roll_command);
1238 // gyro_meas_roll = -2.0e-03 * (stabilization.cmd[COMMAND_ROLL]-ins_flow.lp_roll_command);
1239
1240 // gyro_meas_roll = 1e-04 * parameters[PAR_PRED_ROLL_1] * (stabilization.cmd[COMMAND_ROLL]-ins_flow.lp_roll_command);
1241 // gyro_meas_roll = parameters[PAR_PRED_ROLL_2] * gyro_meas_roll + 1E-3 * parameters[PAR_PRED_ROLL_3] * ins_flow.optical_flow_x;
1242
1243 // only flow:
1245
1246 //printf("Predicted roll: %f, real measured roll: %f.\n", gyro_meas_roll, (ins_flow.lp_gyro_roll - ins_flow.lp_gyro_bias_roll) * (M_PI/180.0f) / 74.0f);
1247 }
1248
1250 //innovation[OF_RATE_IND][0] = rates->p - Z_expected[OF_RATE_IND];
1251 DEBUG_PRINT("Expected rate: %f, Real rate: %f.\n", Z_expected[OF_RATE_IND], ins_flow.lp_gyro_roll);
1252 }
1253
1255 DEBUG_PRINT("Innovation:");
1257
1258 // X_k1_k1 = X_k1_k + K_k1*(i_k1);
1259 float _KI[N_STATES_OF_KF][1];
1262
1263 DEBUG_PRINT("K*innovation:\n");
1265
1266 DEBUG_PRINT("PRE: v = %f, angle = %f\n", OF_X[OF_V_IND], OF_X[OF_ANGLE_IND]);
1267 for (int i = 0; i < N_STATES_OF_KF; i++) {
1268 OF_X[i] += KI[i][0];
1269 }
1270 DEBUG_PRINT("POST v: %f, angle = %f\n", OF_X[OF_V_IND], OF_X[OF_ANGLE_IND]);
1271
1272 DEBUG_PRINT("Angles (deg): ahrs = %f, ekf = %f.\n", (180.0f / M_PI)*eulers->phi, (180.0f / M_PI)*OF_X[OF_ANGLE_IND]);
1273
1274 DEBUG_PRINT("P before correction:\n");
1276
1277 // P_k1_k1 = (eye(Nx) - K_k1*Hx)*P_k1_k*(eye(Nx) - K_k1*Hx)' + K_k1*R*K_k1'; % Joseph form of the covariance update equation
1281
1285 DEBUG_PRINT("eye:\n");
1287
1291 DEBUG_PRINT("eKJac:\n");
1293
1297 // (eye(Nx) - K_k1*Hx)*P_k1_k*(eye(Nx) - K_k1*Hx)'
1302 DEBUG_PRINT("eKJac * P *eKJacT:\n");
1304
1305 // K_k1*R*K_k1'
1306 // TODO: check all MAKE_MATRIX that they mention the number of ROWS!
1316 DEBUG_PRINT("KRKT:\n");
1318
1319 // summing the two parts:
1321
1322 DEBUG_PRINT("P corrected:\n");
1324 float trace_P = 0.0f;
1325 for (int i = 0; i < N_STATES_OF_KF; i++) {
1326 trace_P += P[i][i];
1327 }
1328 DEBUG_PRINT("trace P = %f\n", trace_P);
1329
1330 // indicate that the measurement has been used:
1332 }
1333
1334 // update the time:
1336
1337}
1338
1340 uint32_t stamp, struct Int32Rates *gyro)
1341{
1343#if USE_AUTO_AHRS_FREQ || !defined(AHRS_PROPAGATE_FREQUENCY)
1344 PRINT_CONFIG_MSG("Calculating dt for AHRS_ICQ propagation.")
1345 /* timestamp in usec when last callback was received */
1346 static uint32_t last_stamp = 0;
1347
1348 if (last_stamp > 0 && ahrs_icq.is_aligned) {
1349 float dt = (float)(stamp - last_stamp) * 1e-6;
1350 ahrs_icq_propagate(gyro, dt);
1352
1353 // TODO: filter all gyro values
1354 // For now only filter the roll gyro:
1355 float current_rate = ((float)gyro->p); // TODO: is this correct? / INT32_RATE_FRAC;
1357 current_rate = ((float)gyro->q);
1359 }
1360 last_stamp = stamp;
1361#else
1362 PRINT_CONFIG_MSG("Using fixed AHRS_PROPAGATE_FREQUENCY for AHRS_ICQ propagation.")
1365 const float dt = 1. / (AHRS_PROPAGATE_FREQUENCY);
1366 ahrs_icq_propagate(gyro, dt);
1368 }
1369#endif
1370}
1371
1373 uint32_t __attribute__((unused)) stamp,
1374 struct Int32Vect3 *accel)
1375{
1376#if USE_AUTO_AHRS_FREQ || !defined(AHRS_CORRECT_FREQUENCY)
1377 PRINT_CONFIG_MSG("Calculating dt for AHRS int_cmpl_quat accel update.")
1378 static uint32_t last_stamp = 0;
1379 if (last_stamp > 0 && ahrs_icq.is_aligned) {
1380 float dt = (float)(stamp - last_stamp) * 1e-6;
1381 ahrs_icq_update_accel(accel, dt);
1383 }
1384 last_stamp = stamp;
1385#else
1386 PRINT_CONFIG_MSG("Using fixed AHRS_CORRECT_FREQUENCY for AHRS int_cmpl_quat accel update.")
1388 if (ahrs_icq.is_aligned) {
1389 const float dt = 1. / (AHRS_CORRECT_FREQUENCY);
1390 ahrs_icq_update_accel(accel, dt);
1392 }
1393#endif
1394}
1395
1396
1399{
1400 /* Compute LTP to BODY quaternion */
1401 struct Int32Quat ltp_to_body_quat = ahrs_icq.ltp_to_body_quat;
1402 //struct Int32Quat *body_to_imu_quat = orientationGetQuat_i(&ahrs_icq.body_to_imu);
1403 //int32_quat_comp_inv(&ltp_to_body_quat, &ahrs_icq.ltp_to_imu_quat, body_to_imu_quat);
1404
1405 if (use_filter < USE_ANGLE) {
1406 // Use the orientation as is:
1407 stateSetNedToBodyQuat_i(MODULE_INS_FLOW_ID, &ltp_to_body_quat);
1408 } else {
1409
1410 // get Euler angles:
1411 struct OrientationReps orient;
1412 orient.status = 1 << ORREP_QUAT_I;
1413 orient.quat_i = ltp_to_body_quat;
1414 struct FloatEulers *eulers = orientationGetEulers_f(&orient);
1415
1416 // set roll angle with value from the filter:
1417 GT_phi = eulers->phi;
1418 eulers->phi = OF_X[OF_ANGLE_IND];
1419 if (OF_TWO_DIM) {
1420 GT_theta = eulers->theta;
1421 //printf("Real theta = %f, setting theta to %f.\n", eulers->theta, OF_X[OF_THETA_IND]);
1422 eulers->theta = OF_X[OF_THETA_IND];
1423 }
1424
1425 // Transform the Euler representation to Int32Quat and set the state:
1428 orient_euler.eulers_f = (*eulers);
1429
1432 }
1433
1434 /* compute body rates */
1435 struct Int32Rates body_rate = ahrs_icq.body_rate;
1436 // struct Int32RMat *body_to_imu_rmat = orientationGetRMat_i(&ahrs_icq.body_to_imu);
1437 // int32_rmat_transp_ratemult(&body_rate, body_to_imu_rmat, &ahrs_icq.imu_rate);
1438 /* Set state */
1440
1441}
1442
1444{
1446 for (int i = 0; i < num_act; i++) {
1447 if (feedback[i].set.rpm) {
1448 ins_flow.RPM[i] = feedback[i].rpm;
1449 }
1450 }
1451}
1452
1453
1454/* Update INS based on GPS information */
1457 struct GpsState *gps_s)
1458{
1459
1460 if (gps_s->fix < GPS_FIX_3D) {
1461 return;
1462 }
1465 }
1466
1468
1469 /* simply scale and copy pos/speed from gps */
1474
1475 if (use_filter >= USE_HEIGHT) {
1476 //struct NedCoor_f* position = stateGetPositionNed_f();
1478 //printf("Z true: %f / %d, Z filter: %f / %d. (float / int32_t)\n", position->z, ins_flow.ltp_pos.z, OF_X[OF_Z_IND], z_Ned_i);
1480 }
1481
1483
1484
1485
1490
1491 if (use_filter >= USE_VELOCITY) {
1492 // get NED to body rotation matrix:
1494 // get transpose (inverse):
1495 struct FloatRMat BTN;
1497
1498 // the velocities from the filter are rotated from the body to the inertial frame:
1500 body_velocities.x = 0.0f; // filter does not determine this yet
1502 body_velocities.z = 0.0f;
1503 /*
1504 if(CONSTANT_ALT_FILTER) {
1505 body_velocities.z = 0.0f;
1506 }
1507 else {
1508 body_velocities.z = OF_X[OF_Z_DOT_IND];
1509 }*/
1511 // TODO: also estimate vx, so that we can just use the rotated vector:
1512 // For now, we need to keep the x, and y body axes aligned with the global ones.
1513 // printf("Original speed y = %d, ", ins_flow.ltp_speed.y);
1516 // printf("Changed speed y = %d (%f in float)\n", ins_flow.ltp_speed.y, NED_velocities.y);
1517 }
1518
1520
1521 /*
1522 bool vel_ned_valid = bit_is_set(gps_s->valid_fields, GPS_VALID_VEL_NED_BIT);
1523 uint8_t nsats = gps_s->num_sv;
1524 */
1525}
1526
1528 uint32_t stamp __attribute__((unused)),
1529 struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel,
1530 struct Int32Vect3 *lp_mag)
1531{
1532 if (!ahrs_icq.is_aligned) {
1533 if (ahrs_icq_align(lp_gyro, lp_accel, lp_mag)) {
1535 }
1536 }
1537}
1538
1539
Main include for ABI (AirBorneInterface).
#define ABI_BROADCAST
Broadcast address.
Definition abi_common.h:58
Event structure to store callbacks in a linked list.
Definition abi_common.h:67
#define AHRS_COMP_ID_FLOW
Definition ahrs.h:49
void ahrs_aligner_init(void)
bool ahrs_icq_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel, struct Int32Vect3 *lp_mag)
void ahrs_icq_update_accel(struct Int32Vect3 *accel, float dt)
struct AhrsIntCmplQuat ahrs_icq
Default Rate filter Low pass.
void ahrs_icq_init(void)
void ahrs_icq_update_gps(struct GpsState *gps_s)
void ahrs_icq_propagate(struct Int32Rates *gyro, float dt)
struct Int32Rates gyro_bias
@ AHRS_ICQ_RUNNING
struct Int32Vect3 mag_h
struct Int32Rates body_rate
struct Int32Quat ltp_to_body_quat
enum AhrsICQStatus status
status of the AHRS, AHRS_ICQ_UNINIT or AHRS_ICQ_RUNNING
bool autopilot_in_flight(void)
get in_flight flag
Definition autopilot.c:340
Core autopilot interface common to all firmwares.
#define UNUSED(x)
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
struct GpsState gps
global GPS state
Definition gps.c:74
int32_t hmsl
height above mean sea level (MSL) in mm
Definition gps.h:94
struct LlaCoor_i lla_pos
position in LLA (lat,lon: deg*1e7; alt: mm over ellipsoid)
Definition gps.h:92
struct EcefCoor_i ecef_pos
position in ECEF in cm
Definition gps.h:91
#define GPS_FIX_3D
3D GPS fix
Definition gps.h:44
data structure for GPS information
Definition gps.h:87
float q
in rad/s
float phi
in radians
float p
in rad/s
float theta
in radians
static void float_mat_diff(float **o, float **a, float **b, int m, int n)
o = a - b
static void float_mat_sum(float **o, float **a, float **b, int m, int n)
o = a + b
void float_rmat_inv(struct FloatRMat *m_b2a, struct FloatRMat *m_a2b)
Inverse/transpose of a rotation matrix.
static void float_mat_mul(float **o, float **a, float **b, int m, int n, int l)
o = a * b
static void float_mat_transpose(float **o, float **a, int n, int m)
transpose non-square matrix
#define MAKE_MATRIX_PTR(_ptr, _mat, _rows)
Make a pointer to a matrix of _rows lines.
void float_mat_invert(float **o, float **mat, int n)
Calculate inverse of any n x n matrix (passed as C array) o = mat^-1 Algorithm verified with Matlab.
static void float_mat_diagonal_scal(float **o, float v, int n)
Make an n x n identity matrix (for matrix passed as array)
void float_rmat_vmult(struct FloatVect3 *vb, struct FloatRMat *m_a2b, struct FloatVect3 *va)
rotate 3D vector by rotation matrix.
euler angles
rotation matrix
angular rates
int32_t p
in rad/s with INT32_RATE_FRAC
int32_t r
in rad/s with INT32_RATE_FRAC
int32_t phi
in rad with INT32_ANGLE_FRAC
int32_t q
in rad/s with INT32_RATE_FRAC
int32_t psi
in rad with INT32_ANGLE_FRAC
int32_t theta
in rad with INT32_ANGLE_FRAC
void int32_eulers_of_quat(struct Int32Eulers *e, struct Int32Quat *q)
#define INT32_POS_OF_CM_DEN
#define INT32_SPEED_OF_CM_S_NUM
#define INT32_SPEED_OF_CM_S_DEN
#define INT32_POS_OF_CM_NUM
#define INT32_VECT3_SCALE_2(_a, _b, _num, _den)
#define MAG_FLOAT_OF_BFP(_ai)
euler angles
Rotation quaternion.
angular rates
int32_t lat
in degrees*1e7
int32_t hmsl
Height above mean sea level in mm.
int32_t alt
in millimeters above WGS84 reference ellipsoid
int32_t z
Down.
int32_t z
in centimeters
struct LlaCoor_i lla
Reference point in lla.
int32_t x
in centimeters
int32_t y
East.
struct EcefCoor_i ecef
Reference point in ecef.
int32_t y
in centimeters
int32_t lon
in degrees*1e7
int32_t x
North.
void ecef_of_lla_i(struct EcefCoor_i *out, struct LlaCoor_i *in)
Convert a LLA to ECEF.
void ltp_def_from_ecef_i(struct LtpDef_i *def, struct EcefCoor_i *ecef)
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.
void ned_of_ecef_vect_i(struct NedCoor_i *ned, struct LtpDef_i *def, struct EcefCoor_i *ecef)
Rotate a vector from ECEF to NED.
vector in EarthCenteredEarthFixed coordinates
vector in Latitude, Longitude and Altitude
definition of the local (flat earth) coordinate system
vector in North East Down coordinates
#define E
struct Int32Quat quat_i
Orientation quaternion.
uint8_t status
Holds the status bits for all orientation representations.
#define ORREP_QUAT_I
Quaternion (BFP int)
#define ORREP_EULER_F
zyx Euler (float)
static struct Int32Quat * orientationGetQuat_i(struct OrientationReps *orientation)
Get vehicle body attitude quaternion (int).
static struct FloatEulers * orientationGetEulers_f(struct OrientationReps *orientation)
Get vehicle body attitude euler angles (float).
static struct Int32Quat * stateGetNedToBodyQuat_i(void)
Get vehicle body attitude quaternion (int).
Definition state.h:1276
static struct FloatRMat * stateGetNedToBodyRMat_f(void)
Get vehicle body attitude rotation matrix (float).
Definition state.h:1300
static struct Int32Eulers * stateGetNedToBodyEulers_i(void)
Get vehicle body attitude euler angles (int).
Definition state.h:1288
static void stateSetNedToBodyQuat_i(uint16_t id, struct Int32Quat *ned_to_body_quat)
Set vehicle body attitude from quaternion (int).
Definition state.h:1232
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
Definition state.h:1306
static void stateSetLocalOrigin_i(uint16_t id, struct LtpDef_i *ltp_def)
Set the local (flat earth) coordinate frame origin (int).
Definition state.h:519
static struct NedCoor_f * stateGetPositionNed_f(void)
Get position in local NED coordinates (float).
Definition state.h:839
static void stateSetPositionNed_i(uint16_t id, struct NedCoor_i *ned_pos)
Set position from local NED coordinates (int).
Definition state.h:638
static void stateSetBodyRates_i(uint16_t id, struct Int32Rates *body_rate)
Set vehicle body angular rate (int).
Definition state.h:1336
static struct FloatRates * stateGetBodyRates_f(void)
Get vehicle body angular rate (float).
Definition state.h:1367
static struct NedCoor_f * stateGetSpeedNed_f(void)
Get ground speed in local NED coordinates (float).
Definition state.h:1049
static void stateSetSpeedNed_i(uint16_t id, struct NedCoor_i *ned_speed)
Set ground speed in local NED coordinates (int).
Definition state.h:892
#define AHRS_PROPAGATE_FREQUENCY
Definition hf_float.c:55
#define INS_RESET_REF
flags for INS reset
Definition ins.h:36
static float p[2][2]
#define INS_RPM_ID
Definition ins_flow.c:99
float lp_factor
Definition ins_flow.c:182
#define DEBUG_INS_FLOW
Definition ins_flow.c:49
#define PAR_P3
Definition ins_flow.c:272
int moment_ind
Definition ins_flow.c:170
int use_filter
Definition ins_flow.c:185
static void gps_cb(uint8_t sender_id, uint32_t stamp, struct GpsState *gps_s)
Definition ins_flow.c:1455
float GT_theta
Definition ins_flow.c:191
#define PAR_P2
Definition ins_flow.c:271
#define INS_FLOW_GPS_ID
Definition ins_flow.c:87
float moments[MOMENT_DELAY]
Definition ins_flow.c:169
static void print_ins_flow_state(void)
Definition ins_flow.c:687
static void send_ins(struct transport_tx *trans, struct link_device *dev)
Definition ins_flow.c:360
#define PAR_PRED_ROLL_3
Definition ins_flow.c:279
#define PAR_Q_TB
Definition ins_flow.c:275
#define PAR_Q4
Definition ins_flow.c:268
#define MOMENT_DELAY
Definition ins_flow.c:168
struct NedCoor_i ltp_speed
Definition ins_flow.c:141
bool run_filter
Definition ins_flow.c:186
float optical_flow_y
Definition ins_flow.c:146
static abi_event accel_ev
Definition ins_flow.c:105
float lp_thrust
Definition ins_flow.c:160
static void gyro_cb(uint8_t sender_id, uint32_t stamp, struct Int32Rates *gyro)
Definition ins_flow.c:1339
float OF_P[N_STATES_OF_KF][N_STATES_OF_KF]
Definition ins_flow.c:174
static uint8_t ahrs_flow_id
Component ID for FLOW.
Definition ins_flow.c:129
void ins_flow_init(void)
Definition ins_flow.c:532
#define INS_OPTICAL_FLOW_ID
Definition ins_flow.c:93
uint32_t counter
Definition ins_flow.c:187
static abi_event reset_ev
Definition ins_flow.c:110
static void print_true_state(void)
Definition ins_flow.c:712
float OF_X[N_STATES_OF_KF]
Definition ins_flow.c:172
float thrust_factor
Definition ins_flow.c:159
#define INS_FLOW_IMU_ID
Definition ins_flow.c:80
float vision_time
Definition ins_flow.c:148
#define OF_N_ROTORS
Definition ins_flow.c:177
static abi_event gyro_ev
Definition ins_flow.c:104
float of_time
Definition ins_flow.c:180
static void send_ins_ref(struct transport_tx *trans, struct link_device *dev)
Definition ins_flow.c:376
struct NedCoor_i ltp_accel
Definition ins_flow.c:142
static void reset_cb(uint8_t sender_id UNUSED, uint8_t flag)
Definition ins_flow.c:657
float RPM_FACTORS[OF_N_ROTORS]
Definition ins_flow.c:178
static void send_geo_mag(struct transport_tx *trans, struct link_device *dev)
Definition ins_flow.c:338
static abi_event aligner_ev
Definition ins_flow.c:109
float lp_gyro_pitch
Definition ins_flow.c:155
#define PAR_P4
Definition ins_flow.c:273
uint16_t RPM[8]
Definition ins_flow.c:152
#define PAR_KD
Definition ins_flow.c:274
#define PAR_Q3
Definition ins_flow.c:267
static void ins_act_feedback_cb(uint8_t sender_id, struct act_feedback_t *feedback, uint8_t num_act)
Definition ins_flow.c:1443
static void send_filter_status(struct transport_tx *trans, struct link_device *dev)
Definition ins_flow.c:348
#define DEBUG_PRINT(...)
Definition ins_flow.c:57
struct InsFlow ins_flow
Definition ins_flow.c:164
static void send_quat(struct transport_tx *trans, struct link_device *dev)
Definition ins_flow.c:299
static abi_event ins_act_feedback_ev
Definition ins_flow.c:108
uint8_t RPM_num_act
Definition ins_flow.c:153
float of_prev_time
Definition ins_flow.c:181
float OF_Q[N_STATES_OF_KF][N_STATES_OF_KF]
Definition ins_flow.c:173
float thrust_factor
Definition ins_flow.c:188
static void ins_reset_filter(void)
Definition ins_flow.c:489
#define PAR_P1
Definition ins_flow.c:270
#define INS_FLOW_GYRO_ID
Definition ins_flow.c:68
struct NedCoor_i ltp_pos
Definition ins_flow.c:140
void ins_optical_flow_cb(uint8_t sender_id, uint32_t stamp, int32_t flow_x, int32_t flow_y, int32_t flow_der_x, int32_t flow_der_y, float quality, float size_divergence)
Definition ins_flow.c:668
float lp_factor_strong
Definition ins_flow.c:183
#define PAR_P_TB
Definition ins_flow.c:276
float lp_gyro_roll
Definition ins_flow.c:157
#define PAR_K1
Definition ins_flow.c:259
float lp_gyro_bias_pitch
Definition ins_flow.c:156
static void accel_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *accel)
Definition ins_flow.c:1372
void ins_flow_update(void)
Definition ins_flow.c:725
#define PAR_K0
Definition ins_flow.c:258
#define PAR_IX
Definition ins_flow.c:255
#define PAR_Q0
Definition ins_flow.c:264
struct LtpDef_i ltp_def
Definition ins_flow.c:136
static uint32_t ahrs_icq_last_stamp
Definition ins_flow.c:128
static void aligner_cb(uint8_t sender_id, uint32_t stamp, struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel, struct Int32Vect3 *lp_mag)
Definition ins_flow.c:1527
static void send_euler(struct transport_tx *trans, struct link_device *dev)
Definition ins_flow.c:315
static void set_body_state_from_quat(void)
Rotate angles and rates from imu to body frame and set state.
Definition ins_flow.c:1398
bool ltp_initialized
Definition ins_flow.c:137
bool reset_filter
Definition ins_flow.c:184
float optical_flow_x
Definition ins_flow.c:145
static void send_bias(struct transport_tx *trans, struct link_device *dev)
Definition ins_flow.c:331
#define PAR_K2
Definition ins_flow.c:260
float OF_R[N_MEAS_OF_KF][N_MEAS_OF_KF]
Definition ins_flow.c:175
static abi_event ins_optical_flow_ev
Definition ins_flow.c:107
#define PAR_R1
Definition ins_flow.c:263
float lp_roll_command
Definition ins_flow.c:161
float lp_gyro_bias_roll
Definition ins_flow.c:158
#define PAR_R0
Definition ins_flow.c:262
#define PAR_Q2
Definition ins_flow.c:266
#define PAR_Q1
Definition ins_flow.c:265
#define PAR_K3
Definition ins_flow.c:261
#define DEBUG_MAT_PRINT(...)
Definition ins_flow.c:58
float parameters[22]
Definition ins_flow.c:249
float divergence
Definition ins_flow.c:147
#define AHRS_ICQ_OUTPUT_ENABLED
Definition ins_flow.c:62
#define PAR_P0
Definition ins_flow.c:269
#define INS_FLOW_ACCEL_ID
Definition ins_flow.c:74
static abi_event gps_ev
Definition ins_flow.c:106
bool new_flow_measurement
Definition ins_flow.c:149
float GT_phi
Definition ins_flow.c:190
#define PAR_MASS
Definition ins_flow.c:256
static void send_ins_flow(struct transport_tx *trans, struct link_device *dev)
Definition ins_flow.c:390
#define OF_THRUST_BIAS
Definition ins_flow.h:40
#define CONSTANT_ALT_FILTER
Definition ins_flow.h:35
#define OF_V_IND
Definition ins_flow.h:107
#define USE_HEIGHT
Definition ins_flow.h:145
#define USE_VELOCITY
Definition ins_flow.h:144
#define OF_THETA_IND
Definition ins_flow.h:113
#define OF_DIV_FLOW_IND
Definition ins_flow.h:133
#define OF_USE_GYROS
Definition ins_flow.h:42
#define OF_ANGLE_DOT_IND
Definition ins_flow.h:109
#define OF_LAT_FLOW_IND
Definition ins_flow.h:132
#define PREDICT_GYROS
Definition ins_flow.h:44
#define OF_LAT_FLOW_X_IND
Definition ins_flow.h:138
#define OF_ANGLE_IND
Definition ins_flow.h:108
#define OF_DRAG
Definition ins_flow.h:36
#define N_MEAS_OF_KF
Definition ins_flow.h:122
#define OF_THRUST_BIAS_IND
Definition ins_flow.h:101
#define OF_Z_IND
Definition ins_flow.h:110
#define OF_Z_DOT_IND
Definition ins_flow.h:111
#define OF_VX_IND
Definition ins_flow.h:114
#define OF_TWO_DIM
Definition ins_flow.h:38
#define USE_ANGLE
Definition ins_flow.h:143
#define OF_RATE_IND
Definition ins_flow.h:134
#define N_STATES_OF_KF
Definition ins_flow.h:100
PRINT_CONFIG_MSG("USE_INS_NAV_INIT defaulting to TRUE")
static struct FloatVect3 H
uint16_t foo
Definition main_demo5.c:58
int32_t rpm
RPM.
Definition actuators.h:51
Motor Mixing.
static float g
PRINT_CONFIG_VAR(ONELOOP_ANDI_FILT_CUTOFF)
Paparazzi floating point algebra.
float z
in meters
vector in North East Down coordinates Units: meters
Simple matrix helper macros.
struct Stabilization stabilization
General stabilization interface for rotorcrafts.
int32_t cmd[COMMANDS_NB]
output command vector, range from [-MAX_PPRZ:MAX_PPRZ] (store for messages)
API to get/set the generic vehicle states.
static const struct usb_device_descriptor dev
Definition usb_ser_hw.c:74
Architecture independent timing functions.
static float get_sys_time_float(void)
Get the time in seconds since startup.
Definition sys_time.h:138
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Definition telemetry.c:51
Periodic telemetry system header (includes downlink utility and generated code).
#define DefaultPeriodic
Set default periodic telemetry.
Definition telemetry.h:66
uint16_t val[TCOUPLE_NB]
static float P[3][3]
static float K[9]
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
int int32_t
Typedef defining 32 bit int type.
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.