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_COMMANDS
225#endif
226
227#ifdef STABILIZATION_INDI_ACT_DYN
228#warning STABILIZATION_INDI_ACT_DYN is deprecated, use STABILIZATION_INDI_ACT_FREQ instead.
229#warning You now have to define the continuous time corner frequency in rad/s of the actuators.
230#warning "Use -ln(1 - old_number) * PERIODIC_FREQUENCY to compute it from the old values."
232#else
234float act_dyn_discrete[INDI_NUM_ACT]; // will be computed from freq at init
235#endif
236
238
239// variables needed for control
241struct FloatRates angular_accel_ref = {0., 0., 0.};
242struct FloatRates angular_rate_ref = {0., 0., 0.};
243float angular_acceleration[3] = {0., 0., 0.};
246struct FloatVect3 stab_thrust_filt = { 0.f, 0.f, 0.f };
247
248float q_filt = 0.0;
249float r_filt = 0.0;
250
251float stabilization_indi_filter_freq = 20.0; //Hz, for setting handler
252
253// variables needed for estimation
262
263// The learning rate per axis (roll, pitch, yaw, thrust)
264float mu1[INDI_OUTPUTS] = {0.00001, 0.00001, 0.000003, 0.000002};
265// The learning rate for the propeller inertia (scaled by 512 wrt mu1)
266float mu2 = 0.002;
267
268// other variables
270
271// Number of actuators used to provide thrust
273
276
277// Register actuator feedback if we rely on RPM information
278#if STABILIZATION_INDI_RPM_FEEDBACK
279#ifndef STABILIZATION_INDI_ACT_FEEDBACK_ID
280#define STABILIZATION_INDI_ACT_FEEDBACK_ID ABI_BROADCAST
281#endif
283
285static void act_feedback_cb(uint8_t sender_id, struct act_feedback_t *feedback, uint8_t num_act);
286PRINT_CONFIG_MSG("STABILIZATION_INDI_RPM_FEEDBACK")
287#endif
288
290float g2[INDI_NUM_ACT] = STABILIZATION_INDI_G2; //scaled by INDI_G_SCALING
291#ifdef STABILIZATION_INDI_G1
293#else // old defines TODO remove
294#if INDI_OUTPUTS == 5
298 };
299
300#else
304#endif
305#endif
306
312
313// Can be used to directly control each actuator from the control algorithm
315
321#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
323#else
325#endif
327
328static void init_filters(void);
329static struct FloatRates filter_rates(struct FloatRates *rates);
330static void sum_g1_g2(void);
331
332#if PERIODIC_TELEMETRY
334#if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
335static void send_wls_v_stab(struct transport_tx *trans, struct link_device *dev)
336{
337 send_wls_v("stab", &wls_stab_p, trans, dev);
338}
339static void send_wls_u_stab(struct transport_tx *trans, struct link_device *dev)
340{
341 send_wls_u("stab", &wls_stab_p, trans, dev);
342}
343#endif
344static void send_eff_mat_g_indi(struct transport_tx *trans, struct link_device *dev)
345{
347 INDI_NUM_ACT, g1g2[0],
348 INDI_NUM_ACT, g1g2[1],
349 INDI_NUM_ACT, g1g2[2],
351#if INDI_OUTPUTS <= 5
352 float zero = 0;
353#endif
354#if INDI_OUTPUTS > 3
356#if INDI_OUTPUTS == 4
357 1, &zero,
358 1, &zero,
360#elif INDI_OUTPUTS == 5
361 INDI_NUM_ACT, g1g2[4],
362 1, &zero,
364#elif INDI_OUTPUTS == 6
365 INDI_NUM_ACT, g1g2[3],
366 INDI_NUM_ACT, g1g2[4],
368#endif
369 );
370#endif
371}
372
373static void send_ahrs_ref_quat(struct transport_tx *trans, struct link_device *dev)
374{
375 struct Int32Quat *quat = stateGetNedToBodyQuat_i();
381 &(quat->qi),
382 &(quat->qx),
383 &(quat->qy),
384 &(quat->qz));
385}
386
387static void send_att_full_indi(struct transport_tx *trans, struct link_device *dev)
388{
389 float zero = 0.0;
391 struct FloatEulers att, att_sp;
392#if GUIDANCE_INDI_HYBRID
397#else
400#endif
401 float temp_att[3] = {att.phi, att.theta, att.psi};
402 float temp_att_ref[3] = {att_sp.phi, att_sp.theta, att_sp.psi};
403 float temp_rate[3] = {body_rates->p, body_rates->q, body_rates->r};
407 1, &zero, // att des
408 3, temp_att, // att
409 3, temp_att_ref, // att ref
410 3, temp_rate, // rate
411 3, temp_rate_ref, // rate ref
412 3, angular_acceleration, // ang.acc = rate.diff
413 3, temp_ang_acc_ref, // ang.acc.ref
414 1, &zero, // jerk ref
415 1, &zero); // u
416}
417#endif
418
423{
424 // Initialize filters
425 init_filters();
426
427 int8_t i;
428// If the deprecated STABILIZATION_INDI_ACT_DYN is used, convert it to the new FREQUENCY format
429#ifdef STABILIZATION_INDI_ACT_FREQ
430 // Initialize the array of pointers to the rows of g1g2
431 for (i = 0; i < INDI_NUM_ACT; i++) {
433 }
434#endif
435
436#if STABILIZATION_INDI_RPM_FEEDBACK
438#endif
439
445
446 //Calculate G1G2
447 sum_g1_g2();
448
449 // Do not compute if not needed
450#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
451 //Calculate G1G2_PSEUDO_INVERSE
453#endif
454
455 // Initialize the array of pointers to the rows of g1g2
456 for (i = 0; i < INDI_OUTPUTS; i++) {
457 Bwls[i] = g1g2[i];
458 }
459
460 // Initialize the estimator matrices
463 // Remember the initial matrices
466
467 num_thrusters = 0; // sum of Z thrusters
468 for (i = 0; i < INDI_NUM_ACT; i++) {
469#ifndef STABILIZATION_INDI_ACT_IS_THRUSTER_Z
470 // Assume non-servos and non thrust-x/y motors, not already set to true, are delivering (Z) thrust
471 act_thrust_mat[2][i] = act_thrust_mat[2][i] || (!act_thrust_mat[0][i] && !act_thrust_mat[1][i] && !act_is_servo[i]);
472#endif
473 if (act_thrust_mat[2][i]) {
475 }
476 }
477
478#if PERIODIC_TELEMETRY
482 #if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
485 #endif
486#endif
487}
488
502
518
522static void init_filters(void)
523{
524 // tau = 1/(2*pi*Fc)
525 float tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF);
527 float sample_time = 1.0 / PERIODIC_FREQUENCY;
528 // Filtering of the gyroscope
529 int8_t i;
530 for (i = 0; i < 3; i++) {
533 }
534
535 // Filtering of the actuators
536 for (i = 0; i < INDI_NUM_ACT; i++) {
539 }
540
541 // Filtering of the accel body z
543
544#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
545 tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF_P);
547 tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF_Q);
549 tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF_R);
551#else
552 // Init rate filter for feedback
554
558#endif
559}
560
561static struct FloatRates filter_rates(struct FloatRates *rates)
562{
563 struct FloatRates rates_filt;
564#if STABILIZATION_INDI_FILTER_ROLL_RATE
565#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
567#else
569#endif
570#else
571 rates_filt.p = rates->p;
572#endif
573#if STABILIZATION_INDI_FILTER_PITCH_RATE
574#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
576#else
578#endif
579#else
580 rates_filt.q = rates->q;
581#endif
582#if STABILIZATION_INDI_FILTER_YAW_RATE
583#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
585#else
587#endif
588#else
589 rates_filt.r = rates->r;
590#endif
591 return rates_filt;
592}
593
602void stabilization_indi_rate_run(bool in_flight, struct StabilizationSetpoint *sp, struct ThrustSetpoint *thrust, int32_t *cmd)
603{
604
605 // Propagate actuator filters
608 for (int i = 0; i < INDI_NUM_ACT; i++) {
613
614 // calculate derivatives for estimation
619 }
620
621 // Use the last actuator state for this computation
623
624 // Predict angular acceleration u*B
628
629 /* Propagate the filter on the gyroscopes */
631 float rate_vect[3] = {body_rates->p, body_rates->q, body_rates->r};
632
633 // Get the acceleration in body axes
634 struct Int32Vect3 *body_accel_i;
635 body_accel_i = stateGetAccelBody_i();
636 ACCELS_FLOAT_OF_BFP(body_accel_f, *body_accel_i);
637
638 int8_t i;
639 for (i = 0; i < 3; i++) {
642
643 // Calculate the angular acceleration via finite difference
646
647 // Calculate derivatives for estimation
652 }
653
654 // subtract u*B from angular acceleration
657
658 if (in_flight) {
659 // Limit the estimated disturbance in yaw for drones that are stable in sideslip
661 } else {
662 // Not in flight, so don't estimate disturbance
664 }
665
666 // The rates used for feedback are by default the measured rates.
667 // If there is a lot of noise on the gyroscope, it might be good to use the filtered value for feedback.
668 // Note that due to the delay, the controller may need relaxed gains.
670
671 // calculate the virtual control (reference acceleration) based on a controller
674
675 // compute virtual thrust
676 struct FloatVect3 v_thrust = { 0.f, 0.f, 0.f };
677 if (thrust->type == THRUST_INCR_SP) {
679 v_thrust.y = th_sp_to_incr_f(thrust, 0, THRUST_AXIS_Y);
680 v_thrust.z = th_sp_to_incr_f(thrust, 0, THRUST_AXIS_Z);
681
682 // Compute estimated thrust
684 for (i = 0; i < INDI_NUM_ACT; i++) {
685#if INDI_OUTPUTS == 4
687#endif
688#if INDI_OUTPUTS == 5 // FIXME change order of Z and X, or better detect that automatically ?
691#endif
692#if INDI_OUTPUTS == 6
696#endif
697 }
698 // Add the current estimated thrust to the increment
700 } else {
701 // build incremental thrust
702 struct FloatVect3 th_cmd;
706#if (INDI_OUTPUTS == 5) && (defined RADIO_CONTROL_THRUST_X) && (defined COMMAND_THRUST_X)
707 // TODO set X thrust from RC in the thrust input setpoint
709 th_cmd.x = (float)cmd[COMMAND_THRUST_X];
710#endif
711 for (i = 0; i < INDI_NUM_ACT; i++) {
712#if INDI_OUTPUTS == 4
713 v_thrust.z += th_cmd.z * Bwls[3][i] * (int32_t) act_thrust_mat[2][i];
714#endif
715#if INDI_OUTPUTS == 5 // FIXME change order of Z and X, or better detect that automatically ?
716 v_thrust.x += th_cmd.x * Bwls[4][i] * (int32_t) act_thrust_mat[0][i];
717 v_thrust.z += th_cmd.z * Bwls[3][i] * (int32_t) act_thrust_mat[2][i];
718#endif
719#if INDI_OUTPUTS == 6
720 v_thrust.x += th_cmd.x * Bwls[3][i] * (int32_t) act_thrust_mat[0][i];
721 v_thrust.y += th_cmd.y * Bwls[4][i] * (int32_t) act_thrust_mat[1][i];
722 v_thrust.z += th_cmd.z * Bwls[5][i] * (int32_t) act_thrust_mat[2][i];
723#endif
724 }
725 // store estimated thrust
727 }
728
729 // This term compensates for the spinup torque in the yaw axis
731
732 if (in_flight) {
733 // Limit the estimated disturbance in yaw for drones that are stable in sideslip
735 } else {
736 // Not in flight, so don't estimate disturbance
738 }
739
740 // The control objective in array format
744#if INDI_OUTPUTS == 4
745 indi_v[3] = v_thrust.z;
746#endif
747#if INDI_OUTPUTS == 5 // FIXME order of Z/X is reversed
748 indi_v[3] = v_thrust.z;
749 indi_v[4] = v_thrust.x;
750#endif
751#if INDI_OUTPUTS == 6
752 indi_v[3] = v_thrust.x;
753 indi_v[4] = v_thrust.y;
754 indi_v[5] = v_thrust.z;
755#endif
756
757#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
758 // Calculate the increment for each actuator
759 for (i = 0; i < INDI_NUM_ACT; i++) {
760 indi_u[i] = (g1g2_pseudo_inv[i][0] * indi_v[0])
761 + (g1g2_pseudo_inv[i][1] * indi_v[1])
762 + (g1g2_pseudo_inv[i][2] * indi_v[2])
763 + (g1g2_pseudo_inv[i][3] * indi_v[3]);
764 }
765#else
767
768 // WLS Control Allocator
769 for (i = 0; i < INDI_OUTPUTS; i++) {
770 wls_stab_p.v[i] = indi_v[i];
771 }
772 wls_alloc(&wls_stab_p, Bwls, 0, 0, 10);
773 for (i = 0; i < INDI_NUM_ACT; i++) {
774 indi_u[i] = wls_stab_p.u[i];
775 }
776#endif
777
778 // Use online effectiveness estimation only when flying
779 if (in_flight && indi_use_adaptive) {
781 }
782
783 // update actuators and thrust commands
784 cmd[COMMAND_THRUST] = 0;
785 for (i = 0; i < INDI_NUM_ACT; i++) {
786 // bound actuator command
787 if (act_is_servo[i]) {
789 } else {
791 Bound(indi_u[i], 0, MAX_PPRZ);
792 } else {
793 indi_u[i] = -MAX_PPRZ;
794 }
795 }
796
797 // commit actuator command
798 actuators_pprz[i] = (int16_t) indi_u[i];
799#ifdef STABILIZATION_INDI_COMMANDS
800 // copy to actuators to specified commands
801 cmd[act_to_commands[i]] = actuators_pprz[i];
802#endif
803
804 // update thrust command such that the current is correctly estimated
806 }
808}
809
818void stabilization_indi_attitude_run(bool in_flight, struct StabilizationSetpoint *att_sp, struct ThrustSetpoint *thrust, int32_t *cmd)
819{
820 stab_att_sp_euler = stab_sp_to_eulers_i(att_sp); // stab_att_sp_euler.psi still used in ref..
821 stab_att_sp_quat = stab_sp_to_quat_i(att_sp); // quat attitude setpoint
822
826
827 // calculate the virtual control (reference acceleration) based on a controller
829
830 /* compute the INDI command */
832 stabilization_indi_rate_run(in_flight, &sp, thrust, cmd);
833}
834
841{
842 /* attitude error */
843 struct FloatQuat att_err;
845
846 struct FloatVect3 att_fb;
847#if TILT_TWIST_CTRL
848 struct FloatQuat tilt;
849 struct FloatQuat twist;
851 att_fb.x = tilt.qx;
852 att_fb.y = tilt.qy;
853 att_fb.z = twist.qz;
854#else
855 att_fb.x = att_err.qx;
856 att_fb.y = att_err.qy;
857 att_fb.z = att_err.qz;
858#endif
859
860 struct FloatRates rates_ref;
864 // add feed-forward term
866 return rates_ref;
867}
868
875{
876 struct FloatRates accel_ref;
877 accel_ref.p = (sp.p - rates.p) * indi_gains.rate.p;
878 accel_ref.q = (sp.q - rates.q) * indi_gains.rate.q;
879 accel_ref.r = (sp.r - rates.r) * indi_gains.rate.r;
880 return accel_ref;
881}
882
883
887#if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
889{
890 // Calculate the min and max increments
891 for (uint8_t i = 0; i < INDI_NUM_ACT; i++) {
894 wls_stab_p.u_pref[i] = act_pref[i];
895
896#ifdef GUIDANCE_INDI_MIN_THROTTLE
897 float airspeed = stateGetAirspeed_f();
898 //limit minimum thrust ap can give
899 if (!act_is_servo[i]) {
903 } else {
905 }
906 }
907 }
908#endif
909 }
910}
911#endif
912
920{
921#if STABILIZATION_INDI_RPM_FEEDBACK
923#else
924 //actuator dynamics
925 int8_t i;
927 for (i = 0; i < INDI_NUM_ACT; i++) {
929
931 + act_dyn_discrete[i] * (indi_u[i] - actuator_state[i]);
932
933#ifdef STABILIZATION_INDI_ACT_RATE_LIMIT
936 } else if ((actuator_state[i] - prev_actuator_state) < -act_rate_limit[i]) {
938 }
939#endif
940 }
941
942#endif
943}
944
945#ifdef STABILIZATION_INDI_COMMANDS
951void set_rotorcraft_commands(pprz_t *cmd_out, int32_t *cmd_in, bool in_flight __attribute__((unused)), bool motors_on)
952{
953 for (int i = 0; i < INDI_NUM_ACT; i++) {
954 bool is_motor = act_thrust_mat[0][i] || act_thrust_mat[1][i] || act_thrust_mat[2][i];
955 if (is_motor && !motors_on) {
957 } else {
959 }
960 }
961 // for GCS display
962 if (!motors_on) {
964 }
966}
967#endif
968
979void calc_g1_element(float ddx_error, int8_t i, int8_t j, float mu)
980{
981 g1_est[i][j] = g1_est[i][j] - du_estimation[j] * mu * ddx_error;
982}
983
993void calc_g2_element(float ddx_error, int8_t j, float mu)
994{
995 g2_est[j] = g2_est[j] - ddu_estimation[j] * mu * ddx_error;
996}
997
1004{
1005
1006 // Get the acceleration in body axes
1007 struct Int32Vect3 *body_accel_i;
1008 body_accel_i = stateGetAccelBody_i();
1009 ACCELS_FLOAT_OF_BFP(body_accel_f, *body_accel_i);
1010
1011 // Filter the acceleration in z axis
1013
1014 // Calculate the derivative of the acceleration via finite difference
1017
1018 // scale the inputs to avoid numerical errors
1021
1023
1024 //Estimation of G
1025 // TODO: only estimate when du_norm2 is large enough (enough input)
1026 /*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];*/
1027 int8_t i;
1028 for (i = 0; i < INDI_OUTPUTS; i++) {
1029 // Calculate the error between prediction and measurement
1030 float ddx_error = - ddx_estimation[i];
1031 int8_t j;
1032 for (j = 0; j < INDI_NUM_ACT; j++) {
1033 ddx_error += g1_est[i][j] * du_estimation[j];
1034 if (i == 2) {
1035 // Changing the momentum of the rotors gives a counter torque
1037 }
1038 }
1039
1040 // when doing the yaw axis, also use G2
1041 if (i == 2) {
1042 for (j = 0; j < INDI_NUM_ACT; j++) {
1044 }
1045 } else if (i == 3) {
1046 // If the acceleration change is very large (rough landing), don't adapt
1047 if (fabs(indi_accel_d) > 60.0) {
1048 ddx_error = 0.0;
1049 }
1050 }
1051
1052 // Calculate the row of the G1 matrix corresponding to this axis
1053 for (j = 0; j < INDI_NUM_ACT; j++) {
1054 calc_g1_element(ddx_error, i, j, mu1[i]);
1055 }
1056 }
1057
1058 bound_g_mat();
1059
1060 // Save the calculated matrix to G1 and G2
1061 // until thrust is included, first part of the array
1064
1065 // Calculate sum of G1 and G2 for Bwls
1066 sum_g1_g2();
1067
1068#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
1069 // Calculate the inverse of (G1+G2)
1071#endif
1072}
1073
1078void sum_g1_g2(void)
1079{
1080 int8_t i;
1081 int8_t j;
1082 for (i = 0; i < INDI_OUTPUTS; i++) {
1083 for (j = 0; j < INDI_NUM_ACT; j++) {
1084 if (i != 2) {
1085 g1g2[i][j] = g1[i][j] / INDI_G_SCALING;
1086 } else {
1087 g1g2[i][j] = (g1[i][j] + g2[j]) / INDI_G_SCALING;
1088 }
1089 }
1090 }
1091}
1092
1093#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
1098void calc_g1g2_pseudo_inv(void)
1099{
1100 //G1G2*transpose(G1G2)
1101 //calculate matrix multiplication of its transpose INDI_OUTPUTSxnum_act x num_actxINDI_OUTPUTS
1102 float element = 0;
1103 int8_t row;
1104 int8_t col;
1105 int8_t i;
1106 for (row = 0; row < INDI_OUTPUTS; row++) {
1107 for (col = 0; col < INDI_OUTPUTS; col++) {
1108 element = 0;
1109 for (i = 0; i < INDI_NUM_ACT; i++) {
1110 element = element + g1g2[row][i] * g1g2[col][i];
1111 }
1112 g1g2_trans_mult[row][col] = element;
1113 }
1114 }
1115
1116 //there are numerical errors if the scaling is not right.
1118
1119 //inverse of 4x4 matrix
1121
1122 //scale back
1124
1125 //G1G2'*G1G2inv
1126 //calculate matrix multiplication INDI_NUM_ACTxINDI_OUTPUTS x INDI_OUTPUTSxINDI_OUTPUTS
1127 for (row = 0; row < INDI_NUM_ACT; row++) {
1128 for (col = 0; col < INDI_OUTPUTS; col++) {
1129 element = 0;
1130 for (i = 0; i < INDI_OUTPUTS; i++) {
1131 element = element + g1g2[i][row] * g1g2inv[col][i];
1132 }
1133 g1g2_pseudo_inv[row][col] = element;
1134 }
1135 }
1136}
1137#endif
1138
1139#if STABILIZATION_INDI_RPM_FEEDBACK
1141{
1142 int8_t i;
1143 for (i = 0; i < num_act; i++) {
1144 // Sanity check that index is valid
1145 if (feedback[i].idx < INDI_NUM_ACT && feedback[i].set.rpm) {
1146 int8_t idx = feedback[i].idx;
1147 act_obs[idx] = (feedback[i].rpm - get_servo_min(idx));
1149 Bound(act_obs[idx], 0, MAX_PPRZ);
1150 }
1151 }
1152}
1153#endif
1154
1155static void bound_g_mat(void)
1156{
1157 int8_t i;
1158 int8_t j;
1159 for (j = 0; j < INDI_NUM_ACT; j++) {
1160 float max_limit;
1161 float min_limit;
1162
1163 // Limit the values of the estimated G1 matrix
1164 for (i = 0; i < INDI_OUTPUTS; i++) {
1165 if (g1_init[i][j] > 0.0) {
1168 } else {
1171 }
1172
1173 if (g1_est[i][j] > max_limit) {
1174 g1_est[i][j] = max_limit;
1175 }
1176 if (g1_est[i][j] < min_limit) {
1177 g1_est[i][j] = min_limit;
1178 }
1179 }
1180
1181 // Do the same for the G2 matrix
1182 if (g2_init[j] > 0.0) {
1185 } else {
1188 }
1189
1190 if (g2_est[j] > max_limit) {
1191 g2_est[j] = max_limit;
1192 }
1193 if (g2_est[j] < min_limit) {
1194 g2_est[j] = min_limit;
1195 }
1196 }
1197}
1198
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)
static struct uart_periph * dev
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)
int16_t pprz_t
Definition paparazzi.h:6
#define MAX_PPRZ
Definition paparazzi.h:8
#define MIN_PPRZ
Definition paparazzi.h:9
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]
void WEAK set_rotorcraft_commands(pprz_t *cmd_out, int32_t *cmd_in, bool in_flight, bool motors_on)
Display descent speed in failsafe mode if needed.
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.
Stabilization setpoint.
union StabilizationSetpoint::@277 sp
Thrust setpoint // TODO to a setpoint header Structure to store the desired thrust vector with differ...
enum ThrustSetpoint::@281 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