Paparazzi UAS v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
Loading...
Searching...
No Matches
stabilization_indi.c
Go to the documentation of this file.
1/*
2 * Copyright (C) Ewoud Smeur <ewoud_smeur@msn.com>
3 * MAVLab Delft University of Technology
4 *
5 * This file is part of paparazzi.
6 *
7 * paparazzi is free software; you can redistribute it and/or modify
8 * it under the terms of the GNU General Public License as published by
9 * the Free Software Foundation; either version 2, or (at your option)
10 * any later version.
11 *
12 * paparazzi is distributed in the hope that it will be useful,
13 * but WITHOUT ANY WARRANTY; without even the implied warranty of
14 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 * GNU General Public License for more details.
16 *
17 * You should have received a copy of the GNU General Public License
18 * along with paparazzi; see the file COPYING. If not, see
19 * <http://www.gnu.org/licenses/>.
20 */
21
35
37#include "state.h"
38#include "generated/airframe.h"
41#include "modules/core/abi.h"
43#include "math/wls/wls_alloc.h"
44#include <stdio.h>
45
46// Factor that the estimated G matrix is allowed to deviate from initial one
47#define INDI_ALLOWED_G_FACTOR 2.0
48
49#ifdef STABILIZATION_INDI_FILT_CUTOFF_P
50#define STABILIZATION_INDI_FILTER_ROLL_RATE TRUE
51#else
52#define STABILIZATION_INDI_FILT_CUTOFF_P 20.0
53#endif
54
55#ifdef STABILIZATION_INDI_FILT_CUTOFF_Q
56#define STABILIZATION_INDI_FILTER_PITCH_RATE TRUE
57#else
58#define STABILIZATION_INDI_FILT_CUTOFF_Q 20.0
59#endif
60
61#ifdef STABILIZATION_INDI_FILT_CUTOFF_R
62#define STABILIZATION_INDI_FILTER_YAW_RATE TRUE
63#else
64#define STABILIZATION_INDI_FILT_CUTOFF_R 20.0
65#endif
66
67// Default is WLS
68#ifndef STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
69#define STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE FALSE
70#endif
71
72#ifndef STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
73#define STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER FALSE
74#endif
75
76// Airspeed [m/s] at which the forward flight throttle limit is used instead of
77// the hover throttle limit.
78#ifndef STABILIZATION_INDI_THROTTLE_LIMIT_AIRSPEED_FWD
79#define STABILIZATION_INDI_THROTTLE_LIMIT_AIRSPEED_FWD 8.0
80#endif
81
82#ifndef STABILIZATION_INDI_USE_ADAPTIVE
83#define STABILIZATION_INDI_USE_ADAPTIVE false
84#endif
85
86#ifndef STABILIZATION_INDI_ADAPTIVE_MU
87#define STABILIZATION_INDI_ADAPTIVE_MU 0.001f
88#endif
89
90#ifndef STABILIZATION_INDI_ACT_IS_SERVO
91#define STABILIZATION_INDI_ACT_IS_SERVO {0}
92#endif
93
94#ifndef STABILIZATION_INDI_ACT_IS_THRUSTER_X
95#define STABILIZATION_INDI_ACT_IS_THRUSTER_X {0}
96#endif
97
98#ifndef STABILIZATION_INDI_ACT_IS_THRUSTER_Y
99#define STABILIZATION_INDI_ACT_IS_THRUSTER_Y {0}
100#endif
101
105#ifndef STABILIZATION_INDI_YAW_DISTURBANCE_LIMIT
106#define STABILIZATION_INDI_YAW_DISTURBANCE_LIMIT 99999.f
107#endif
108
109#if INDI_OUTPUTS == 5
110#ifndef STABILIZATION_INDI_G1_THRUST_X
111#error "You must define STABILIZATION_INDI_G1_THRUST_X for your number of INDI_OUTPUTS"
112#endif
113#endif
114
115#ifdef SetCommandsFromRC
116#warning SetCommandsFromRC not used: STAB_INDI writes actuators directly
117#endif
118
119#ifdef SetAutoCommandsFromRC
120#warning SetAutoCommandsFromRC not used: STAB_INDI writes actuators directly
121#endif
122
123#if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE // e.g. use WLS
124
125// Weighting of different control objectives in the cost function
126#ifndef STABILIZATION_INDI_WLS_PRIORITIES
127#if INDI_OUTPUTS == 5
128#define STABILIZATION_INDI_WLS_PRIORITIES {1000, 1000, 1, 100, 100} // roll, pitch, yaw, thrust_z, thrust_x
129#else
130#define STABILIZATION_INDI_WLS_PRIORITIES {1000, 1000, 1, 100} // default: roll, pitch, yaw, thrust_z
131#endif
132#endif
133
134// Weighting of different actuators in the cost function
135#ifndef STABILIZATION_INDI_WLS_WU
136#define STABILIZATION_INDI_WLS_WU {[0 ... INDI_NUM_ACT - 1] = 1.0}
137#endif
138
139// Preferred (neutral, least energy) actuator value
140// Assume 0 is neutral
141#ifndef STABILIZATION_INDI_ACT_PREF
142#define STABILIZATION_INDI_ACT_PREF {0.0}
143#endif
144
145#if INDI_NUM_ACT > WLS_N_U_MAX
146#error Matrix-WLS_N_U_MAX too small or not defined: define WLS_N_U_MAX >= INDI_NUM_ACT in airframe file
147#endif
148#if INDI_OUTPUTS > WLS_N_V_MAX
149#error Matrix-WLS_N_V_MAX too small or not defined: define WLS_N_V_MAX >= INDI_OUTPUTS in airframe file
150#endif
151
153 .nu = INDI_NUM_ACT,
154 .nv = INDI_OUTPUTS,
155 .gamma_sq = 10000.0,
156 .v = {0.0},
159 .u_pref = {0.0},
160 .u_min = {0.0},
161 .u_max = {0.0},
162 .PC = 0.0,
163 .SC = 0.0,
164 .iter = 0
165};
166
168
169#endif // !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE (e.g. use WLS)
170
173
174
175static void lms_estimation(void);
176static void get_actuator_state(void);
177static void calc_g1_element(float dx_error, int8_t i, int8_t j, float mu_extra);
178static void calc_g2_element(float dx_error, int8_t j, float mu_extra);
179#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
180static void calc_g1g2_pseudo_inv(void);
181#endif
182static void bound_g_mat(void);
183
197
199
200#ifdef STABILIZATION_INDI_ACT_RATE_LIMIT
202#endif
203
204// Vector of boolean telling if an actuator is a servo
206
207// [3 x INDI_NUM_ACT] matrix representing the contribution (True/False) of an
208// actuator to the total 3D thrust vector
209#ifdef STABILIZATION_INDI_ACT_THRUST_MAT
211#else // backward compatibility
212static bool act_thrust_mat[3][INDI_NUM_ACT] = {
215#ifdef STABILIZATION_INDI_ACT_IS_THRUSTER_Z
217#else
218 {0}
219#endif
220};
221#endif
222
223#ifdef STABILIZATION_INDI_ACT_DYN
224#warning STABILIZATION_INDI_ACT_DYN is deprecated, use STABILIZATION_INDI_ACT_FREQ instead.
225#warning You now have to define the continuous time corner frequency in rad/s of the actuators.
226#warning "Use -ln(1 - old_number) * PERIODIC_FREQUENCY to compute it from the old values."
228#else
230float act_dyn_discrete[INDI_NUM_ACT]; // will be computed from freq at init
231#endif
232
234
235// variables needed for control
237struct FloatRates angular_accel_ref = {0., 0., 0.};
238struct FloatRates angular_rate_ref = {0., 0., 0.};
239float angular_acceleration[3] = {0., 0., 0.};
242struct FloatVect3 stab_thrust_filt = { 0.f, 0.f, 0.f };
243
244float q_filt = 0.0;
245float r_filt = 0.0;
246
247float stabilization_indi_filter_freq = 20.0; //Hz, for setting handler
248
249// variables needed for estimation
258
259// The learning rate per axis (roll, pitch, yaw, thrust)
260float mu1[INDI_OUTPUTS] = {0.00001, 0.00001, 0.000003, 0.000002};
261// The learning rate for the propeller inertia (scaled by 512 wrt mu1)
262float mu2 = 0.002;
263
264// other variables
266
267// Number of actuators used to provide thrust
269
272
273// Register actuator feedback if we rely on RPM information
274#if STABILIZATION_INDI_RPM_FEEDBACK
275#ifndef STABILIZATION_INDI_ACT_FEEDBACK_ID
276#define STABILIZATION_INDI_ACT_FEEDBACK_ID ABI_BROADCAST
277#endif
279
281static void act_feedback_cb(uint8_t sender_id, struct act_feedback_t *feedback, uint8_t num_act);
282PRINT_CONFIG_MSG("STABILIZATION_INDI_RPM_FEEDBACK")
283#endif
284
286float g2[INDI_NUM_ACT] = STABILIZATION_INDI_G2; //scaled by INDI_G_SCALING
287#ifdef STABILIZATION_INDI_G1
289#else // old defines TODO remove
290#if INDI_OUTPUTS == 5
294 };
295
296#else
300#endif
301#endif
302
308
309// Can be used to directly control each actuator from the control algorithm
311
317#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
319#else
321#endif
323
324static void init_filters(void);
325static struct FloatRates filter_rates(struct FloatRates *rates);
326static void sum_g1_g2(void);
327
328#if PERIODIC_TELEMETRY
330#if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
331static void send_wls_v_stab(struct transport_tx *trans, struct link_device *dev)
332{
333 send_wls_v("stab", &wls_stab_p, trans, dev);
334}
335static void send_wls_u_stab(struct transport_tx *trans, struct link_device *dev)
336{
337 send_wls_u("stab", &wls_stab_p, trans, dev);
338}
339#endif
340static void send_eff_mat_g_indi(struct transport_tx *trans, struct link_device *dev)
341{
343 INDI_NUM_ACT, g1g2[0],
344 INDI_NUM_ACT, g1g2[1],
345 INDI_NUM_ACT, g1g2[2],
346 INDI_NUM_ACT, g1g2[3],
348}
349
350static void send_ahrs_ref_quat(struct transport_tx *trans, struct link_device *dev)
351{
352 struct Int32Quat *quat = stateGetNedToBodyQuat_i();
358 &(quat->qi),
359 &(quat->qx),
360 &(quat->qy),
361 &(quat->qz));
362}
363
364static void send_att_full_indi(struct transport_tx *trans, struct link_device *dev)
365{
366 float zero = 0.0;
368 struct FloatEulers att, att_sp;
369#if GUIDANCE_INDI_HYBRID
374#else
377#endif
378 float temp_att[3] = {att.phi, att.theta, att.psi};
379 float temp_att_ref[3] = {att_sp.phi, att_sp.theta, att_sp.psi};
380 float temp_rate[3] = {body_rates->p, body_rates->q, body_rates->r};
384 1, &zero, // att des
385 3, temp_att, // att
386 3, temp_att_ref, // att ref
387 3, temp_rate, // rate
388 3, temp_rate_ref, // rate ref
389 3, angular_acceleration, // ang.acc = rate.diff
390 3, temp_ang_acc_ref, // ang.acc.ref
391 1, &zero, // jerk ref
392 1, &zero); // u
393}
394#endif
395
400{
401 // Initialize filters
402 init_filters();
403
404 int8_t i;
405// If the deprecated STABILIZATION_INDI_ACT_DYN is used, convert it to the new FREQUENCY format
406#ifdef STABILIZATION_INDI_ACT_FREQ
407 // Initialize the array of pointers to the rows of g1g2
408 for (i = 0; i < INDI_NUM_ACT; i++) {
410 }
411#endif
412
413#if STABILIZATION_INDI_RPM_FEEDBACK
415#endif
416
422
423 //Calculate G1G2
424 sum_g1_g2();
425
426 // Do not compute if not needed
427#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
428 //Calculate G1G2_PSEUDO_INVERSE
430#endif
431
432 // Initialize the array of pointers to the rows of g1g2
433 for (i = 0; i < INDI_OUTPUTS; i++) {
434 Bwls[i] = g1g2[i];
435 }
436
437 // Initialize the estimator matrices
440 // Remember the initial matrices
443
444 num_thrusters = 0; // sum of Z thrusters
445 for (i = 0; i < INDI_NUM_ACT; i++) {
446#ifndef STABILIZATION_INDI_ACT_IS_THRUSTER_Z
447 // Assume non-servos and non thrust-x/y motors, not already set to true, are delivering (Z) thrust
448 act_thrust_mat[2][i] = act_thrust_mat[2][i] || (!act_thrust_mat[0][i] && !act_thrust_mat[1][i] && !act_is_servo[i]);
449#endif
450 if (act_thrust_mat[2][i]) {
452 }
453 }
454
455#if PERIODIC_TELEMETRY
459 #if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
462 #endif
463#endif
464}
465
479
495
499static void init_filters(void)
500{
501 // tau = 1/(2*pi*Fc)
502 float tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF);
504 float sample_time = 1.0 / PERIODIC_FREQUENCY;
505 // Filtering of the gyroscope
506 int8_t i;
507 for (i = 0; i < 3; i++) {
510 }
511
512 // Filtering of the actuators
513 for (i = 0; i < INDI_NUM_ACT; i++) {
516 }
517
518 // Filtering of the accel body z
520
521#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
522 tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF_P);
524 tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF_Q);
526 tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF_R);
528#else
529 // Init rate filter for feedback
531
535#endif
536}
537
538static struct FloatRates filter_rates(struct FloatRates *rates)
539{
540 struct FloatRates rates_filt;
541#if STABILIZATION_INDI_FILTER_ROLL_RATE
542#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
544#else
546#endif
547#else
548 rates_filt.p = rates->p;
549#endif
550#if STABILIZATION_INDI_FILTER_PITCH_RATE
551#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
553#else
555#endif
556#else
557 rates_filt.q = rates->q;
558#endif
559#if STABILIZATION_INDI_FILTER_YAW_RATE
560#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
562#else
564#endif
565#else
566 rates_filt.r = rates->r;
567#endif
568 return rates_filt;
569}
570
579void stabilization_indi_rate_run(bool in_flight, struct StabilizationSetpoint *sp, struct ThrustSetpoint *thrust, int32_t *cmd)
580{
581
582 // Propagate actuator filters
585 for (int i = 0; i < INDI_NUM_ACT; i++) {
590
591 // calculate derivatives for estimation
596 }
597
598 // Use the last actuator state for this computation
600
601 // Predict angular acceleration u*B
605
606 /* Propagate the filter on the gyroscopes */
608 float rate_vect[3] = {body_rates->p, body_rates->q, body_rates->r};
609
610 // Get the acceleration in body axes
611 struct Int32Vect3 *body_accel_i;
612 body_accel_i = stateGetAccelBody_i();
613 ACCELS_FLOAT_OF_BFP(body_accel_f, *body_accel_i);
614
615 int8_t i;
616 for (i = 0; i < 3; i++) {
619
620 // Calculate the angular acceleration via finite difference
623
624 // Calculate derivatives for estimation
629 }
630
631 // subtract u*B from angular acceleration
634
635 if (in_flight) {
636 // Limit the estimated disturbance in yaw for drones that are stable in sideslip
638 } else {
639 // Not in flight, so don't estimate disturbance
641 }
642
643 // The rates used for feedback are by default the measured rates.
644 // If there is a lot of noise on the gyroscope, it might be good to use the filtered value for feedback.
645 // Note that due to the delay, the controller may need relaxed gains.
647
648 // calculate the virtual control (reference acceleration) based on a controller
651
652 // compute virtual thrust
653 struct FloatVect3 v_thrust = { 0.f, 0.f, 0.f };
654 if (thrust->type == THRUST_INCR_SP) {
656 v_thrust.y = th_sp_to_incr_f(thrust, 0, THRUST_AXIS_Y);
657 v_thrust.z = th_sp_to_incr_f(thrust, 0, THRUST_AXIS_Z);
658
659 // Compute estimated thrust
661 for (i = 0; i < INDI_NUM_ACT; i++) {
662#if INDI_OUTPUTS == 4
664#endif
665#if INDI_OUTPUTS == 5 // FIXME change order of Z and X, or better detect that automatically ?
668#endif
669#if INDI_OUTPUTS == 6
673#endif
674 }
675 // Add the current estimated thrust to the increment
677 } else {
678 // build incremental thrust
679 struct FloatVect3 th_cmd;
683#if (INDI_OUTPUTS == 5) && (defined RADIO_CONTROL_THRUST_X) && (defined COMMAND_THRUST_X)
684 // TODO set X thrust from RC in the thrust input setpoint
686 th_cmd.x = (float)cmd[COMMAND_THRUST_X];
687#endif
688 for (i = 0; i < INDI_NUM_ACT; i++) {
689#if INDI_OUTPUTS == 4
690 v_thrust.z += th_cmd.z * Bwls[3][i] * (int32_t) act_thrust_mat[2][i];
691#endif
692#if INDI_OUTPUTS == 5 // FIXME change order of Z and X, or better detect that automatically ?
693 v_thrust.x += th_cmd.x * Bwls[4][i] * (int32_t) act_thrust_mat[0][i];
694 v_thrust.z += th_cmd.z * Bwls[3][i] * (int32_t) act_thrust_mat[2][i];
695#endif
696#if INDI_OUTPUTS == 6
697 v_thrust.x += th_cmd.x * Bwls[3][i] * (int32_t) act_thrust_mat[0][i];
698 v_thrust.y += th_cmd.y * Bwls[4][i] * (int32_t) act_thrust_mat[1][i];
699 v_thrust.z += th_cmd.z * Bwls[5][i] * (int32_t) act_thrust_mat[2][i];
700#endif
701 }
702 // store estimated thrust
704 }
705
706 // This term compensates for the spinup torque in the yaw axis
708
709 if (in_flight) {
710 // Limit the estimated disturbance in yaw for drones that are stable in sideslip
712 } else {
713 // Not in flight, so don't estimate disturbance
715 }
716
717 // The control objective in array format
721#if INDI_OUTPUTS == 4
722 indi_v[3] = v_thrust.z;
723#endif
724#if INDI_OUTPUTS == 5 // FIXME order of Z/X is reversed
725 indi_v[3] = v_thrust.z;
726 indi_v[4] = v_thrust.x;
727#endif
728#if INDI_OUTPUTS == 6
729 indi_v[3] = v_thrust.x;
730 indi_v[4] = v_thrust.y;
731 indi_v[5] = v_thrust.z;
732#endif
733
734#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
735 // Calculate the increment for each actuator
736 for (i = 0; i < INDI_NUM_ACT; i++) {
737 indi_u[i] = (g1g2_pseudo_inv[i][0] * indi_v[0])
738 + (g1g2_pseudo_inv[i][1] * indi_v[1])
739 + (g1g2_pseudo_inv[i][2] * indi_v[2])
740 + (g1g2_pseudo_inv[i][3] * indi_v[3]);
741 }
742#else
744
745 // WLS Control Allocator
746 for (i = 0; i < INDI_OUTPUTS; i++) {
747 wls_stab_p.v[i] = indi_v[i];
748 }
749 wls_alloc(&wls_stab_p, Bwls, 0, 0, 10);
750 for (i = 0; i < INDI_NUM_ACT; i++) {
751 indi_u[i] = wls_stab_p.u[i];
752 }
753#endif
754
755 // Use online effectiveness estimation only when flying
756 if (in_flight && indi_use_adaptive) {
758 }
759
760 // update actuators and thrust commands
761 cmd[COMMAND_THRUST] = 0;
762 for (i = 0; i < INDI_NUM_ACT; i++) {
763 // bound actuator command
764 if (act_is_servo[i]) {
766 } else {
768 Bound(indi_u[i], 0, MAX_PPRZ);
769 } else {
770 indi_u[i] = -MAX_PPRZ;
771 }
772 }
773
774 // commit actuator command
775 actuators_pprz[i] = (int16_t) indi_u[i];
776
777 // update thrust command such that the current is correctly estimated
779 }
781}
782
791void stabilization_indi_attitude_run(bool in_flight, struct StabilizationSetpoint *att_sp, struct ThrustSetpoint *thrust, int32_t *cmd)
792{
793 stab_att_sp_euler = stab_sp_to_eulers_i(att_sp); // stab_att_sp_euler.psi still used in ref..
794 stab_att_sp_quat = stab_sp_to_quat_i(att_sp); // quat attitude setpoint
795
799
800 // calculate the virtual control (reference acceleration) based on a controller
802
803 /* compute the INDI command */
805 stabilization_indi_rate_run(in_flight, &sp, thrust, cmd);
806}
807
814{
815 /* attitude error */
816 struct FloatQuat att_err;
818
819 struct FloatVect3 att_fb;
820#if TILT_TWIST_CTRL
821 struct FloatQuat tilt;
822 struct FloatQuat twist;
824 att_fb.x = tilt.qx;
825 att_fb.y = tilt.qy;
826 att_fb.z = twist.qz;
827#else
828 att_fb.x = att_err.qx;
829 att_fb.y = att_err.qy;
830 att_fb.z = att_err.qz;
831#endif
832
833 struct FloatRates rates_ref;
837 // add feed-forward term
839 return rates_ref;
840}
841
848{
849 struct FloatRates accel_ref;
850 accel_ref.p = (sp.p - rates.p) * indi_gains.rate.p;
851 accel_ref.q = (sp.q - rates.q) * indi_gains.rate.q;
852 accel_ref.r = (sp.r - rates.r) * indi_gains.rate.r;
853 return accel_ref;
854}
855
856
860#if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
862{
863 // Calculate the min and max increments
864 for (uint8_t i = 0; i < INDI_NUM_ACT; i++) {
867 wls_stab_p.u_pref[i] = act_pref[i];
868
869#ifdef GUIDANCE_INDI_MIN_THROTTLE
870 float airspeed = stateGetAirspeed_f();
871 //limit minimum thrust ap can give
872 if (!act_is_servo[i]) {
876 } else {
878 }
879 }
880 }
881#endif
882 }
883}
884#endif
885
893{
894#if STABILIZATION_INDI_RPM_FEEDBACK
896#else
897 //actuator dynamics
898 int8_t i;
900 for (i = 0; i < INDI_NUM_ACT; i++) {
902
904 + act_dyn_discrete[i] * (indi_u[i] - actuator_state[i]);
905
906#ifdef STABILIZATION_INDI_ACT_RATE_LIMIT
909 } else if ((actuator_state[i] - prev_actuator_state) < -act_rate_limit[i]) {
911 }
912#endif
913 }
914
915#endif
916}
917
928void calc_g1_element(float ddx_error, int8_t i, int8_t j, float mu)
929{
930 g1_est[i][j] = g1_est[i][j] - du_estimation[j] * mu * ddx_error;
931}
932
942void calc_g2_element(float ddx_error, int8_t j, float mu)
943{
944 g2_est[j] = g2_est[j] - ddu_estimation[j] * mu * ddx_error;
945}
946
953{
954
955 // Get the acceleration in body axes
956 struct Int32Vect3 *body_accel_i;
957 body_accel_i = stateGetAccelBody_i();
958 ACCELS_FLOAT_OF_BFP(body_accel_f, *body_accel_i);
959
960 // Filter the acceleration in z axis
962
963 // Calculate the derivative of the acceleration via finite difference
966
967 // scale the inputs to avoid numerical errors
970
972
973 //Estimation of G
974 // TODO: only estimate when du_norm2 is large enough (enough input)
975 /*float du_norm2 = du_estimation[0]*du_estimation[0] + du_estimation[1]*du_estimation[1] +du_estimation[2]*du_estimation[2] + du_estimation[3]*du_estimation[3];*/
976 int8_t i;
977 for (i = 0; i < INDI_OUTPUTS; i++) {
978 // Calculate the error between prediction and measurement
979 float ddx_error = - ddx_estimation[i];
980 int8_t j;
981 for (j = 0; j < INDI_NUM_ACT; j++) {
982 ddx_error += g1_est[i][j] * du_estimation[j];
983 if (i == 2) {
984 // Changing the momentum of the rotors gives a counter torque
986 }
987 }
988
989 // when doing the yaw axis, also use G2
990 if (i == 2) {
991 for (j = 0; j < INDI_NUM_ACT; j++) {
993 }
994 } else if (i == 3) {
995 // If the acceleration change is very large (rough landing), don't adapt
996 if (fabs(indi_accel_d) > 60.0) {
997 ddx_error = 0.0;
998 }
999 }
1000
1001 // Calculate the row of the G1 matrix corresponding to this axis
1002 for (j = 0; j < INDI_NUM_ACT; j++) {
1003 calc_g1_element(ddx_error, i, j, mu1[i]);
1004 }
1005 }
1006
1007 bound_g_mat();
1008
1009 // Save the calculated matrix to G1 and G2
1010 // until thrust is included, first part of the array
1013
1014 // Calculate sum of G1 and G2 for Bwls
1015 sum_g1_g2();
1016
1017#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
1018 // Calculate the inverse of (G1+G2)
1020#endif
1021}
1022
1027void sum_g1_g2(void)
1028{
1029 int8_t i;
1030 int8_t j;
1031 for (i = 0; i < INDI_OUTPUTS; i++) {
1032 for (j = 0; j < INDI_NUM_ACT; j++) {
1033 if (i != 2) {
1034 g1g2[i][j] = g1[i][j] / INDI_G_SCALING;
1035 } else {
1036 g1g2[i][j] = (g1[i][j] + g2[j]) / INDI_G_SCALING;
1037 }
1038 }
1039 }
1040}
1041
1042#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
1047void calc_g1g2_pseudo_inv(void)
1048{
1049 //G1G2*transpose(G1G2)
1050 //calculate matrix multiplication of its transpose INDI_OUTPUTSxnum_act x num_actxINDI_OUTPUTS
1051 float element = 0;
1052 int8_t row;
1053 int8_t col;
1054 int8_t i;
1055 for (row = 0; row < INDI_OUTPUTS; row++) {
1056 for (col = 0; col < INDI_OUTPUTS; col++) {
1057 element = 0;
1058 for (i = 0; i < INDI_NUM_ACT; i++) {
1059 element = element + g1g2[row][i] * g1g2[col][i];
1060 }
1061 g1g2_trans_mult[row][col] = element;
1062 }
1063 }
1064
1065 //there are numerical errors if the scaling is not right.
1067
1068 //inverse of 4x4 matrix
1070
1071 //scale back
1073
1074 //G1G2'*G1G2inv
1075 //calculate matrix multiplication INDI_NUM_ACTxINDI_OUTPUTS x INDI_OUTPUTSxINDI_OUTPUTS
1076 for (row = 0; row < INDI_NUM_ACT; row++) {
1077 for (col = 0; col < INDI_OUTPUTS; col++) {
1078 element = 0;
1079 for (i = 0; i < INDI_OUTPUTS; i++) {
1080 element = element + g1g2[i][row] * g1g2inv[col][i];
1081 }
1082 g1g2_pseudo_inv[row][col] = element;
1083 }
1084 }
1085}
1086#endif
1087
1088#if STABILIZATION_INDI_RPM_FEEDBACK
1090{
1091 int8_t i;
1092 for (i = 0; i < num_act; i++) {
1093 // Sanity check that index is valid
1094 if (feedback[i].idx < INDI_NUM_ACT && feedback[i].set.rpm) {
1095 int8_t idx = feedback[i].idx;
1096 act_obs[idx] = (feedback[i].rpm - get_servo_min(idx));
1098 Bound(act_obs[idx], 0, MAX_PPRZ);
1099 }
1100 }
1101}
1102#endif
1103
1104static void bound_g_mat(void)
1105{
1106 int8_t i;
1107 int8_t j;
1108 for (j = 0; j < INDI_NUM_ACT; j++) {
1109 float max_limit;
1110 float min_limit;
1111
1112 // Limit the values of the estimated G1 matrix
1113 for (i = 0; i < INDI_OUTPUTS; i++) {
1114 if (g1_init[i][j] > 0.0) {
1117 } else {
1120 }
1121
1122 if (g1_est[i][j] > max_limit) {
1123 g1_est[i][j] = max_limit;
1124 }
1125 if (g1_est[i][j] < min_limit) {
1126 g1_est[i][j] = min_limit;
1127 }
1128 }
1129
1130 // Do the same for the G2 matrix
1131 if (g2_init[j] > 0.0) {
1134 } else {
1137 }
1138
1139 if (g2_est[j] > max_limit) {
1140 g2_est[j] = max_limit;
1141 }
1142 if (g2_est[j] < min_limit) {
1143 g2_est[j] = min_limit;
1144 }
1145 }
1146}
1147
Main include for ABI (AirBorneInterface).
Event structure to store callbacks in a linked list.
Definition abi_common.h:68
bool autopilot_get_motors_on(void)
get motors status
Definition autopilot.c:295
#define UNUSED(x)
float q
in rad/s
float phi
in radians
float p
in rad/s
float r
in rad/s
float theta
in radians
float psi
in radians
static void float_vect_zero(float *a, const int n)
a = 0
void float_eulers_of_quat_zxy(struct FloatEulers *e, const struct FloatQuat *q)
euler rotation 'ZXY' This rotation order is useful if you need 90 deg pitch
static void float_vect_smul(float *o, const float *a, const float s, const int n)
o = a * s
#define FLOAT_VECT3_ZERO(_v)
static void float_vect_scale(float *a, const float s, const int n)
a *= s
static void float_mat_vect_mul(float *o, float **a, const float *b, const int m, const int n)
o = a * b
static float float_vect_dot_product(const float *a, const float *b, const int n)
a.b
static void float_vect_copy(float *a, const float *b, const int n)
a = b
static void float_vect_diff(float *o, const float *a, const float *b, const int n)
o = a - b
bool float_mat_inv_4d(float invOut[4][4], const float mat_in[4][4])
4x4 Matrix inverse
void float_quat_tilt_twist(struct FloatQuat *tilt, struct FloatQuat *twist, const struct FloatQuat *quat)
Tilt twist decomposition of quaternion.
void float_quat_inv_comp_norm_shortest(struct FloatQuat *b2c, const struct FloatQuat *a2b, const struct FloatQuat *a2c)
Composition (multiplication) of two quaternions with normalization.
euler angles
Roation quaternion.
angular rates
#define RATES_ADD(_a, _b)
#define QUAT_FLOAT_OF_BFP(_qf, _qi)
#define VECT3_ADD(_a, _b)
#define EULERS_FLOAT_OF_BFP(_ef, _ei)
#define ACCELS_FLOAT_OF_BFP(_ef, _ei)
euler angles
Rotation quaternion.
static struct Int32Quat * stateGetNedToBodyQuat_i(void)
Get vehicle body attitude quaternion (int).
Definition state.h:1284
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
Definition state.h:1314
static struct FloatQuat * stateGetNedToBodyQuat_f(void)
Get vehicle body attitude quaternion (float).
Definition state.h:1302
static struct FloatRates * stateGetBodyRates_f(void)
Get vehicle body angular rate (float).
Definition state.h:1375
static struct Int32Vect3 * stateGetAccelBody_i(void)
Get acceleration in Body coordinates (int).
Definition state.h:1094
static float stateGetAirspeed_f(void)
Get airspeed (float).
Definition state.h:1598
static float p[2][2]
PRINT_CONFIG_MSG("USE_INS_NAV_INIT defaulting to TRUE")
Simple first order low pass filter with bilinear transform.
float o[2]
output history
static void init_first_order_low_pass(struct FirstOrderLowPass *filter, float tau, const float sample_time, float value)
Init first order low pass filter.
static float update_first_order_low_pass(struct FirstOrderLowPass *filter, const float value)
Update first order low pass filter state with a new value.
static void init_butterworth_2_low_pass(Butterworth2LowPass *filter, const float tau, const float sample_time, const float value)
Init a second order Butterworth filter.
static float update_butterworth_2_low_pass(Butterworth2LowPass *filter, const float value)
Update second order Butterworth low pass filter state with a new value.
First order low pass filter structure.
Second order low pass filter structure.
uint16_t foo
Definition main_demo5.c:58
Hardware independent API for actuators (servos, motor controllers).
int32_t rpm
RPM.
Definition actuators.h:51
uint8_t idx
General index of the actuators (generated in airframe.h)
Definition actuators.h:45
static uint32_t idx
PRINT_CONFIG_VAR(ONELOOP_ANDI_FILT_CUTOFF)
#define MAX_PPRZ
Definition paparazzi.h:8
static abi_event act_feedback_ev
Paparazzi floating point algebra.
struct RadioControl radio_control
Generic interface for radio control modules.
pprz_t values[RADIO_CONTROL_NB_CHANNEL]
struct HorizontalGuidance guidance_h
Definition guidance_h.c:45
#define GUIDANCE_H_MODE_NAV
Definition guidance_h.h:58
#define GUIDANCE_H_MODE_HOVER
Definition guidance_h.h:57
struct FloatRates stab_sp_to_rates_f(struct StabilizationSetpoint *sp)
float th_sp_to_incr_f(struct ThrustSetpoint *th, int32_t thrust, uint8_t axis)
struct Int32Quat stab_sp_to_quat_i(struct StabilizationSetpoint *sp)
struct Int32Eulers stab_sp_to_eulers_i(struct StabilizationSetpoint *sp)
struct StabilizationSetpoint stab_sp_from_rates_f(struct FloatRates *rates)
struct FloatQuat stab_sp_to_quat_f(struct StabilizationSetpoint *sp)
int32_t th_sp_to_thrust_i(struct ThrustSetpoint *th, int32_t thrust, uint8_t axis)
#define THRUST_AXIS_X
#define THRUST_AXIS_Z
#define THRUST_AXIS_Y
Quaternion transformation functions.
Read an attitude setpoint from the RC.
static void calc_g1_element(float dx_error, int8_t i, int8_t j, float mu_extra)
#define STABILIZATION_INDI_WLS_WU
Butterworth2LowPass acceleration_lowpass_filter
static void send_eff_mat_g_indi(struct transport_tx *trans, struct link_device *dev)
static void send_ahrs_ref_quat(struct transport_tx *trans, struct link_device *dev)
void stabilization_indi_enter(void)
Function that resets important values upon engaging INDI.
float act_pref[INDI_NUM_ACT]
struct FloatRates WEAK stabilization_indi_attitude_controller(struct FloatQuat att, struct FloatQuat att_sp, struct FloatRates rates_ff)
Default PD angular rate controller.
#define STABILIZATION_INDI_ACT_PREF
float * Bwls[INDI_OUTPUTS]
int32_t stabilization_att_indi_cmd[COMMANDS_NB]
struct Indi_gains indi_gains
void WEAK stabilization_indi_set_wls_settings(void)
Function that sets the u_min, u_max and u_pref if function not elsewhere defined.
#define STABILIZATION_INDI_THROTTLE_LIMIT_AIRSPEED_FWD
static bool act_thrust_mat[3][INDI_NUM_ACT]
bool act_is_servo[INDI_NUM_ACT]
static struct FirstOrderLowPass rates_filt_fo[3]
float angular_acceleration[3]
static void send_wls_v_stab(struct transport_tx *trans, struct link_device *dev)
int32_t num_thrusters
float actuator_state_filt_vectd[INDI_NUM_ACT]
#define STABILIZATION_INDI_ADAPTIVE_MU
float r_filt
#define STABILIZATION_INDI_FILT_CUTOFF_P
static void bound_g_mat(void)
float mu1[INDI_OUTPUTS]
#define STABILIZATION_INDI_FILT_CUTOFF_Q
struct WLS_t wls_stab_p
#define STABILIZATION_INDI_ACT_IS_THRUSTER_X
float g1g2[INDI_OUTPUTS][INDI_NUM_ACT]
static void calc_g2_element(float dx_error, int8_t j, float mu_extra)
float q_filt
static struct Int32Eulers stab_att_sp_euler
static void send_wls_u_stab(struct transport_tx *trans, struct link_device *dev)
float estimation_rate_d[INDI_NUM_ACT]
static void init_filters(void)
Function that resets the filters to zeros.
#define STABILIZATION_INDI_YAW_DISTURBANCE_LIMIT
Limit the maximum specific moment that can be compensated (units rad/s^2)
float du_estimation[INDI_NUM_ACT]
float actuator_state_filt_vectdd[INDI_NUM_ACT]
Butterworth2LowPass measurement_lowpass_filters[3]
void stabilization_indi_update_filt_freq(float freq)
static struct FloatRates filter_rates(struct FloatRates *rates)
float g2[INDI_NUM_ACT]
struct FloatVect3 body_accel_f
float ddu_estimation[INDI_NUM_ACT]
float estimation_rate_dd[INDI_NUM_ACT]
float mu2
float act_obs[INDI_NUM_ACT]
float g1[INDI_OUTPUTS][INDI_NUM_ACT]
void stabilization_indi_init(void)
Function that initializes important values upon engaging INDI.
struct FloatRates angular_rate_ref
struct FloatVect3 stab_thrust_filt
#define STABILIZATION_INDI_WLS_PRIORITIES
float stablization_indi_yaw_dist_limit
float g1g2inv[INDI_OUTPUTS][INDI_OUTPUTS]
void stabilization_indi_attitude_run(bool in_flight, struct StabilizationSetpoint *att_sp, struct ThrustSetpoint *thrust, int32_t *cmd)
float actuator_state_filt_vect[INDI_NUM_ACT]
#define STABILIZATION_INDI_USE_ADAPTIVE
#define STABILIZATION_INDI_ACT_IS_SERVO
void stabilization_indi_rate_run(bool in_flight, struct StabilizationSetpoint *sp, struct ThrustSetpoint *thrust, int32_t *cmd)
float act_first_order_cutoff[INDI_NUM_ACT]
float act_dyn_discrete[INDI_NUM_ACT]
struct FloatRates angular_accel_ref
float g1g2_trans_mult[INDI_OUTPUTS][INDI_OUTPUTS]
#define STABILIZATION_INDI_FILT_CUTOFF_R
#define STABILIZATION_INDI_ACT_IS_THRUSTER_Y
bool indi_use_adaptive
float g2_init[INDI_NUM_ACT]
Butterworth2LowPass estimation_input_lowpass_filters[INDI_NUM_ACT]
static void sum_g1_g2(void)
Function that sums g1 and g2 to obtain the g1g2 matrix It also undoes the scaling that was done to ma...
float g1g2_pseudo_inv[INDI_NUM_ACT][INDI_OUTPUTS]
float g2_est[INDI_NUM_ACT]
float g1_init[INDI_OUTPUTS][INDI_NUM_ACT]
static struct Int32Quat stab_att_sp_quat
float actuator_state[INDI_NUM_ACT]
struct FloatRates WEAK stabilization_indi_rate_controller(struct FloatRates rates, struct FloatRates sp)
Default PD angular acceleration controller.
static void lms_estimation(void)
Function that estimates the control effectiveness of each actuator online.
static void send_att_full_indi(struct transport_tx *trans, struct link_device *dev)
#define INDI_ALLOWED_G_FACTOR
float g1_est[INDI_OUTPUTS][INDI_NUM_ACT]
float indi_v[INDI_OUTPUTS]
float stabilization_indi_filter_freq
int16_t actuators_pprz[INDI_NUM_ACT+1]
PPRZ command to each actuator Can be used to directly control actuators from the control algorithm if...
float indi_u[INDI_NUM_ACT]
static void get_actuator_state(void)
Function that tries to get actuator feedback.
Butterworth2LowPass actuator_lowpass_filters[INDI_NUM_ACT]
Butterworth2LowPass estimation_output_lowpass_filters[3]
#define INDI_G_SCALING
#define STABILIZATION_INDI_ESTIMATION_FILT_CUTOFF
#define STABILIZATION_INDI_FILT_CUTOFF
struct FloatRates rate
struct FloatRates att
API to get/set the generic vehicle states.
static const struct usb_device_descriptor dev
Definition usb_ser_hw.c:74
Stabilization setpoint.
union StabilizationSetpoint::@278 sp
Thrust setpoint // TODO to a setpoint header Structure to store the desired thrust vector with differ...
enum ThrustSetpoint::@282 type
int16_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint16_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
static void act_feedback_cb(uint8_t sender_id, struct act_feedback_t *feedback, uint8_t num_act)
RPM callback for RPM based control throttle curves.
int int32_t
Typedef defining 32 bit int type.
short int16_t
Typedef defining 16 bit short type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
signed char int8_t
Typedef defining 8 bit char type.
void send_wls_v(char *name, struct WLS_t *WLS_p, struct transport_tx *trans, struct link_device *dev)
Definition wls_alloc.c:61
void wls_alloc(struct WLS_t *WLS_p, float **B, float *u_guess, float *W_init, int imax)
active set algorithm for control allocation
Definition wls_alloc.c:119
void send_wls_u(char *name, struct WLS_t *WLS_p, struct transport_tx *trans, struct link_device *dev)
Definition wls_alloc.c:71
float u[WLS_N_U_MAX]
Definition wls_alloc.h:71
float u_min[WLS_N_U_MAX]
Definition wls_alloc.h:75
float u_max[WLS_N_U_MAX]
Definition wls_alloc.h:76
float u_pref[WLS_N_U_MAX]
Definition wls_alloc.h:74
float v[WLS_N_V_MAX]
Definition wls_alloc.h:70
int nu
Definition wls_alloc.h:67