39 #include "generated/airframe.h"
48 #define INDI_ALLOWED_G_FACTOR 2.0
50 #ifdef STABILIZATION_INDI_FILT_CUTOFF_P
51 #define STABILIZATION_INDI_FILTER_ROLL_RATE TRUE
53 #define STABILIZATION_INDI_FILT_CUTOFF_P 20.0
56 #ifdef STABILIZATION_INDI_FILT_CUTOFF_Q
57 #define STABILIZATION_INDI_FILTER_PITCH_RATE TRUE
59 #define STABILIZATION_INDI_FILT_CUTOFF_Q 20.0
62 #ifdef STABILIZATION_INDI_FILT_CUTOFF_R
63 #define STABILIZATION_INDI_FILTER_YAW_RATE TRUE
65 #define STABILIZATION_INDI_FILT_CUTOFF_R 20.0
69 #ifndef STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
70 #define STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE FALSE
73 #ifndef STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
74 #define STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER FALSE
79 #ifndef STABILIZATION_INDI_THROTTLE_LIMIT_AIRSPEED_FWD
80 #define STABILIZATION_INDI_THROTTLE_LIMIT_AIRSPEED_FWD 8.0
84 #ifndef STABILIZATION_INDI_G1_THRUST_X
85 #error "You must define STABILIZATION_INDI_G1_THRUST_X for your number of INDI_OUTPUTS"
89 #ifdef SetCommandsFromRC
90 #warning SetCommandsFromRC not used: STAB_INDI writes actuators directly
93 #ifdef SetAutoCommandsFromRC
94 #warning SetAutoCommandsFromRC not used: STAB_INDI writes actuators directly
98 #if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
99 #if INDI_NUM_ACT > WLS_N_U_MAX
100 #error Matrix-WLS_N_U_MAX too small or not defined: define WLS_N_U_MAX >= INDI_NUM_ACT in airframe file
102 #if INDI_OUTPUTS > WLS_N_V_MAX
103 #error Matrix-WLS_N_V_MAX too small or not defined: define WLS_N_V_MAX >= INDI_OUTPUTS in airframe file
110 #ifdef STABILIZATION_INDI_WLS_PRIORITIES
111 .Wv = STABILIZATION_INDI_WLS_PRIORITIES,
113 #if INDI_OUTPUTS == 5
114 .Wv = {1000, 1000, 1, 100, 100},
116 .Wv = {1000, 1000, 1, 100},
119 #ifdef STABILIZATION_INDI_WLS_WU
120 .Wu = STABILIZATION_INDI_WLS_WU,
122 .Wu = {[0 ... INDI_NUM_ACT - 1] = 1.0},
139 #if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
140 static void calc_g1g2_pseudo_inv(
void);
147 STABILIZATION_INDI_REF_ERR_P,
148 STABILIZATION_INDI_REF_ERR_Q,
149 STABILIZATION_INDI_REF_ERR_R
152 STABILIZATION_INDI_REF_RATE_P,
153 STABILIZATION_INDI_REF_RATE_Q,
154 STABILIZATION_INDI_REF_RATE_R
158 #if STABILIZATION_INDI_USE_ADAPTIVE
164 #ifdef STABILIZATION_INDI_ACT_RATE_LIMIT
165 float act_rate_limit[INDI_NUM_ACT] = STABILIZATION_INDI_ACT_RATE_LIMIT;
168 #ifdef STABILIZATION_INDI_ACT_IS_SERVO
169 bool act_is_servo[INDI_NUM_ACT] = STABILIZATION_INDI_ACT_IS_SERVO;
174 #ifdef STABILIZATION_INDI_ACT_IS_THRUSTER_X
182 #ifdef STABILIZATION_INDI_ACT_PREF
184 float act_pref[INDI_NUM_ACT] = STABILIZATION_INDI_ACT_PREF;
190 #ifdef STABILIZATION_INDI_ACT_DYN
191 #warning STABILIZATION_INDI_ACT_DYN is deprecated, use STABILIZATION_INDI_ACT_FREQ instead.
192 #warning You now have to define the continuous time corner frequency in rad/s of the actuators.
193 #warning "Use -ln(1 - old_number) * PERIODIC_FREQUENCY to compute it from the old values."
203 #ifdef STABILIZATION_INDI_YAW_DISTURBANCE_LIMIT
233 float mu1[INDI_OUTPUTS] = {0.00001, 0.00001, 0.000003, 0.000002};
248 #if STABILIZATION_INDI_RPM_FEEDBACK
249 #ifndef STABILIZATION_INDI_ACT_FEEDBACK_ID
250 #define STABILIZATION_INDI_ACT_FEEDBACK_ID ABI_BROADCAST
260 float g2[INDI_NUM_ACT] = STABILIZATION_INDI_G2;
261 #ifdef STABILIZATION_INDI_G1
262 float g1[INDI_OUTPUTS][INDI_NUM_ACT] = STABILIZATION_INDI_G1;
264 #if INDI_OUTPUTS == 5
265 float g1[INDI_OUTPUTS][INDI_NUM_ACT] = {STABILIZATION_INDI_G1_ROLL,
266 STABILIZATION_INDI_G1_PITCH, STABILIZATION_INDI_G1_YAW,
267 STABILIZATION_INDI_G1_THRUST, STABILIZATION_INDI_G1_THRUST_X
270 float g1[INDI_OUTPUTS][INDI_NUM_ACT] = {STABILIZATION_INDI_G1_ROLL,
271 STABILIZATION_INDI_G1_PITCH, STABILIZATION_INDI_G1_YAW, STABILIZATION_INDI_G1_THRUST
276 float g1g2[INDI_OUTPUTS][INDI_NUM_ACT];
277 float g1_est[INDI_OUTPUTS][INDI_NUM_ACT];
288 #if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
298 #if PERIODIC_TELEMETRY
300 #if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
312 pprz_msg_send_EFF_MAT_STAB(trans,
dev, AC_ID,
313 INDI_NUM_ACT,
g1g2[0],
314 INDI_NUM_ACT,
g1g2[1],
315 INDI_NUM_ACT,
g1g2[2],
316 INDI_NUM_ACT,
g1g2[3],
323 pprz_msg_send_AHRS_REF_QUAT(trans,
dev, AC_ID,
339 #if GUIDANCE_INDI_HYBRID
349 float temp_att_ref[3] = {att_sp.
phi, att_sp.
theta, att_sp.
psi};
350 float temp_rate[3] = {body_rates->
p, body_rates->
q, body_rates->
r};
353 pprz_msg_send_STAB_ATTITUDE(trans,
dev, AC_ID,
376 #ifdef STABILIZATION_INDI_ACT_FREQ
378 for (i = 0; i < INDI_NUM_ACT; i++) {
383 #if STABILIZATION_INDI_RPM_FEEDBACK
397 #if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
399 calc_g1g2_pseudo_inv();
403 for (i = 0; i < INDI_OUTPUTS; i++) {
417 for (i = 0; i < INDI_NUM_ACT; i++) {
426 #if PERIODIC_TELEMETRY
430 #if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
454 float tau = 1.0 / (2.0 * M_PI * freq);
455 float sample_time = 1.0 / PERIODIC_FREQUENCY;
456 #if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
475 float sample_time = 1.0 / PERIODIC_FREQUENCY;
478 for (i = 0; i < 3; i++) {
484 for (i = 0; i < INDI_NUM_ACT; i++) {
495 #if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
525 float actuator_state_filt_vect_prev[INDI_NUM_ACT];
526 for (
int i = 0; i < INDI_NUM_ACT; i++) {
543 float angular_acc_prediction_filt[INDI_OUTPUTS];
545 angular_acc_prediction_filt[2] -= g2_times_u_act_filt;
549 float rate_vect[3] = {body_rates->
p, body_rates->
q, body_rates->
r};
557 for (i = 0; i < 3; i++) {
575 float angular_acc_disturbance_estimate[INDI_OUTPUTS];
590 #if STABILIZATION_INDI_FILTER_ROLL_RATE
591 #if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
597 rates_filt.
p = body_rates->
p;
599 #if STABILIZATION_INDI_FILTER_PITCH_RATE
600 #if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
606 rates_filt.
q = body_rates->
q;
608 #if STABILIZATION_INDI_FILTER_YAW_RATE
609 #if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
615 rates_filt.
r = body_rates->
r;
625 struct FloatVect3 v_thrust = { 0.f, 0.f, 0.f };
626 if (thrust->type == THRUST_INCR_SP) {
633 for (i = 0; i < INDI_NUM_ACT; i++) {
635 #if INDI_OUTPUTS == 5
644 for (i = 0; i < INDI_NUM_ACT; i++) {
645 v_thrust.z += th_cmd_z *
Bwls[3][i];
646 #if INDI_OUTPUTS == 5
649 v_thrust.x += cmd[COMMAND_THRUST_X] *
Bwls[4][i];
671 #if INDI_OUTPUTS == 5
675 #if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
677 for (i = 0; i < INDI_NUM_ACT; i++) {
687 for (i = 0; i < INDI_OUTPUTS; i++) {
691 for (i = 0; i < INDI_NUM_ACT; i++) {
697 for (i = 0; i < INDI_NUM_ACT; i++) {
715 for (i = 0; i < INDI_NUM_ACT; i++) {
720 cmd[COMMAND_THRUST] = 0;
721 for (i = 0; i < INDI_NUM_ACT; i++) {
731 #if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
735 for (
uint8_t i = 0; i < INDI_NUM_ACT; i++) {
740 #ifdef GUIDANCE_INDI_MIN_THROTTLE
786 att_fb.
x = att_err.
qx;
787 att_fb.
y = att_err.
qy;
788 att_fb.
z = att_err.
qz;
823 #if STABILIZATION_INDI_RPM_FEEDBACK
828 float UNUSED prev_actuator_state;
829 for (i = 0; i < INDI_NUM_ACT; i++) {
835 #ifdef STABILIZATION_INDI_ACT_RATE_LIMIT
836 if ((
actuator_state[i] - prev_actuator_state) > act_rate_limit[i]) {
838 }
else if ((
actuator_state[i] - prev_actuator_state) < -act_rate_limit[i]) {
898 #ifndef STABILIZATION_INDI_ADAPTIVE_MU
899 float adaptive_mu_lr = 0.001;
901 float adaptive_mu_lr = STABILIZATION_INDI_ADAPTIVE_MU;
914 for (i = 0; i < INDI_OUTPUTS; i++) {
916 float ddx_error = - ddx_estimation[i];
918 for (j = 0; j < INDI_NUM_ACT; j++) {
928 for (j = 0; j < INDI_NUM_ACT; j++) {
933 if (fabs(indi_accel_d) > 60.0) {
939 for (j = 0; j < INDI_NUM_ACT; j++) {
954 #if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
956 calc_g1g2_pseudo_inv();
968 for (i = 0; i < INDI_OUTPUTS; i++) {
969 for (j = 0; j < INDI_NUM_ACT; j++) {
979 #if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
984 void calc_g1g2_pseudo_inv(
void)
992 for (row = 0; row < INDI_OUTPUTS; row++) {
993 for (col = 0; col < INDI_OUTPUTS; col++) {
995 for (i = 0; i < INDI_NUM_ACT; i++) {
996 element = element +
g1g2[row][i] *
g1g2[col][i];
1013 for (row = 0; row < INDI_NUM_ACT; row++) {
1014 for (col = 0; col < INDI_OUTPUTS; col++) {
1016 for (i = 0; i < INDI_OUTPUTS; i++) {
1017 element = element +
g1g2[i][row] *
g1g2inv[col][i];
1025 #if STABILIZATION_INDI_RPM_FEEDBACK
1029 for (i = 0; i < num_act; i++) {
1031 if (feedback[i].
idx < INDI_NUM_ACT && feedback[i].set.rpm) {
1045 for (j = 0; j < INDI_NUM_ACT; j++) {
1050 for (i = 0; i < INDI_OUTPUTS; i++) {
1059 if (
g1_est[i][j] > max_limit) {
1060 g1_est[i][j] = max_limit;
1062 if (
g1_est[i][j] < min_limit) {
1063 g1_est[i][j] = min_limit;
1076 if (
g2_est[j] > max_limit) {
1079 if (
g2_est[j] < min_limit) {
Main include for ABI (AirBorneInterface).
Event structure to store callbacks in a linked list.
bool autopilot_get_motors_on(void)
get motors status
static void float_vect_zero(float *a, const int n)
a = 0
void float_quat_inv_comp_norm_shortest(struct FloatQuat *b2c, struct FloatQuat *a2b, struct FloatQuat *a2c)
Composition (multiplication) of two quaternions with normalization.
static void float_vect_smul(float *o, const float *a, const float s, const int n)
o = a * s
static void float_mat_vect_mul(float *o, float **a, float *b, int m, int n)
o = a * b
static void float_vect_scale(float *a, const float s, const int n)
a *= s
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
void float_eulers_of_quat_zxy(struct FloatEulers *e, struct FloatQuat *q)
euler rotation 'ZXY' This rotation order is useful if you need 90 deg pitch
static void float_vect_diff(float *o, const float *a, const float *b, const int n)
o = a - b
void float_quat_tilt_twist(struct FloatQuat *tilt, struct FloatQuat *twist, struct FloatQuat *quat)
Tilt twist decomposition of a quaternion (z axis)
bool float_mat_inv_4d(float invOut[4][4], float mat_in[4][4])
4x4 Matrix inverse
#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)
static struct Int32Quat * stateGetNedToBodyQuat_i(void)
Get vehicle body attitude quaternion (int).
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
static struct FloatQuat * stateGetNedToBodyQuat_f(void)
Get vehicle body attitude quaternion (float).
static struct FloatRates * stateGetBodyRates_f(void)
Get vehicle body angular rate (float).
static struct Int32Vect3 * stateGetAccelBody_i(void)
Get acceleration in Body coordinates (int).
static float stateGetAirspeed_f(void)
Get airspeed (float).
Butterworth2LowPass thrust_filt
PRINT_CONFIG_MSG("USE_INS_NAV_INIT defaulting to TRUE")
Simple first order low pass filter with bilinear transform.
static float update_first_order_low_pass(struct FirstOrderLowPass *filter, float value)
Update first order low pass filter state with a new value.
static void init_butterworth_2_low_pass(Butterworth2LowPass *filter, float tau, float sample_time, float value)
Init a second order Butterworth filter.
static void init_first_order_low_pass(struct FirstOrderLowPass *filter, float tau, float sample_time, float value)
Init first order low pass filter.
static float update_butterworth_2_low_pass(Butterworth2LowPass *filter, 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.
Hardware independent API for actuators (servos, motor controllers).
uint8_t idx
General index of the actuators (generated in airframe.h)
static float mu
Physical model parameters.
PRINT_CONFIG_VAR(ONELOOP_ANDI_FILT_CUTOFF)
static abi_event act_feedback_ev
Paparazzi floating point algebra.
struct RadioControl radio_control
Generic interface for radio control modules.
pprz_t values[RADIO_CONTROL_NB_CHANNEL]
struct HorizontalGuidance guidance_h
#define GUIDANCE_H_MODE_NAV
#define GUIDANCE_H_MODE_HOVER
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)
Read an attitude setpoint from the RC.
static void calc_g1_element(float dx_error, int8_t i, int8_t j, float mu_extra)
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.
Butterworth2LowPass acceleration_body_x_filter
float act_pref[INDI_NUM_ACT]
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
bool act_is_thruster_x[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)
float actuator_state_filt_vectd[INDI_NUM_ACT]
#define STABILIZATION_INDI_FILT_CUTOFF_P
static void bound_g_mat(void)
#define STABILIZATION_INDI_FILT_CUTOFF_Q
float g1g2[INDI_OUTPUTS][INDI_NUM_ACT]
static void calc_g2_element(float dx_error, int8_t j, float mu_extra)
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]
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)
bool act_is_thruster_z[INDI_NUM_ACT]
struct FloatVect3 body_accel_f
float ddu_estimation[INDI_NUM_ACT]
float estimation_rate_dd[INDI_NUM_ACT]
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
float stablization_indi_yaw_dist_limit
Limit the maximum specific moment that can be compensated (units rad/s^2)
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]
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
float g2_init[INDI_NUM_ACT]
Butterworth2LowPass estimation_input_lowpass_filters[INDI_NUM_ACT]
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]
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
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]
void init_filters(void)
Function that resets the filters to zeros.
Butterworth2LowPass estimation_output_lowpass_filters[3]
#define STABILIZATION_INDI_ESTIMATION_FILT_CUTOFF
#define STABILIZATION_INDI_FILT_CUTOFF
API to get/set the generic vehicle states.
static const struct usb_device_descriptor dev
union StabilizationSetpoint::@278 sp
Thrust setpoint // TODO to a setpoint header Structure to store the desired thrust vector with differ...
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Periodic telemetry system header (includes downlink utility and generated code).
#define DefaultPeriodic
Set default periodic telemetry.
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)
void wls_alloc(struct WLS_t *WLS_p, float **B, float *u_guess, float *W_init, int imax)
active set algorithm for control allocation
void send_wls_u(char *name, struct WLS_t *WLS_p, struct transport_tx *trans, struct link_device *dev)
float u_pref[WLS_N_U_MAX]