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],
350 INDI_NUM_ACT, g1g2[3],
352}
353
354static void send_ahrs_ref_quat(struct transport_tx *trans, struct link_device *dev)
355{
356 struct Int32Quat *quat = stateGetNedToBodyQuat_i();
362 &(quat->qi),
363 &(quat->qx),
364 &(quat->qy),
365 &(quat->qz));
366}
367
368static void send_att_full_indi(struct transport_tx *trans, struct link_device *dev)
369{
370 float zero = 0.0;
372 struct FloatEulers att, att_sp;
373#if GUIDANCE_INDI_HYBRID
378#else
381#endif
382 float temp_att[3] = {att.phi, att.theta, att.psi};
383 float temp_att_ref[3] = {att_sp.phi, att_sp.theta, att_sp.psi};
384 float temp_rate[3] = {body_rates->p, body_rates->q, body_rates->r};
388 1, &zero, // att des
389 3, temp_att, // att
390 3, temp_att_ref, // att ref
391 3, temp_rate, // rate
392 3, temp_rate_ref, // rate ref
393 3, angular_acceleration, // ang.acc = rate.diff
394 3, temp_ang_acc_ref, // ang.acc.ref
395 1, &zero, // jerk ref
396 1, &zero); // u
397}
398#endif
399
404{
405 // Initialize filters
406 init_filters();
407
408 int8_t i;
409// If the deprecated STABILIZATION_INDI_ACT_DYN is used, convert it to the new FREQUENCY format
410#ifdef STABILIZATION_INDI_ACT_FREQ
411 // Initialize the array of pointers to the rows of g1g2
412 for (i = 0; i < INDI_NUM_ACT; i++) {
414 }
415#endif
416
417#if STABILIZATION_INDI_RPM_FEEDBACK
419#endif
420
426
427 //Calculate G1G2
428 sum_g1_g2();
429
430 // Do not compute if not needed
431#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
432 //Calculate G1G2_PSEUDO_INVERSE
434#endif
435
436 // Initialize the array of pointers to the rows of g1g2
437 for (i = 0; i < INDI_OUTPUTS; i++) {
438 Bwls[i] = g1g2[i];
439 }
440
441 // Initialize the estimator matrices
444 // Remember the initial matrices
447
448 num_thrusters = 0; // sum of Z thrusters
449 for (i = 0; i < INDI_NUM_ACT; i++) {
450#ifndef STABILIZATION_INDI_ACT_IS_THRUSTER_Z
451 // Assume non-servos and non thrust-x/y motors, not already set to true, are delivering (Z) thrust
452 act_thrust_mat[2][i] = act_thrust_mat[2][i] || (!act_thrust_mat[0][i] && !act_thrust_mat[1][i] && !act_is_servo[i]);
453#endif
454 if (act_thrust_mat[2][i]) {
456 }
457 }
458
459#if PERIODIC_TELEMETRY
463 #if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
466 #endif
467#endif
468}
469
483
499
503static void init_filters(void)
504{
505 // tau = 1/(2*pi*Fc)
506 float tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF);
508 float sample_time = 1.0 / PERIODIC_FREQUENCY;
509 // Filtering of the gyroscope
510 int8_t i;
511 for (i = 0; i < 3; i++) {
514 }
515
516 // Filtering of the actuators
517 for (i = 0; i < INDI_NUM_ACT; i++) {
520 }
521
522 // Filtering of the accel body z
524
525#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
526 tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF_P);
528 tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF_Q);
530 tau = 1.0 / (2.0 * M_PI * STABILIZATION_INDI_FILT_CUTOFF_R);
532#else
533 // Init rate filter for feedback
535
539#endif
540}
541
542static struct FloatRates filter_rates(struct FloatRates *rates)
543{
544 struct FloatRates rates_filt;
545#if STABILIZATION_INDI_FILTER_ROLL_RATE
546#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
548#else
550#endif
551#else
552 rates_filt.p = rates->p;
553#endif
554#if STABILIZATION_INDI_FILTER_PITCH_RATE
555#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
557#else
559#endif
560#else
561 rates_filt.q = rates->q;
562#endif
563#if STABILIZATION_INDI_FILTER_YAW_RATE
564#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
566#else
568#endif
569#else
570 rates_filt.r = rates->r;
571#endif
572 return rates_filt;
573}
574
583void stabilization_indi_rate_run(bool in_flight, struct StabilizationSetpoint *sp, struct ThrustSetpoint *thrust, int32_t *cmd)
584{
585
586 // Propagate actuator filters
589 for (int i = 0; i < INDI_NUM_ACT; i++) {
594
595 // calculate derivatives for estimation
600 }
601
602 // Use the last actuator state for this computation
604
605 // Predict angular acceleration u*B
609
610 /* Propagate the filter on the gyroscopes */
612 float rate_vect[3] = {body_rates->p, body_rates->q, body_rates->r};
613
614 // Get the acceleration in body axes
615 struct Int32Vect3 *body_accel_i;
616 body_accel_i = stateGetAccelBody_i();
617 ACCELS_FLOAT_OF_BFP(body_accel_f, *body_accel_i);
618
619 int8_t i;
620 for (i = 0; i < 3; i++) {
623
624 // Calculate the angular acceleration via finite difference
627
628 // Calculate derivatives for estimation
633 }
634
635 // subtract u*B from angular acceleration
638
639 if (in_flight) {
640 // Limit the estimated disturbance in yaw for drones that are stable in sideslip
642 } else {
643 // Not in flight, so don't estimate disturbance
645 }
646
647 // The rates used for feedback are by default the measured rates.
648 // If there is a lot of noise on the gyroscope, it might be good to use the filtered value for feedback.
649 // Note that due to the delay, the controller may need relaxed gains.
651
652 // calculate the virtual control (reference acceleration) based on a controller
655
656 // compute virtual thrust
657 struct FloatVect3 v_thrust = { 0.f, 0.f, 0.f };
658 if (thrust->type == THRUST_INCR_SP) {
660 v_thrust.y = th_sp_to_incr_f(thrust, 0, THRUST_AXIS_Y);
661 v_thrust.z = th_sp_to_incr_f(thrust, 0, THRUST_AXIS_Z);
662
663 // Compute estimated thrust
665 for (i = 0; i < INDI_NUM_ACT; i++) {
666#if INDI_OUTPUTS == 4
668#endif
669#if INDI_OUTPUTS == 5 // FIXME change order of Z and X, or better detect that automatically ?
672#endif
673#if INDI_OUTPUTS == 6
677#endif
678 }
679 // Add the current estimated thrust to the increment
681 } else {
682 // build incremental thrust
683 struct FloatVect3 th_cmd;
687#if (INDI_OUTPUTS == 5) && (defined RADIO_CONTROL_THRUST_X) && (defined COMMAND_THRUST_X)
688 // TODO set X thrust from RC in the thrust input setpoint
690 th_cmd.x = (float)cmd[COMMAND_THRUST_X];
691#endif
692 for (i = 0; i < INDI_NUM_ACT; i++) {
693#if INDI_OUTPUTS == 4
694 v_thrust.z += th_cmd.z * Bwls[3][i] * (int32_t) act_thrust_mat[2][i];
695#endif
696#if INDI_OUTPUTS == 5 // FIXME change order of Z and X, or better detect that automatically ?
697 v_thrust.x += th_cmd.x * Bwls[4][i] * (int32_t) act_thrust_mat[0][i];
698 v_thrust.z += th_cmd.z * Bwls[3][i] * (int32_t) act_thrust_mat[2][i];
699#endif
700#if INDI_OUTPUTS == 6
701 v_thrust.x += th_cmd.x * Bwls[3][i] * (int32_t) act_thrust_mat[0][i];
702 v_thrust.y += th_cmd.y * Bwls[4][i] * (int32_t) act_thrust_mat[1][i];
703 v_thrust.z += th_cmd.z * Bwls[5][i] * (int32_t) act_thrust_mat[2][i];
704#endif
705 }
706 // store estimated thrust
708 }
709
710 // This term compensates for the spinup torque in the yaw axis
712
713 if (in_flight) {
714 // Limit the estimated disturbance in yaw for drones that are stable in sideslip
716 } else {
717 // Not in flight, so don't estimate disturbance
719 }
720
721 // The control objective in array format
725#if INDI_OUTPUTS == 4
726 indi_v[3] = v_thrust.z;
727#endif
728#if INDI_OUTPUTS == 5 // FIXME order of Z/X is reversed
729 indi_v[3] = v_thrust.z;
730 indi_v[4] = v_thrust.x;
731#endif
732#if INDI_OUTPUTS == 6
733 indi_v[3] = v_thrust.x;
734 indi_v[4] = v_thrust.y;
735 indi_v[5] = v_thrust.z;
736#endif
737
738#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
739 // Calculate the increment for each actuator
740 for (i = 0; i < INDI_NUM_ACT; i++) {
741 indi_u[i] = (g1g2_pseudo_inv[i][0] * indi_v[0])
742 + (g1g2_pseudo_inv[i][1] * indi_v[1])
743 + (g1g2_pseudo_inv[i][2] * indi_v[2])
744 + (g1g2_pseudo_inv[i][3] * indi_v[3]);
745 }
746#else
748
749 // WLS Control Allocator
750 for (i = 0; i < INDI_OUTPUTS; i++) {
751 wls_stab_p.v[i] = indi_v[i];
752 }
753 wls_alloc(&wls_stab_p, Bwls, 0, 0, 10);
754 for (i = 0; i < INDI_NUM_ACT; i++) {
755 indi_u[i] = wls_stab_p.u[i];
756 }
757#endif
758
759 // Use online effectiveness estimation only when flying
760 if (in_flight && indi_use_adaptive) {
762 }
763
764 // update actuators and thrust commands
765 cmd[COMMAND_THRUST] = 0;
766 for (i = 0; i < INDI_NUM_ACT; i++) {
767 // bound actuator command
768 if (act_is_servo[i]) {
770 } else {
772 Bound(indi_u[i], 0, MAX_PPRZ);
773 } else {
774 indi_u[i] = -MAX_PPRZ;
775 }
776 }
777
778 // commit actuator command
779 actuators_pprz[i] = (int16_t) indi_u[i];
780#ifdef STABILIZATION_INDI_COMMANDS
781 // copy to actuators to specified commands
782 cmd[act_to_commands[i]] = actuators_pprz[i];
783#endif
784
785 // update thrust command such that the current is correctly estimated
787 }
789}
790
799void stabilization_indi_attitude_run(bool in_flight, struct StabilizationSetpoint *att_sp, struct ThrustSetpoint *thrust, int32_t *cmd)
800{
801 stab_att_sp_euler = stab_sp_to_eulers_i(att_sp); // stab_att_sp_euler.psi still used in ref..
802 stab_att_sp_quat = stab_sp_to_quat_i(att_sp); // quat attitude setpoint
803
807
808 // calculate the virtual control (reference acceleration) based on a controller
810
811 /* compute the INDI command */
813 stabilization_indi_rate_run(in_flight, &sp, thrust, cmd);
814}
815
822{
823 /* attitude error */
824 struct FloatQuat att_err;
826
827 struct FloatVect3 att_fb;
828#if TILT_TWIST_CTRL
829 struct FloatQuat tilt;
830 struct FloatQuat twist;
832 att_fb.x = tilt.qx;
833 att_fb.y = tilt.qy;
834 att_fb.z = twist.qz;
835#else
836 att_fb.x = att_err.qx;
837 att_fb.y = att_err.qy;
838 att_fb.z = att_err.qz;
839#endif
840
841 struct FloatRates rates_ref;
845 // add feed-forward term
847 return rates_ref;
848}
849
856{
857 struct FloatRates accel_ref;
858 accel_ref.p = (sp.p - rates.p) * indi_gains.rate.p;
859 accel_ref.q = (sp.q - rates.q) * indi_gains.rate.q;
860 accel_ref.r = (sp.r - rates.r) * indi_gains.rate.r;
861 return accel_ref;
862}
863
864
868#if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
870{
871 // Calculate the min and max increments
872 for (uint8_t i = 0; i < INDI_NUM_ACT; i++) {
875 wls_stab_p.u_pref[i] = act_pref[i];
876
877#ifdef GUIDANCE_INDI_MIN_THROTTLE
878 float airspeed = stateGetAirspeed_f();
879 //limit minimum thrust ap can give
880 if (!act_is_servo[i]) {
884 } else {
886 }
887 }
888 }
889#endif
890 }
891}
892#endif
893
901{
902#if STABILIZATION_INDI_RPM_FEEDBACK
904#else
905 //actuator dynamics
906 int8_t i;
908 for (i = 0; i < INDI_NUM_ACT; i++) {
910
912 + act_dyn_discrete[i] * (indi_u[i] - actuator_state[i]);
913
914#ifdef STABILIZATION_INDI_ACT_RATE_LIMIT
917 } else if ((actuator_state[i] - prev_actuator_state) < -act_rate_limit[i]) {
919 }
920#endif
921 }
922
923#endif
924}
925
926#ifdef STABILIZATION_INDI_COMMANDS
932void set_rotorcraft_commands(pprz_t *cmd_out, int32_t *cmd_in, bool in_flight __attribute__((unused)), bool motors_on)
933{
934 for (int i = 0; i < INDI_NUM_ACT; i++) {
935 bool is_motor = act_thrust_mat[0][i] || act_thrust_mat[1][i] || act_thrust_mat[2][i];
936 if (is_motor && !motors_on) {
938 } else {
940 }
941 }
942 // for GCS display
943 if (!motors_on) {
945 }
947}
948#endif
949
960void calc_g1_element(float ddx_error, int8_t i, int8_t j, float mu)
961{
962 g1_est[i][j] = g1_est[i][j] - du_estimation[j] * mu * ddx_error;
963}
964
974void calc_g2_element(float ddx_error, int8_t j, float mu)
975{
976 g2_est[j] = g2_est[j] - ddu_estimation[j] * mu * ddx_error;
977}
978
985{
986
987 // Get the acceleration in body axes
988 struct Int32Vect3 *body_accel_i;
989 body_accel_i = stateGetAccelBody_i();
990 ACCELS_FLOAT_OF_BFP(body_accel_f, *body_accel_i);
991
992 // Filter the acceleration in z axis
994
995 // Calculate the derivative of the acceleration via finite difference
998
999 // scale the inputs to avoid numerical errors
1002
1004
1005 //Estimation of G
1006 // TODO: only estimate when du_norm2 is large enough (enough input)
1007 /*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];*/
1008 int8_t i;
1009 for (i = 0; i < INDI_OUTPUTS; i++) {
1010 // Calculate the error between prediction and measurement
1011 float ddx_error = - ddx_estimation[i];
1012 int8_t j;
1013 for (j = 0; j < INDI_NUM_ACT; j++) {
1014 ddx_error += g1_est[i][j] * du_estimation[j];
1015 if (i == 2) {
1016 // Changing the momentum of the rotors gives a counter torque
1018 }
1019 }
1020
1021 // when doing the yaw axis, also use G2
1022 if (i == 2) {
1023 for (j = 0; j < INDI_NUM_ACT; j++) {
1025 }
1026 } else if (i == 3) {
1027 // If the acceleration change is very large (rough landing), don't adapt
1028 if (fabs(indi_accel_d) > 60.0) {
1029 ddx_error = 0.0;
1030 }
1031 }
1032
1033 // Calculate the row of the G1 matrix corresponding to this axis
1034 for (j = 0; j < INDI_NUM_ACT; j++) {
1035 calc_g1_element(ddx_error, i, j, mu1[i]);
1036 }
1037 }
1038
1039 bound_g_mat();
1040
1041 // Save the calculated matrix to G1 and G2
1042 // until thrust is included, first part of the array
1045
1046 // Calculate sum of G1 and G2 for Bwls
1047 sum_g1_g2();
1048
1049#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
1050 // Calculate the inverse of (G1+G2)
1052#endif
1053}
1054
1059void sum_g1_g2(void)
1060{
1061 int8_t i;
1062 int8_t j;
1063 for (i = 0; i < INDI_OUTPUTS; i++) {
1064 for (j = 0; j < INDI_NUM_ACT; j++) {
1065 if (i != 2) {
1066 g1g2[i][j] = g1[i][j] / INDI_G_SCALING;
1067 } else {
1068 g1g2[i][j] = (g1[i][j] + g2[j]) / INDI_G_SCALING;
1069 }
1070 }
1071 }
1072}
1073
1074#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
1079void calc_g1g2_pseudo_inv(void)
1080{
1081 //G1G2*transpose(G1G2)
1082 //calculate matrix multiplication of its transpose INDI_OUTPUTSxnum_act x num_actxINDI_OUTPUTS
1083 float element = 0;
1084 int8_t row;
1085 int8_t col;
1086 int8_t i;
1087 for (row = 0; row < INDI_OUTPUTS; row++) {
1088 for (col = 0; col < INDI_OUTPUTS; col++) {
1089 element = 0;
1090 for (i = 0; i < INDI_NUM_ACT; i++) {
1091 element = element + g1g2[row][i] * g1g2[col][i];
1092 }
1093 g1g2_trans_mult[row][col] = element;
1094 }
1095 }
1096
1097 //there are numerical errors if the scaling is not right.
1099
1100 //inverse of 4x4 matrix
1102
1103 //scale back
1105
1106 //G1G2'*G1G2inv
1107 //calculate matrix multiplication INDI_NUM_ACTxINDI_OUTPUTS x INDI_OUTPUTSxINDI_OUTPUTS
1108 for (row = 0; row < INDI_NUM_ACT; row++) {
1109 for (col = 0; col < INDI_OUTPUTS; col++) {
1110 element = 0;
1111 for (i = 0; i < INDI_OUTPUTS; i++) {
1112 element = element + g1g2[i][row] * g1g2inv[col][i];
1113 }
1114 g1g2_pseudo_inv[row][col] = element;
1115 }
1116 }
1117}
1118#endif
1119
1120#if STABILIZATION_INDI_RPM_FEEDBACK
1122{
1123 int8_t i;
1124 for (i = 0; i < num_act; i++) {
1125 // Sanity check that index is valid
1126 if (feedback[i].idx < INDI_NUM_ACT && feedback[i].set.rpm) {
1127 int8_t idx = feedback[i].idx;
1128 act_obs[idx] = (feedback[i].rpm - get_servo_min(idx));
1130 Bound(act_obs[idx], 0, MAX_PPRZ);
1131 }
1132 }
1133}
1134#endif
1135
1136static void bound_g_mat(void)
1137{
1138 int8_t i;
1139 int8_t j;
1140 for (j = 0; j < INDI_NUM_ACT; j++) {
1141 float max_limit;
1142 float min_limit;
1143
1144 // Limit the values of the estimated G1 matrix
1145 for (i = 0; i < INDI_OUTPUTS; i++) {
1146 if (g1_init[i][j] > 0.0) {
1149 } else {
1152 }
1153
1154 if (g1_est[i][j] > max_limit) {
1155 g1_est[i][j] = max_limit;
1156 }
1157 if (g1_est[i][j] < min_limit) {
1158 g1_est[i][j] = min_limit;
1159 }
1160 }
1161
1162 // Do the same for the G2 matrix
1163 if (g2_init[j] > 0.0) {
1166 } else {
1169 }
1170
1171 if (g2_est[j] > max_limit) {
1172 g2_est[j] = max_limit;
1173 }
1174 if (g2_est[j] < min_limit) {
1175 g2_est[j] = min_limit;
1176 }
1177 }
1178}
1179
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