Paparazzi UAS v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
Loading...
Searching...
No Matches
stabilization_andi.c
Go to the documentation of this file.
1/*
2 *
3 * Copyright (C) 2025 Justin Dubois <j.p.g.dubois@student.tudelft.nl>
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 */
22
45#include "state.h"
46#include "generated/airframe.h"
49#include "modules/core/abi.h"
50#include "math/wls/wls_alloc.h"
55#include "autopilot.h"
64
65#include <stdio.h>
66#if INS_EXT_POSE
68#endif
69
70#ifdef STABILIZATION_ANDI_SCHEDULE_EFF
72#else
73 const bool SCHEDULE_EFF = false;
74#endif
75
76#ifdef STABILIZATION_ANDI_USE_STATE_DYNAMICS
78#else
79 const bool USE_STATE_DYNAMICS = false;
80#endif
81
82#ifdef STABILIZATION_ANDI_RELAX_OBM
84#else
85 const float ANDI_RELAX_OBM = 1.0f;
86#endif
87
88#ifdef STABILIZATION_ANDI_ACT_IS_SERVO
90#else
92#endif
93
94#ifdef STABILIZATION_ANDI_ACT_DYNAMICS
96#else
97 #error "You must specify the actuator dynamics"
98#endif
99
100#ifdef STABILIZATION_ANDI_ACT_DELAY
102#else
104#endif
105
106#if defined(STABILIZATION_ANDI_ACT_MAX) && defined(STABILIZATION_ANDI_ACT_MIN)
109#else
110 #error "You must specify the actuator limits: STABILIZATION_ANDI_ACT_MAX and STABILIZATION_ANDI_ACT_MIN"
111#endif
112
113#if defined(STABILIZATION_ANDI_ACT_RATE_MAX) && defined(STABILIZATION_ANDI_ACT_RATE_MIN)
116#else
117 #error "You must specify the actuator limits: STABILIZATION_ANDI_ACT_RATE_MAX and STABILIZATION_ANDI_ACT_RATE_MIN"
118#endif
119
120#if defined STABILIZATION_ANDI_ACT_PREF
122#else
123const float ACTUATOR_PREF[ANDI_NUM_ACT] = {0.0f};
124#endif
125
126#if defined STABILIZATION_ANDI_RC_RATE_MAX
128#else
129const float RC_RATE_MAX[ANDI_OUTPUTS] = {[0 ... ANDI_OUTPUTS - 1] = 5.0f};
130#endif
131
132#ifdef STABILIZATION_ANDI_THRUST_MIN
134#else
135 const float THRUST_MIN = 0.0f;
136#endif
137
138#ifdef STABILIZATION_ANDI_THRUST_MAX
140#else
141 #error "You must specify maximum specific thrust: STABILIZATION_ANDI_THRUST_MAX"
142#endif
143
144#ifdef PERIODIC_FREQUENCY
145 const float SAMPLE_TIME = 1.0f / PERIODIC_FREQUENCY;
146#else
147 #error "Periodic frequency is not defined."
148#endif
149
150#if ANDI_NUM_ACT > WLS_N_U_MAX
151 #error Matrix-WLS_N_U_MAX too small or not defined: define WLS_N_U_MAX >= ANDI_NUM_ACT in airframe file
152#endif
153#if ANDI_OUTPUTS > WLS_N_V_MAX
154 #error Matrix-WLS_N_V_MAX too small or not defined: define WLS_N_V_MAX >= ANDI_OUTPUTS in airframe file
155#endif
156
157#ifdef STABILIZATION_ANDI_WLS_WV
159#else
160const float WLS_WV[ANDI_OUTPUTS] = {[0 ... ANDI_OUTPUTS - 1] = 1.0f};
161#endif
162
169#ifdef STABILIZATION_ANDI_WLS_WU
171#else
172float WLS_WU[ANDI_NUM_ACT] = {[0 ... ANDI_NUM_ACT - 1] = 1.0f};
173#endif
174
175#ifdef STABILIZATION_ANDI_CUTOFF_FREQ_OMEGA
176const struct FloatVect3 CUTOFF_FREQ_OMEGA = {
180}; // rad/s
181#else
182#error "You must specify the cutoff frequency for omega: STABILIZATION_ANDI_CUTOFF_FREQ_OMEGA"
183#endif
184
185#ifdef STABILIZATION_ANDI_CUTOFF_FREQ_OMEGA_DOT
186const struct FloatVect3 CUTOFF_FREQ_OMEGA_DOT = {
190}; // rad/s
193#else
194#error "You must specify the cutoff frequency for omega_dot: STABILIZATION_ANDI_CUTOFF_FREQ_OMEGA_DOT"
195#endif
196
197#ifdef STABILIZATION_ANDI_CUTOFF_FREQ_ACCEL
198const struct FloatVect3 CUTOFF_FREQ_ACCEL = {
202};
203#else
204#error "You must specify the cutoff frequency for accel: STABILIZATION_ANDI_CUTOFF_FREQ_ACCEL"
205#endif
206
207#ifdef STABILIZATION_ANDI_CUTOFF_FREQ_VEL
208const struct FloatVect3 CUTOFF_FREQ_VEL = {
212}; // rad/s
213#else
214#error "You must specify the cutoff frequency for vel: STABILIZATION_ANDI_CUTOFF_FREQ_VEL"
215#endif
216
217
218// Function prototypes
226static void generate_reference_rate(float dt, const struct FloatRates *rate_des,
227 const struct GainsOrder2Vect3 *k_rate_rm, const struct AttQuat *bounds,
228 struct AttQuat *att_ref) __attribute__((unused));
229static void generate_reference_attitude(float dt, const struct FloatQuat *att_des,
230 const struct GainsOrder3Vect3 *k_att_rm, const struct AttQuat *bounds, struct AttQuat *att_ref);
231static void generate_reference_thrust(float dt, float thrust_des, const float k_thrust_rm,
232 const struct ThrustRef *bounds_min, const struct ThrustRef *bounds_max, struct ThrustRef *thrust_ref);
233static struct FloatVect3 control_error_rate(const struct AttQuat *att_ref, const struct AttStateQuat *att_state,
234 const struct GainsOrder2Vect3 *k_rate_ec) __attribute__((unused));
235static struct FloatVect3 control_error_attitude(const struct AttQuat *att_ref, const struct AttStateQuat *att_state,
236 const struct GainsOrder3Vect3 *k_att_ec);
237static float control_error_thrust(const struct ThrustRef *thrust_ref, const float thrust_state,
238 const float k_thrust_ec);
239static void compute_wls_upper_bounds(float u_d_max[ANDI_NUM_ACT], const float act_state[ANDI_NUM_ACT],
240 const float act_max[ANDI_NUM_ACT], const float act_rate_max[ANDI_NUM_ACT],
241 const float actuator_bandwidth[ANDI_NUM_ACT]);
242static void compute_wls_lower_bounds(float u_d_min[ANDI_NUM_ACT], const float act_state[ANDI_NUM_ACT],
243 const float act_min[ANDI_NUM_ACT], const float act_rate_min[ANDI_NUM_ACT],
244 const float actuator_bandwidth[ANDI_NUM_ACT]);
245static void compute_wls_u_scaler(float u_scaler[ANDI_NUM_ACT], const float act_min[ANDI_NUM_ACT],
246 const float act_max[ANDI_NUM_ACT]);
247static void compute_wls_v_scaler(float v_scaler[ANDI_NUM_ACT], const float v[ANDI_NUM_ACT]) __attribute__((unused));
248
249static inline float ec_k1_order3_f(const float omega_n, const float zeta, const float omega_a) { return (omega_n * omega_n * (omega_a - 2 * zeta * omega_n)); }
250static inline float ec_k2_order3_f(const float omega_n, const float zeta, const float omega_a) { return (omega_n * omega_n + 2.0f * zeta * omega_n * (omega_a - 2 * zeta * omega_n)); }
251static inline float ec_k3_order3_f(const float omega_n __attribute__((unused)),
252 const float zeta __attribute__((unused)), const float omega_a) { return omega_a; }
253static inline float rm_k1_order3_f(const float omega_n, const float zeta, const float omega_a) { return (omega_n * omega_n * omega_a) / (omega_n * omega_n + 2 * zeta * omega_n * omega_a); }
254static inline float rm_k2_order3_f(const float omega_n, const float zeta, const float omega_a) { return (omega_n * omega_n + 2 * zeta * omega_n * omega_a) / (2 * zeta * omega_n + omega_a); }
255static inline float rm_k3_order3_f(const float omega_n, const float zeta, const float omega_a) { return 2 * zeta * omega_n + omega_a; }
256
257static inline float ec_k1_order2_f(const float omega_a, const float zeta) { return omega_a * omega_a / (4 * zeta * zeta); }
258static inline float ec_k2_order2_f(const float omega_a, const float zeta __attribute__((unused))) { return omega_a; }
259static inline float rm_k1_order2_f(const float omega_a, const float zeta) { return ec_k2_order2_f(omega_a, zeta) / ec_k2_order2_f(omega_a, zeta); }
260static inline float rm_k2_order2_f(const float omega_a, const float zeta) { return ec_k2_order2_f(omega_a, zeta); }
261
322
323
324// WLS allocation variables
326 .nu = ANDI_NUM_ACT,
327 .nv = ANDI_OUTPUTS,
328 .gamma_sq = 100000.0,
329 .u_pref = {0.0f},
330 .u_min = {0.0f},
331 .u_max = {0.0f},
332 .PC = 0.0f,
333 .SC = 0.0f,
334 .iter = 0
335};
336
337// Controller gains
344
345// Complementary filter instances for state dependent contribution
349
353
354// Actuator and delay
355struct FirstOrderZOHLowPass actuator_obm_zohlpf[ANDI_NUM_ACT]; // ZOH low pass filter for actuator model
356struct TransportDelay actuator_obm_delay[ANDI_NUM_ACT]; // transport delay for actuator model
357float actuator_state[ANDI_NUM_ACT]; // from feedback or model
358float actuator_state_lpf[ANDI_NUM_ACT]; // delayed actuator state
359
360// T4 Actuator feedback handling
363float actuator_meas[ANDI_NUM_ACT]; // measured actuator feedback
364
365// Raw state measurement variables
367
368// State variables
369struct AttStateQuat attitude_state_cf; // undelayed attitude state for feedforward
370struct LinState linear_state_cf; // undelayed linear state for feedforward
371float thrust_state; // delayed thrust state for feedback
372
373// Reference model variables
376
377// Setpoints
381
382// Bounds
386
387// Controller variables
393
394// Pseudo command variables
395float nu_obj[ANDI_OUTPUTS]; // Total pseudo command allocated to the actuators
396float nu_ec[ANDI_OUTPUTS]; // Pseudo command from the error controller
397float nu_obm[ANDI_OUTPUTS]; // Pseudo command from the on board model state dependent term
398// float nu_reconstructed[ANDI_OUTPUTS]; // Reconstructed angular acceleration from the actuator commands (for model verification)
399
400#if PERIODIC_TELEMETRY
403{
404 char *name = "andi";
406 strlen(name), name,
407 &wls_stab_p.gamma_sq, // Does this need scaling as a function of scaling factor?
410 ANDI_OUTPUTS, (float *)WLS_WV);
411}
412
414{
415 char *name = "andi";
416 float zero_array[ANDI_NUM_ACT] = {0.0f};
418 strlen(name), name,
419 ANDI_NUM_ACT, (float *)WLS_WU,
424}
425
427{
428 float zero = 0.0f;
434 1, &zero);
435}
436
438{
440 4, (float *)&attitude_des,
441 4, (float *)&attitude_state_cf.att,
442 4, (float *)&attitude_ref.att,
443 3, (float *)&attitude_state_cf.att_d,
444 3, (float *)&attitude_ref.att_d,
445 3, (float *)&attitude_state_cf.att_2d,
446 3, (float *)&attitude_ref.att_2d,
447 3, (float *)&attitude_ref.att_3d,
449}
450// For debug only
451// static void send_stab_thrust_stabilization_andi(struct transport_tx *trans, struct link_device *dev)
452// {
453// pprz_msg_send_STAB_THRUST(trans, dev, AC_ID,
454// &thrust_des,
455// &thrust_ref.thrust,
456// &thrust_state,
457// &thrust_ref.thrust_d);
458// }
459
460// static void send_on_board_model_stabilization_andi(struct transport_tx *trans, struct link_device *dev)
461// {
462// pprz_msg_send_ON_BOARD_MODEL(trans, dev, AC_ID,
463// 3, (float *)&linear_state_cf.vel,
464// 3, (float *)&linear_state_cf.acc,
465// ANDI_NUM_ACT, (float *)&actuator_meas,
466// ANDI_OUTPUTS, (float *)&nu_obm);
467// }
468
469// static void send_stab_pseudo_command_stabilization_andi(struct transport_tx *trans, struct link_device *dev)
470// {
471// /**
472// * nu_obj: Total pseudo command sent to the actuators
473// * nu_ec: Pseudo command from the error controller
474// * nu_obm: Pseudo command from the on board model state dependent term
475// * nu_reconstructed: Reconstructed angular acceleration from the actuator commands.
476// * This is used to verify the on board model. If the OBM is perfect, then nu_reconstructed should be
477// * equal to the measured state plus any external disturbances.
478// *
479// * nu_obj = nu_ec + nu_obm
480// * nu_reconstructed = Ce * u_meas - nu_obm NOTE: This is wrong equation, fix it.
481// *
482// * FIXME: nu_reconstructed has been repurposed and no longer is the reconstructed value. Update the telemetry message accordingly.
483// */
484// pprz_msg_send_STAB_PSEUDO_COMMAND(trans, dev, AC_ID,
485// ANDI_OUTPUTS, nu_obj, // Total pseudo command
486// ANDI_OUTPUTS, nu_ec, // From error controller
487// ANDI_OUTPUTS, nu_obm, // From on board model state dependent term
488// ANDI_OUTPUTS, nu_reconstructed); // Reconstructed from actuator commands
489// }
490
491#endif // PERIODIC_TELEMETRY
492
495
509{
510 // Copy the entire ActuatorsT4In struct from the pointer to actuator_obs
512}
513
533{
534 actuator_meas[0] = RadOfCentiDeg((float)actuators_t4_in_ptr->servo_1_angle);
535 actuator_meas[1] = -RadOfCentiDeg((float)actuators_t4_in_ptr->servo_6_angle);
536 actuator_meas[2] = (float)actuators_t4_in_ptr->esc_1_rpm * 2 * M_PI / 60; // Convert rpm to rad/s
537 actuator_meas[2] *= actuator_meas[2]; // square motor rpm
538 actuator_meas[3] = (float)actuators_t4_in_ptr->esc_2_rpm * 2 * M_PI / 60;
539 actuator_meas[3] *= actuator_meas[3]; // square motor rpm
540}
541
549{
550 struct GainsOrder3Vect3 gains;
551 gains.k1.x = rm_k1_order3_f(poles->omega_n.x, poles->zeta.x, poles->omega_a.x);
552 gains.k1.y = rm_k1_order3_f(poles->omega_n.y, poles->zeta.y, poles->omega_a.y);
553 gains.k1.z = rm_k1_order3_f(poles->omega_n.z, poles->zeta.z, poles->omega_a.z);
554
555 gains.k2.x = rm_k2_order3_f(poles->omega_n.x, poles->zeta.x, poles->omega_a.x);
556 gains.k2.y = rm_k2_order3_f(poles->omega_n.y, poles->zeta.y, poles->omega_a.y);
557 gains.k2.z = rm_k2_order3_f(poles->omega_n.z, poles->zeta.z, poles->omega_a.z);
558
559 gains.k3.x = rm_k3_order3_f(poles->omega_n.x, poles->zeta.x, poles->omega_a.x);
560 gains.k3.y = rm_k3_order3_f(poles->omega_n.y, poles->zeta.y, poles->omega_a.y);
561 gains.k3.z = rm_k3_order3_f(poles->omega_n.z, poles->zeta.z, poles->omega_a.z);
562 return gains;
563}
564
572{
573 struct GainsOrder2Vect3 gains;
574 gains.k1.x = rm_k1_order2_f(poles->omega_a.x, poles->zeta.x);
575 gains.k1.y = rm_k1_order2_f(poles->omega_a.y, poles->zeta.y);
576 gains.k1.z = rm_k1_order2_f(poles->omega_a.z, poles->zeta.z);
577
578 gains.k2.x = rm_k2_order2_f(poles->omega_a.x, poles->zeta.x);
579 gains.k2.y = rm_k2_order2_f(poles->omega_a.y, poles->zeta.y);
580 gains.k2.z = rm_k2_order2_f(poles->omega_a.z, poles->zeta.z);
581 return gains;
582}
583
591{
592 struct GainsOrder3Vect3 gains;
593 gains.k1.x = ec_k1_order3_f(poles->omega_n.x, poles->zeta.x, poles->omega_a.x);
594 gains.k1.y = ec_k1_order3_f(poles->omega_n.y, poles->zeta.y, poles->omega_a.y);
595 gains.k1.z = ec_k1_order3_f(poles->omega_n.z, poles->zeta.z, poles->omega_a.z);
596
597 gains.k2.x = ec_k2_order3_f(poles->omega_n.x, poles->zeta.x, poles->omega_a.x);
598 gains.k2.y = ec_k2_order3_f(poles->omega_n.y, poles->zeta.y, poles->omega_a.y);
599 gains.k2.z = ec_k2_order3_f(poles->omega_n.z, poles->zeta.z, poles->omega_a.z);
600
601 gains.k3.x = ec_k3_order3_f(poles->omega_n.x, poles->zeta.x, poles->omega_a.x);
602 gains.k3.y = ec_k3_order3_f(poles->omega_n.y, poles->zeta.y, poles->omega_a.y);
603 gains.k3.z = ec_k3_order3_f(poles->omega_n.z, poles->zeta.z, poles->omega_a.z);
604 return gains;
605}
606
614{
615 struct GainsOrder2Vect3 gains;
616 gains.k1.x = ec_k1_order2_f(poles->omega_a.x, poles->zeta.x);
617 gains.k1.y = ec_k1_order2_f(poles->omega_a.y, poles->zeta.y);
618 gains.k1.z = ec_k1_order2_f(poles->omega_a.z, poles->zeta.z);
619
620 gains.k2.x = ec_k2_order2_f(poles->omega_a.x, poles->zeta.x);
621 gains.k2.y = ec_k2_order2_f(poles->omega_a.y, poles->zeta.y);
622 gains.k2.z = ec_k2_order2_f(poles->omega_a.z, poles->zeta.z);
623 return gains;
624}
625
641 float dt,
642 const struct FloatRates *rate_des,
643 const struct GainsOrder2Vect3 *k_rate_rm,
644 const struct AttQuat *bounds,
645 struct AttQuat *att_ref)
646{
647 float p_des = rate_des->p;
648 float q_des = rate_des->q;
649 float r_des = rate_des->r;
650
651 BoundAbs(p_des, bounds->att_d.p);
652 BoundAbs(q_des, bounds->att_d.q);
653 BoundAbs(r_des, bounds->att_d.r);
654
655 float p_d_des = k_rate_rm->k1.x * (p_des - att_ref->att_d.p);
656 float q_d_des = k_rate_rm->k1.y * (q_des - att_ref->att_d.q);
657 float r_d_des = k_rate_rm->k1.z * (r_des - att_ref->att_d.r);
658
659 BoundAbs(p_d_des, bounds->att_2d.x);
660 BoundAbs(q_d_des, bounds->att_2d.y);
661 BoundAbs(r_d_des, bounds->att_2d.z);
662
663 float p_2d_des = k_rate_rm->k2.x * (p_d_des - att_ref->att_2d.x);
664 float q_2d_des = k_rate_rm->k2.y * (q_d_des - att_ref->att_2d.y);
665 float r_2d_des = k_rate_rm->k2.z * (r_d_des - att_ref->att_2d.z);
666
667 BoundAbs(p_2d_des, bounds->att_3d.x);
668 BoundAbs(q_2d_des, bounds->att_3d.y);
669 BoundAbs(r_2d_des, bounds->att_3d.z);
670
671 att_ref->att_3d.x = p_2d_des;
672 att_ref->att_3d.y = q_2d_des;
673 att_ref->att_3d.z = r_2d_des;
674
675 att_ref->att_2d.x += p_2d_des * dt;
676 att_ref->att_2d.y += q_2d_des * dt;
677 att_ref->att_2d.z += r_2d_des * dt;
678
679 att_ref->att_d.p += att_ref->att_2d.x * dt;
680 att_ref->att_d.q += att_ref->att_2d.y * dt;
681 att_ref->att_d.r += att_ref->att_2d.z * dt;
682
684}
685
705 float dt,
706 const struct FloatQuat *att_des,
707 const struct GainsOrder3Vect3 *k_att_rm,
708 const struct AttQuat *bounds,
709 struct AttQuat *att_ref)
710{
711 struct FloatQuat att_err; // rotation from ref to des
713 float p_des = k_att_rm->k1.x * att_err.qx * 2;
714 float q_des = k_att_rm->k1.y * att_err.qy * 2;
715 float r_des = k_att_rm->k1.z * att_err.qz * 2;
716
717 BoundAbs(p_des, bounds->att_d.p);
718 BoundAbs(q_des, bounds->att_d.q);
719 BoundAbs(r_des, bounds->att_d.r);
720
721 float p_d_des = k_att_rm->k2.x * (p_des - att_ref->att_d.p);
722 float q_d_des = k_att_rm->k2.y * (q_des - att_ref->att_d.q);
723 float r_d_des = k_att_rm->k2.z * (r_des - att_ref->att_d.r);
724
725 BoundAbs(p_d_des, bounds->att_2d.x);
726 BoundAbs(q_d_des, bounds->att_2d.y);
727 BoundAbs(r_d_des, bounds->att_2d.z);
728
729 float p_2d_des = k_att_rm->k3.x * (p_d_des - att_ref->att_2d.x);
730 float q_2d_des = k_att_rm->k3.y * (q_d_des - att_ref->att_2d.y);
731 float r_2d_des = k_att_rm->k3.z * (r_d_des - att_ref->att_2d.z);
732
733 BoundAbs(p_2d_des, bounds->att_3d.x);
734 BoundAbs(q_2d_des, bounds->att_3d.y);
735 BoundAbs(r_2d_des, bounds->att_3d.z);
736
737 att_ref->att_3d.x = p_2d_des;
738 att_ref->att_3d.y = q_2d_des;
739 att_ref->att_3d.z = r_2d_des;
740
741 att_ref->att_2d.x += p_2d_des * dt;
742 att_ref->att_2d.y += q_2d_des * dt;
743 att_ref->att_2d.z += r_2d_des * dt;
744
745 att_ref->att_d.p += att_ref->att_2d.x * dt;
746 att_ref->att_d.q += att_ref->att_2d.y * dt;
747 att_ref->att_d.r += att_ref->att_2d.z * dt;
748
749 float_quat_integrate(&att_ref->att, &att_ref->att_d, dt);
751}
752
753
768 float dt,
769 float thrust_des,
770 const float k_thrust_rm,
771 const struct ThrustRef *bounds_min,
772 const struct ThrustRef *bounds_max,
773 struct ThrustRef *thrust_ref)
774{
775 Bound(thrust_des, bounds_min->thrust, bounds_max->thrust);
777
778 Bound(thrust_ref->thrust_d, bounds_min->thrust_d, bounds_max->thrust_d);
780}
781
796 const struct AttQuat *att_ref,
797 const struct AttStateQuat *att_state,
798 const struct GainsOrder2Vect3 *k_rate_ec)
799{
800 struct FloatVect3 nu = att_ref->att_3d;
801
802 nu.x += k_rate_ec->k2.x * (att_ref->att_2d.x - att_state->att_2d.x);
803 nu.y += k_rate_ec->k2.y * (att_ref->att_2d.y - att_state->att_2d.y);
804 nu.z += k_rate_ec->k2.z * (att_ref->att_2d.z - att_state->att_2d.z);
805
806 nu.x += k_rate_ec->k1.x * (att_ref->att_d.p - att_state->att_d.p);
807 nu.y += k_rate_ec->k1.y * (att_ref->att_d.q - att_state->att_d.q);
808 nu.z += k_rate_ec->k1.z * (att_ref->att_d.r - att_state->att_d.r);
809
810 return nu;
811}
812
827 const struct AttQuat *att_ref,
828 const struct AttStateQuat *att_state,
829 const struct GainsOrder3Vect3 *k_att_ec)
830{
831 struct FloatVect3 nu = att_ref->att_3d;
832
833 nu.x += k_att_ec->k3.x * (att_ref->att_2d.x - att_state->att_2d.x);
834 nu.y += k_att_ec->k3.y * (att_ref->att_2d.y - att_state->att_2d.y);
835 nu.z += k_att_ec->k3.z * (att_ref->att_2d.z - att_state->att_2d.z);
836
837 nu.x += k_att_ec->k2.x * (att_ref->att_d.p - att_state->att_d.p);
838 nu.y += k_att_ec->k2.y * (att_ref->att_d.q - att_state->att_d.q);
839 nu.z += k_att_ec->k2.z * (att_ref->att_d.r - att_state->att_d.r);
840
841 struct FloatQuat att_err; // rotation from state to reference
843 // Multiplication by 2 needed to convert quaternion difference to angular rate.
844 nu.x += k_att_ec->k1.x * att_err.qx * 2;
845 nu.y += k_att_ec->k1.y * att_err.qy * 2;
846 nu.z += k_att_ec->k1.z * att_err.qz * 2;
847
848 return nu;
849}
850
867 const struct ThrustRef *thrust_ref,
868 const float thrust_state,
869 const float k_thrust_ec)
870{
871 float nu = thrust_ref->thrust_d;
873 return nu;
874}
875
890static void compute_wls_upper_bounds(float u_d_max[ANDI_NUM_ACT], const float act_state[ANDI_NUM_ACT],
891 const float act_max[ANDI_NUM_ACT], const float act_rate_max[ANDI_NUM_ACT], const float actuator_bandwidth[ANDI_NUM_ACT])
892{
893 for (uint8_t i = 0; i < ANDI_NUM_ACT; i++) {
894 // Calculate max rate allowed to avoid exceeding actuator max position in one timestep
895 float rate_limit_pos = (act_max[i] - act_state[i]) * actuator_bandwidth[i];
897 Bound(u_d_max[i], 0.0f, INFINITY);
898 }
899}
900
916static void compute_wls_lower_bounds(float u_d_min[ANDI_NUM_ACT], const float act_state[ANDI_NUM_ACT],
917 const float act_min[ANDI_NUM_ACT], const float act_rate_min[ANDI_NUM_ACT], const float actuator_bandwidth[ANDI_NUM_ACT])
918{
919 for (uint8_t i = 0; i < ANDI_NUM_ACT; i++) {
920 // Calculate min rate allowed to avoid going below actuator min position in one timestep
921 float rate_limit_pos = (act_min[i] - act_state[i]) * actuator_bandwidth[i];
923 Bound(u_d_min[i], -INFINITY, 0.0f);
924 }
925}
926
942 const float act_max[ANDI_NUM_ACT])
943{
944 for (uint8_t i = 0; i < ANDI_NUM_ACT; i++) {
945 float range = fabs(act_max[i] - act_min[i]);
946 if (range <= FLT_EPSILON) {
947 u_scaler[i] = 1.0f;
948 } else {
949 u_scaler[i] = 1.0f / range;
950 }
951 }
952}
953
965static void compute_wls_v_scaler(float v_scaler[ANDI_NUM_ACT], const float v[ANDI_NUM_ACT])
966{
967 for (uint8_t i = 0; i < ANDI_NUM_ACT; i++) {
968 if (fabs(v[i]) <= FLT_EPSILON) {
969 v_scaler[i] = 1.0f;
970 } else {
971 v_scaler[i] = 1.0f / fabs(v[i]);
972 }
973 }
974}
975
977{
978 // Compute gains
985
986 // Initialize state variables
987 rates_prev.p = 0.0f;
988 rates_prev.q = 0.0f;
989 rates_prev.r = 0.0f;
990
998
999 linear_state_cf.vel.x = 0.0f;
1000 linear_state_cf.vel.y = 0.0f;
1001 linear_state_cf.vel.z = 0.0f;
1002 linear_state_cf.acc.x = 0.0f;
1003 linear_state_cf.acc.y = 0.0f;
1004 linear_state_cf.acc.z = 0.0f;
1005
1006 thrust_state = 0.0f;
1013 // float_vect_zero(nu_reconstructed, ANDI_NUM_ACT);
1014
1015 // Initialize reference variables
1017 attitude_ref.att_d.p = 0.0f;
1018 attitude_ref.att_d.q = 0.0f;
1019 attitude_ref.att_d.r = 0.0f;
1020 attitude_ref.att_2d.x = 0.0f;
1021 attitude_ref.att_2d.y = 0.0f;
1022 attitude_ref.att_2d.z = 0.0f;
1023 attitude_ref.att_3d.x = 0.0f;
1024 attitude_ref.att_3d.y = 0.0f;
1025 attitude_ref.att_3d.z = 0.0f;
1026
1027 thrust_ref.thrust = 0.0f;
1028 thrust_ref.thrust_d = 0.0f;
1029
1030 // FIXME: These bounds should be set via parameters
1031 // Initialize attitude bounds (symmetric bounds on abs values)
1033 attitude_bounds.att_d.p = 100.0f;
1034 attitude_bounds.att_d.q = 100.0f;
1035 attitude_bounds.att_d.r = 25.0f;
1036 attitude_bounds.att_2d.x = 100.0f;
1037 attitude_bounds.att_2d.y = 100.0f;
1038 attitude_bounds.att_2d.z = 20.0f;
1039 attitude_bounds.att_3d.x = 100.0f;
1040 attitude_bounds.att_3d.y = 100.0f;
1041 attitude_bounds.att_3d.z = 100.0f;
1042
1043 // Limit thrust bounds (asymmetric bounds)
1046 thrust_bounds_min.thrust_d = -1000.0f;
1047 thrust_bounds_max.thrust_d = 1000.0f;
1048
1049 // Initial control effectiveness matrix
1051
1052 // Initialize filters
1055 angular_rates_obm.p = 0.0f;
1056 angular_rates_obm.q = 0.0f;
1057 angular_rates_obm.r = 0.0f;
1058
1061 linear_velocity_obm.x = 0.0f;
1062 linear_velocity_obm.y = 0.0f;
1063 linear_velocity_obm.z = 0.0f;
1064
1065 // Bind T4 actuator feedback abi message
1067
1068 // Precompute discrete-time actuator dynamics coefficients
1071
1072// Start telemetry
1073#if PERIODIC_TELEMETRY
1075 // register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_STAB_THRUST, send_stab_thrust_stabilization_andi); // For debug only, dont forget to add your message.
1079 // register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_STAB_PSEUDO_COMMAND, send_stab_pseudo_command_stabilization_andi);
1080 // register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_ON_BOARD_MODEL, send_on_board_model_stabilization_andi);
1081#endif
1082}
1083
1095{
1096 // Reset actuator states to current measurements
1100
1101 // Clear previous rates
1102 rates_prev.p = 0.0f;
1103 rates_prev.q = 0.0f;
1104 rates_prev.r = 0.0f;
1105
1106 // Reset state to current measurements, higher order derivatives are set to zero
1108 linear_state_cf.acc.x = 0.0f;
1109 linear_state_cf.acc.y = 0.0f;
1110 linear_state_cf.acc.z = 0.0f;
1114
1117 attitude_state_cf.att_2d.x = 0.0f;
1118 attitude_state_cf.att_2d.y = 0.0f;
1119 attitude_state_cf.att_2d.z = 0.0f;
1123
1127 attitude_ref.att_3d.x = 0.0f;
1128 attitude_ref.att_3d.y = 0.0f;
1129 attitude_ref.att_3d.z = 0.0f;
1130
1132
1134 thrust_ref.thrust_d = 0.0f;
1135
1136 // Reset controller states
1139
1140 // Initial control effectiveness matrix
1142
1143}
1144
1187{
1188 // Recompute gains
1189 // FIXME: Only recompute when parameters change, use parameter update handler callback.
1196
1197 // Fetch linear measurements
1198 struct LinState lin_meas;
1200 (struct FloatVect3 *)stateGetSpeedNed_f()); // From Kalman filter
1201 lin_meas.acc = *stateGetAccelBody_f(); // From accelerometer
1202
1203 // Fetch attitude measurements
1205 attitude_meas.att = *stateGetNedToBodyQuat_f(); // From Kalman filter
1206 attitude_meas.att_d = *stateGetBodyRates_f(); // From gyroscope
1210 rates_prev = attitude_meas.att_d; // Store previous rates for next acceleration calculation
1211
1212 // Propagate and get on board model actuator state estimates
1218
1219 // Get actuator measurements from T4 feedback
1221
1222 // FIXME: Make configurable which source to use for each actuator.
1223 // Choose actuator feedback for elevon and on board model for esc (because lack of rpm control).
1228
1229 // Evaluate On Board Model with previous filtered state estimates
1234
1235 // FIXME: Integral before filtering can cause numerical issues. Update complementary filter to handle this case.
1236 // FIXME: Numerical differentiation to get accelerations can be noisy. Consider using a filter before differentiation.
1237 // Cascaded complementary filter for linear velocity and accelerations measurements
1243
1244 // Cascaded complementary filter for angular rates and accelerations measurements
1251
1252 // Get thrust measurement from on board model
1254
1255 // Reconstructed nu is repurposed to hold modeled moments and specific thrust from the on board model (for obm validation).
1256 // This can be used to compare the on board model prediction to the actual measured acceleration to validate model accuracy.
1257 // Do not compare this to the complementary filter values since these are influenced by the model, use the raw measurements instead.
1258 // nu_reconstructed[0] = angular_accel_obm.x;
1259 // nu_reconstructed[1] = angular_accel_obm.y;
1260 // nu_reconstructed[2] = angular_accel_obm.z;
1261 // nu_reconstructed[3] = thrust_state;
1262
1263 // Get setpoints
1264 if (use_rate_control) {
1266 if (in_flight)
1268 } else {
1270 if (in_flight)
1272 }
1273
1274 // FIXME: Thrust setpoint cant be of type THRUST_INCR_SP, this is not enforced but will silently fail
1277 &thrust_ref);
1278
1279 // Construct pseudo control
1280 struct FloatVect3 nu_attitude;
1281 if (use_rate_control) {
1283 } else {
1285 }
1287
1288 nu_ec[0] = nu_attitude.x;
1289 nu_ec[1] = nu_attitude.y;
1290 nu_ec[2] = nu_attitude.z;
1291 nu_ec[3] = nu_thrust;
1292
1293 // State feedback from on board model
1297
1298 if (in_flight) {
1299 nu_obj[0] = nu_ec[0] - (nu_obm[0] * ANDI_RELAX_OBM);
1300 nu_obj[1] = nu_ec[1] - (nu_obm[1] * ANDI_RELAX_OBM);
1301 nu_obj[2] = nu_ec[2] - (nu_obm[2] * ANDI_RELAX_OBM);
1302 } else {
1303 nu_obj[0] = 0.0f;
1304 nu_obj[1] = 0.0f;
1305 nu_obj[2] = 0.0f;
1306 }
1307 nu_obj[3] = nu_ec[3] - (nu_obm[3] * ANDI_RELAX_OBM);
1308
1309 // Compute control effectiveness matrix based on current states
1311
1312 // Solve control allocation using weighted least squares
1316 float wls_v_scaler[ANDI_OUTPUTS] = {[0 ... ANDI_OUTPUTS - 1] = 1.0f}; // Disable v scaling
1318 du_max); // FIXME: Compute only once in advance for fixed bounds (important for well defined WLS Wu weights)
1319 // compute_wls_v_scaler(wls_v_scaler, nu_obj);
1320
1322 float *bwls[ANDI_OUTPUTS];
1323 // Scale control effectiveness matrix
1324 for (uint8_t i = 0; i < ANDI_OUTPUTS; i++) {
1325 for (uint8_t j = 0; j < ANDI_NUM_ACT; j++) {
1327 }
1328 bwls[i] = ce_mat_scaled[i];
1329 }
1330
1331 // Scale actuator bounds and weights
1332 for (uint8_t i = 0; i < ANDI_NUM_ACT; i++) {
1333 wls_stab_p.u_min[i] = du_min[i] * wls_u_scaler[i];
1334 wls_stab_p.u_max[i] = du_max[i] * wls_u_scaler[i];
1335 wls_stab_p.u_pref[i] = (wls_stab_p.u_min[i] + wls_stab_p.u_max[i]) / 2.0f; // Use mid-point as preferred command
1336 wls_stab_p.Wu[i] = WLS_WU[i];
1337 }
1338
1339 // Scale pseudo control and weights
1340 for (uint8_t i = 0; i < ANDI_OUTPUTS; i++) {
1341 wls_stab_p.v[i] = nu_obj[i] * wls_v_scaler[i];
1342 wls_stab_p.Wv[i] = WLS_WV[i];
1343 }
1344
1345 wls_alloc(&wls_stab_p, bwls, 0, 0, 10);
1346
1347 // Scale back actuator commands
1348 for (uint8_t i = 0; i < ANDI_NUM_ACT; i++) {
1349 du_cmd[i] = (wls_stab_p.u[i] / wls_u_scaler[i]);
1350 u_cmd[i] = du_cmd[i] / ACTUATOR_DYNAMICS[i] + actuator_state[i];
1352 }
1353
1354 // Commit actuator commands
1355 // Resulting commands are in rad for servo and rad/s for motor
1356 // Paparazzi expects the commands in pprz units (-MAX_PPRZ to MAX_PPRZ for servo, 0 to MAX_PPRZ for motor).
1357 // FIXME: Do not hardcode actuator layout
1358 commands[0] = (pprz_t)(u_cmd[0] / ACTUATOR_MAX[0] * MAX_PPRZ);
1359 commands[1] = (pprz_t)(u_cmd[1] / ACTUATOR_MAX[1] * MAX_PPRZ);
1360 commands[2] = (pprz_t)(sqrt(u_cmd[2] / ACTUATOR_MAX[2]) * MAX_PPRZ);
1361 commands[3] = (pprz_t)(sqrt(u_cmd[3] / ACTUATOR_MAX[3]) * MAX_PPRZ);
1362
1363 // Set Thrust command for compatibility with other modules
1364 // FIXME: Do not hardcode actuator layout
1365 cmd[COMMAND_THRUST] = 0;
1366 cmd[COMMAND_THRUST] += (pprz_t)(sqrt(u_cmd[2] / ACTUATOR_MAX[2]) * MAX_PPRZ);
1367 cmd[COMMAND_THRUST] += (pprz_t)(sqrt(u_cmd[3] / ACTUATOR_MAX[3]) * MAX_PPRZ);
1368 cmd[COMMAND_THRUST] /= 2;
1369}
1370
1371// FIXME: The following functions are to integrate the controller in the existing stabilization framework, find a better way to do this or move.
1373{
1374 ;
1375}
1376
1378{
1379 ;
1380}
1381
1382void stabilization_rate_run(bool in_flight __attribute__((unused)),
1383 struct StabilizationSetpoint *rate_sp __attribute__((unused)), struct ThrustSetpoint *thrust __attribute__((unused)),
1384 int32_t *cmd __attribute__((unused)))
1385{
1386 ;
1387}
1388
1389void stabilization_attitude_run(bool in_flight __attribute__((unused)),
1390 struct StabilizationSetpoint *sp __attribute__((unused)), struct ThrustSetpoint *thrust __attribute__((unused)),
1391 int32_t *cmd __attribute__((unused)))
1392{
1393 ;
1394}
1395
1396// FIXME: This function is duplicated in stabilization_rate.c, find a way to share it
1398{
1399 struct FloatRates rate_sp;
1402 rate_sp.p = rc->values[RC_RATE_P] * RC_RATE_MAX[0] / MAX_PPRZ;
1403 }
1405 rate_sp.q = rc->values[RC_RATE_Q] * RC_RATE_MAX[1] / MAX_PPRZ;
1406 }
1408 rate_sp.r = rc->values[RC_RATE_R] * RC_RATE_MAX[2] / MAX_PPRZ;
1409 }
1411}
1412
1413// FIXME: Autopilot end flight detection is not applicable to tailsitters.
1415{
1416 return false;
1417}
1418
1419// DEBUG FUNCTION
1420// static int counter = 0;
1421// /**
1422// * @brief Debug function for actuators.
1423// *
1424// * Send step inputs to actuators and observe responses.
1425// * useful to estimate actuator dynamics.
1426// */
1427// void actuator_debug(bool do_servo_step, bool do_motor_step, float step_rate)
1428// {
1429// if (counter++ > PERIODIC_FREQUENCY * step_rate) {
1430// counter = 0;
1431// }
1432
1433// if (counter <= (PERIODIC_FREQUENCY * step_rate) / 2) {
1434// commands[0] = (pprz_t)(do_servo_step ? MAX_PPRZ : 0);
1435// commands[1] = (pprz_t)(do_servo_step ? MAX_PPRZ : 0);
1436// commands[2] = (pprz_t)(do_motor_step ? MAX_PPRZ : 0);
1437// commands[3] = (pprz_t)(do_motor_step ? MAX_PPRZ : 0);
1438// } else {
1439// commands[0] = (pprz_t)(do_servo_step ? MIN_PPRZ : 0);
1440// commands[1] = (pprz_t)(do_servo_step ? MIN_PPRZ : 0);
1441// commands[2] = (pprz_t)(do_motor_step ? 0 : 0);
1442// commands[3] = (pprz_t)(do_motor_step ? 0 : 0);
1443// }
1444// }
Main include for ABI (AirBorneInterface).
#define ABI_BROADCAST
Broadcast address.
Definition abi_common.h:59
Event structure to store callbacks in a linked list.
Definition abi_common.h:68
Core autopilot interface common to all firmwares.
Hardware independent code for commands handling.
Implementation of complementary filters (first order, second order, and Butterworth variants)
Definitions and inline functions for 1st order complementary filter vector types.
static struct FloatVect3 update_butterworth_2_complementary_vect3(struct Butterworth2ComplementaryVect3 *filter, const struct FloatVect3 *value_x, const struct FloatVect3 *value_y)
Initialize 3D vector of 2nd order Butterworth complementary filters.
static struct FloatRates update_first_order_complementary_rates(struct FirstOrderComplementaryVect3 *filter, const struct FloatRates *value_x, const struct FloatRates *value_y)
Update 3D vector of 1st order complementary filters for rates.
static void reset_first_order_complementary_rates(struct FirstOrderComplementaryVect3 *filter, const struct FloatRates *value)
Reset 3D vector of 1st order complementary filters for rates to a specific value.
static void reset_first_order_complementary_vect3(struct FirstOrderComplementaryVect3 *filter, const struct FloatVect3 *value)
Reset 3D vector of 1st order complementary filters to a specific value.
static void init_butterworth_2_complementary_vect3(struct Butterworth2ComplementaryVect3 *filter, const struct FloatVect3 *cut_off, float sample_time)
Initialize 3D vector of 2nd order Butterworth complementary filters.
static struct FloatVect3 update_first_order_complementary_vect3(struct FirstOrderComplementaryVect3 *filter, const struct FloatVect3 *value_x, const struct FloatVect3 *value_y)
Update 3D vector of 1st order complementary filters.
static struct FloatRates get_first_order_complementary_rates(const struct FirstOrderComplementaryVect3 *filter)
Get current output rates from 1st order complementary filters.
static void reset_butterworth_2_complementary_vect3(struct Butterworth2ComplementaryVect3 *filter, const struct FloatVect3 *value)
Reset 3D vector of 2nd order Butterworth complementary filters to a specific value.
static struct FloatVect3 get_butterworth_2_complementary_vect3(const struct Butterworth2ComplementaryVect3 *filter)
Get current output 3D vector from 2nd order Butterworth complementary filters.
static void init_first_order_complementary_vect3(struct FirstOrderComplementaryVect3 *filter, const struct FloatVect3 *cut_off, float sample_time)
Initialize 3D vector of 1st order complementary filters.
static struct FloatVect3 get_first_order_complementary_vect3(const struct FirstOrderComplementaryVect3 *filter)
Get current output 3D vector from 1st order complementary filters.
3D vector of 2nd order Butterworth complementary filters.
3D vector of 1st order complementary filters.
float q
in rad/s
float p
in rad/s
float r
in rad/s
static void float_quat_normalize(struct FloatQuat *q)
static void float_quat_identity(struct FloatQuat *q)
initialises a quaternion to identity
static void float_vect_zero(float *a, const int n)
a = 0
void float_vect3_integrate_fi(struct FloatVect3 *vec, const struct FloatVect3 *dv, const float dt)
in place first order integration of a 3D-vector
void float_rates_vect3_integrate_fi(struct FloatRates *r, const struct FloatVect3 *dr, const float dt)
in place first order integration of angular rates
void float_quat_integrate(struct FloatQuat *q, const struct FloatRates *omega, const float dt)
in place quaternion integration with constant rotational velocity
#define FLOAT_RATES_ZERO(_r)
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.
void float_quat_vmult(struct FloatVect3 *v_out, const struct FloatQuat *q, const struct FloatVect3 *v_in)
rotate 3D vector by quaternion.
Roation quaternion.
angular rates
static struct FloatQuat * stateGetNedToBodyQuat_f(void)
Get vehicle body attitude quaternion (float).
Definition state.h:1302
static struct FloatVect3 * stateGetAccelBody_f(void)
Definition state.h:1100
static struct FloatRates * stateGetBodyRates_f(void)
Get vehicle body angular rate (float).
Definition state.h:1375
static struct NedCoor_f * stateGetSpeedNed_f(void)
Get ground speed in local NED coordinates (float).
Definition state.h:1049
Integrated Navigation System interface.
Simple first order low pass filter with bilinear transform.
Definitions and inline functions for 1st order low-pass filter vector types.
A first order low pass filter using Zero Order Hold (ZOH) discretization.
Zero Order Hold (ZOH) discrete first order low pass filter structure.
static void update_first_order_zoh_low_pass_array(const uint8_t n, struct FirstOrderZOHLowPass filter_array[restrict n], const float input_array[restrict n])
Update an array of first order ZOH low-pass filters.
static void init_first_order_zoh_low_pass_array(const uint8_t n, struct FirstOrderZOHLowPass filter_array[restrict n], const float omega[restrict n], const float sample_time)
Initialize a set of first order ZOH low-pass filters to zero for 3D vector data.
static void get_first_order_zoh_low_pass_array(const uint8_t n, const struct FirstOrderZOHLowPass filter_array[restrict n], float output_array[restrict n])
Retrieve the filtered outputs from an array of first order ZOH low-pass filters.
static void reset_first_order_zoh_low_pass_array(const uint8_t n, struct FirstOrderZOHLowPass filter_array[restrict n], const float value_array[restrict n])
Reset an array of first order ZOH low-pass filters to specific values.
uint16_t foo
Definition main_demo5.c:58
Hardware independent API for actuators (servos, motor controllers).
Specific navigation functions for hybrid aircraft.
float evaluate_obm_thrust_z(const float actuator_state[ANDI_NUM_ACT])
Compute total thrust produced by the current actuator state.
struct FloatVect3 evaluate_obm_forces(const struct FloatRates *rates, const struct FloatVect3 *vel_body, const float actuator_state[ANDI_NUM_ACT])
Evaluate total force acting on the vehicle from the OBM.
struct FloatVect3 evaluate_obm_moments(const struct FloatRates *rates, const struct FloatVect3 *vel_body, const float actuator_state[ANDI_NUM_ACT])
Evaluate total moments acting on the vehicle from the OBM.
void evaluate_obm_f_stb_u(float fu_mat[ANDI_NUM_ACT *ANDI_OUTPUTS], const struct FloatRates *rates, const struct FloatVect3 *vel_body, const float actuator_state[ANDI_NUM_ACT])
Evaluate the state-dependent control effectiveness matrix F_u for stabilization.
void evaluate_obm_f_stb_x(float nu_obm[ANDI_OUTPUTS], const struct FloatRates *rates, const struct FloatVect3 *vel_body, const struct FloatVect3 *ang_accel, const struct FloatVect3 *accel_body, const float actuator_state[ANDI_NUM_ACT])
Evaluate the state-dependent contribution F_x * x_dot for stabilization.
struct Gains3rdOrder k_att_rm
float nu[ANDI_OUTPUTS]
float act_max[ANDI_NUM_ACT_TOT]
float act_min[ANDI_NUM_ACT_TOT]
#define ANDI_NUM_ACT
#define ANDI_OUTPUTS
float gains[MAX_SAMPLES_LEARNING]
int16_t pprz_t
Definition paparazzi.h:6
#define MAX_PPRZ
Definition paparazzi.h:8
Paparazzi floating point algebra.
Generic interface for radio control modules.
Rotorcraft navigation functions.
static const ShellCommand commands[]
Definition shell_arch.c:78
struct FloatRates stab_sp_to_rates_f(struct StabilizationSetpoint *sp)
float th_sp_to_thrust_f(struct ThrustSetpoint *th, int32_t thrust, uint8_t axis)
struct StabilizationSetpoint stab_sp_from_rates_f(struct FloatRates *rates)
struct FloatQuat stab_sp_to_quat_f(struct StabilizationSetpoint *sp)
#define THRUST_AXIS_Z
const float ACTUATOR_PREF[ANDI_NUM_ACT]
struct AttQuat attitude_bounds
static float ec_k3_order3_f(const float omega_n, const float zeta, const float omega_a)
float actuator_state[ANDI_NUM_ACT]
const uint8_t ACTUATOR_DELAY[ANDI_NUM_ACT]
void stabilization_attitude_run(bool in_flight, struct StabilizationSetpoint *sp, struct ThrustSetpoint *thrust, int32_t *cmd)
Attitude control run function.
struct FirstOrderComplementaryVect3 attitude_rates_cf
float du_max[ANDI_NUM_ACT]
struct PolesOrder2Vect3 andi_p_rate_rm
static float control_error_thrust(const struct ThrustRef *thrust_ref, const float thrust_state, const float k_thrust_ec)
Computes the thrust control command based on desired and current thrust.
float andi_p_thrust_ec
void stabilization_andi_enter(void)
Initializes the ANDI stabilization controller state upon entering stabilization mode.
float andi_p_thrust_rm
static void generate_reference_attitude(float dt, const struct FloatQuat *att_des, const struct GainsOrder3Vect3 *k_att_rm, const struct AttQuat *bounds, struct AttQuat *att_ref)
Generates a bounded second-order reference signal for quaternion-based attitude control.
static void compute_wls_v_scaler(float v_scaler[ANDI_NUM_ACT], const float v[ANDI_NUM_ACT])
Compute output scaling factors for normalizing weighted least squares outputs.
struct GainsOrder3Vect3 andi_k_att_rm
void stabilization_attitude_enter(void)
Attitude control enter function.
static void compute_wls_lower_bounds(float u_d_min[ANDI_NUM_ACT], const float act_state[ANDI_NUM_ACT], const float act_min[ANDI_NUM_ACT], const float act_rate_min[ANDI_NUM_ACT], const float actuator_bandwidth[ANDI_NUM_ACT])
Compute lower bounds for actuator rate commands based on actuator state and constraints.
struct FloatRates angular_rates_obm
float andi_k_thrust_ec
static float ec_k1_order3_f(const float omega_n, const float zeta, const float omega_a)
const bool ACTUATOR_IS_SERVO[ANDI_NUM_ACT]
static void fetch_actuators_t4(float actuator_meas[ANDI_NUM_ACT], const struct ActuatorsT4In *actuators_t4_in_ptr)
Extract actuator states from ActuatorsT4In struct.
struct LinState linear_state_cf
void stabilization_andi_run(bool use_rate_control, bool in_flight, struct StabilizationSetpoint *stab_setpoint, struct ThrustSetpoint *thrust_setpoint, int32_t *cmd)
Main ANDI stabilization control loop.
float actuator_state_lpf[ANDI_NUM_ACT]
static struct GainsOrder2Vect3 compute_reference_gains_order_2_vect_3(const struct PolesOrder2Vect3 *poles)
Compute reference-model gains for a 2nd-order 3D system.
void stabilization_rate_enter(void)
struct PolesOrder3Vect3 andi_p_att_ec
static float rm_k1_order2_f(const float omega_a, const float zeta)
struct StabilizationSetpoint stabilization_rate_read_rc(struct RadioControl *rc)
static void generate_reference_thrust(float dt, float thrust_des, const float k_thrust_rm, const struct ThrustRef *bounds_min, const struct ThrustRef *bounds_max, struct ThrustRef *thrust_ref)
Generates a bounded second-order reference signal for thrust control.
static struct GainsOrder3Vect3 compute_error_gains_order_3_vect_3(const struct PolesOrder3Vect3 *poles)
Compute error-compensation gains for a 3rd-order 3D system.
struct PolesOrder2Vect3 andi_p_rate_ec
const float THRUST_MIN
struct FirstOrderComplementaryVect3 linear_vel_cf
struct FloatRates rates_des
struct GainsOrder3Vect3 andi_k_att_ec
struct Butterworth2ComplementaryVect3 linear_accel_cf
float nu_ec[ANDI_OUTPUTS]
static void generate_reference_rate(float dt, const struct FloatRates *rate_des, const struct GainsOrder2Vect3 *k_rate_rm, const struct AttQuat *bounds, struct AttQuat *att_ref)
Generates a bounded second-order reference signal for attitude rate control.
float u_cmd[ANDI_NUM_ACT]
struct WLS_t wls_stab_p
static void send_wls_u_stabilization_andi(struct transport_tx *trans, struct link_device *dev)
void stabilization_rate_run(bool in_flight, struct StabilizationSetpoint *rate_sp, struct ThrustSetpoint *thrust, int32_t *cmd)
void stabilization_andi_init(void)
struct ActuatorsT4In actuators_t4_obs
const float RC_RATE_MAX[ANDI_OUTPUTS]
const bool USE_STATE_DYNAMICS
static struct GainsOrder2Vect3 compute_error_gains_order_2_vect_3(const struct PolesOrder2Vect3 *poles)
Compute error-compensation gains for a 2nd-order 3D system.
struct Butterworth2ComplementaryVect3 attitude_accel_cf
static struct FloatVect3 control_error_attitude(const struct AttQuat *att_ref, const struct AttStateQuat *att_state, const struct GainsOrder3Vect3 *k_att_ec)
Computes the attitude rate error control command.
const float WLS_WV[ANDI_OUTPUTS]
struct ThrustRef thrust_ref
static void send_eff_mat_stabilization_andi(struct transport_tx *trans, struct link_device *dev)
static float rm_k2_order3_f(const float omega_n, const float zeta, const float omega_a)
float nu_obm[ANDI_OUTPUTS]
static float rm_k1_order3_f(const float omega_n, const float zeta, const float omega_a)
static void actuators_t4_in_callback(uint8_t sender_id, struct ActuatorsT4In *actuators_t4_in_ptr, float *actuators_t4_extra_data_in_ptr)
Callback function to handle incoming actuator telemetry data.
static struct FloatVect3 control_error_rate(const struct AttQuat *att_ref, const struct AttStateQuat *att_state, const struct GainsOrder2Vect3 *k_rate_ec)
Computes the control error command for attitude rate regulation.
struct ThrustRef thrust_bounds_max
float nu_obj[ANDI_OUTPUTS]
struct FloatRates rates_prev
static void send_stab_attitude_stabilization_andi(struct transport_tx *trans, struct link_device *dev)
struct AttStateQuat attitude_state_cf
struct FloatVect3 linear_velocity_obm
float actuator_meas[ANDI_NUM_ACT]
struct PolesOrder3Vect3 andi_p_att_rm
struct TransportDelay actuator_obm_delay[ANDI_NUM_ACT]
struct FirstOrderZOHLowPass actuator_obm_zohlpf[ANDI_NUM_ACT]
struct AttQuat attitude_ref
float andi_k_thrust_rm
float WLS_WU[ANDI_NUM_ACT]
Normalized actuator cost for WLS allocation.
static float rm_k2_order2_f(const float omega_a, const float zeta)
static float ec_k1_order2_f(const float omega_a, const float zeta)
abi_event actuators_t4_in_event
static void send_wls_v_stabilization_andi(struct transport_tx *trans, struct link_device *dev)
float thrust_des
static float ec_k2_order3_f(const float omega_n, const float zeta, const float omega_a)
const bool SCHEDULE_EFF
bool autopilot_in_flight_end_detection(bool motors_on)
float du_min[ANDI_NUM_ACT]
struct ThrustRef thrust_bounds_min
static void compute_wls_u_scaler(float u_scaler[ANDI_NUM_ACT], const float act_min[ANDI_NUM_ACT], const float act_max[ANDI_NUM_ACT])
Compute input scaling factors for normalizing weighted least squares.
static float ec_k2_order2_f(const float omega_a, const float zeta)
const float ANDI_RELAX_OBM
float du_cmd[ANDI_NUM_ACT]
struct FloatQuat attitude_des
struct GainsOrder2Vect3 andi_k_rate_ec
static void compute_wls_upper_bounds(float u_d_max[ANDI_NUM_ACT], const float act_state[ANDI_NUM_ACT], const float act_max[ANDI_NUM_ACT], const float act_rate_max[ANDI_NUM_ACT], const float actuator_bandwidth[ANDI_NUM_ACT])
Compute upper bounds for actuator rate commands based on actuator state and constraints.
float ce_mat[ANDI_NUM_ACT *ANDI_OUTPUTS]
static struct GainsOrder3Vect3 compute_reference_gains_order_3_vect_3(const struct PolesOrder3Vect3 *poles)
Compute reference-model gains for a 3rd-order 3D system.
struct GainsOrder2Vect3 andi_k_rate_rm
static float rm_k3_order3_f(const float omega_n, const float zeta, const float omega_a)
float thrust_state
ANDI stabilization controller for tiltbody rotorcraft.
struct FloatRates att_d
struct FloatVect3 k1
struct FloatVect3 vel
struct FloatQuat att
struct FloatVect3 acc
struct FloatVect3 att_2d
struct FloatQuat att
struct FloatRates att_d
struct FloatVect3 omega_a
struct FloatVect3 omega_n
struct FloatVect3 att_3d
struct FloatVect3 att_2d
struct FloatVect3 k1
Structure representing attitude in quaternion form along with its first three derivatives,...
Structure representing attitude in quaternion form along with its first two derivatives,...
Structure defining second-order gain parameters for vectorized 3D quantities.
Structure defining third-order gain parameters for vectorized 3D quantities.
Structure representing linear state with velocity and acceleration vectors.
Structure defining second-order pole parameters for vectorized 3D quantities.
Structure defining third-order pole parameters for vectorized 3D quantities.
Structure representing (specific) thrust reference and its derivative.
Read an attitude setpoint from the RC.
static struct FloatRates att_state
#define RC_RATE_R
#define RC_RATE_Q
#define YAW_RATE_DEADBAND_EXCEEDED(_rc)
#define RC_RATE_P
#define ROLL_RATE_DEADBAND_EXCEEDED(_rc)
#define PITCH_RATE_DEADBAND_EXCEEDED(_rc)
API to get/set the generic vehicle states.
static const struct usb_device_descriptor dev
Definition usb_ser_hw.c:74
Stabilization setpoint.
Thrust setpoint // TODO to a setpoint header Structure to store the desired thrust vector with differ...
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
Transport delay filter implementation.
Transport delay filter type definitions and array operations.
static void reset_transport_delay_array(const uint8_t n, struct TransportDelay td_array[restrict n], const float initial_value[restrict n])
Reset an array of TransportDelay structures to specific initial values.
static void update_transport_delay_array(uint8_t n, struct TransportDelay td_array[restrict n], const float input_array[restrict n])
Update an array of TransportDelay structures with input values.
static void get_transport_delay_array(const uint8_t n, const struct TransportDelay td_array[restrict n], float output_array[restrict n])
Get output values from an array of TransportDelay structures.
static void init_transport_delay_array(uint8_t n, struct TransportDelay td_array[restrict n], const uint8_t delay_samples[restrict n], float initial_value[restrict n])
Initialize an array of TransportDelay structures.
int int32_t
Typedef defining 32 bit int type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
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
float gamma_sq
Definition wls_alloc.h:69
float u[WLS_N_U_MAX]
Definition wls_alloc.h:71
int iter
Definition wls_alloc.h:79
float u_min[WLS_N_U_MAX]
Definition wls_alloc.h:75
float Wu[WLS_N_U_MAX]
Definition wls_alloc.h:73
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 Wv[WLS_N_V_MAX]
Definition wls_alloc.h:72
float v[WLS_N_V_MAX]
Definition wls_alloc.h:70
int nu
Definition wls_alloc.h:67