38#include "generated/airframe.h"
47#define INDI_ALLOWED_G_FACTOR 2.0
49#ifdef STABILIZATION_INDI_FILT_CUTOFF_P
50#define STABILIZATION_INDI_FILTER_ROLL_RATE TRUE
52#define STABILIZATION_INDI_FILT_CUTOFF_P 20.0
55#ifdef STABILIZATION_INDI_FILT_CUTOFF_Q
56#define STABILIZATION_INDI_FILTER_PITCH_RATE TRUE
58#define STABILIZATION_INDI_FILT_CUTOFF_Q 20.0
61#ifdef STABILIZATION_INDI_FILT_CUTOFF_R
62#define STABILIZATION_INDI_FILTER_YAW_RATE TRUE
64#define STABILIZATION_INDI_FILT_CUTOFF_R 20.0
68#ifndef STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
69#define STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE FALSE
72#ifndef STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
73#define STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER FALSE
78#ifndef STABILIZATION_INDI_THROTTLE_LIMIT_AIRSPEED_FWD
79#define STABILIZATION_INDI_THROTTLE_LIMIT_AIRSPEED_FWD 8.0
82#ifndef STABILIZATION_INDI_USE_ADAPTIVE
83#define STABILIZATION_INDI_USE_ADAPTIVE false
86#ifndef STABILIZATION_INDI_ADAPTIVE_MU
87#define STABILIZATION_INDI_ADAPTIVE_MU 0.001f
90#ifndef STABILIZATION_INDI_ACT_IS_SERVO
91#define STABILIZATION_INDI_ACT_IS_SERVO {0}
94#ifndef STABILIZATION_INDI_ACT_IS_THRUSTER_X
95#define STABILIZATION_INDI_ACT_IS_THRUSTER_X {0}
98#ifndef STABILIZATION_INDI_ACT_IS_THRUSTER_Y
99#define STABILIZATION_INDI_ACT_IS_THRUSTER_Y {0}
105#ifndef STABILIZATION_INDI_YAW_DISTURBANCE_LIMIT
106#define STABILIZATION_INDI_YAW_DISTURBANCE_LIMIT 99999.f
110#ifndef STABILIZATION_INDI_G1_THRUST_X
111#error "You must define STABILIZATION_INDI_G1_THRUST_X for your number of INDI_OUTPUTS"
115#ifdef SetCommandsFromRC
116#warning SetCommandsFromRC not used: STAB_INDI writes actuators directly
119#ifdef SetAutoCommandsFromRC
120#warning SetAutoCommandsFromRC not used: STAB_INDI writes actuators directly
123#if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
126#ifndef STABILIZATION_INDI_WLS_PRIORITIES
128#define STABILIZATION_INDI_WLS_PRIORITIES {1000, 1000, 1, 100, 100}
130#define STABILIZATION_INDI_WLS_PRIORITIES {1000, 1000, 1, 100}
135#ifndef STABILIZATION_INDI_WLS_WU
136#define STABILIZATION_INDI_WLS_WU {[0 ... INDI_NUM_ACT - 1] = 1.0}
141#ifndef STABILIZATION_INDI_ACT_PREF
142#define STABILIZATION_INDI_ACT_PREF {0.0}
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
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
179#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
200#ifdef STABILIZATION_INDI_ACT_RATE_LIMIT
209#ifdef STABILIZATION_INDI_ACT_THRUST_MAT
215#ifdef STABILIZATION_INDI_ACT_IS_THRUSTER_Z
223#ifdef STABILIZATION_INDI_ACT_DYN
224#warning STABILIZATION_INDI_ACT_DYN is deprecated, use STABILIZATION_INDI_ACT_FREQ instead.
225#warning You now have to define the continuous time corner frequency in rad/s of the actuators.
226#warning "Use -ln(1 - old_number) * PERIODIC_FREQUENCY to compute it from the old values."
274#if STABILIZATION_INDI_RPM_FEEDBACK
275#ifndef STABILIZATION_INDI_ACT_FEEDBACK_ID
276#define STABILIZATION_INDI_ACT_FEEDBACK_ID ABI_BROADCAST
287#ifdef STABILIZATION_INDI_G1
317#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
328#if PERIODIC_TELEMETRY
330#if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
369#if GUIDANCE_INDI_HYBRID
406#ifdef STABILIZATION_INDI_ACT_FREQ
413#if STABILIZATION_INDI_RPM_FEEDBACK
427#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
446#ifndef STABILIZATION_INDI_ACT_IS_THRUSTER_Z
455#if PERIODIC_TELEMETRY
459 #if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
483 float tau = 1.0 / (2.0 *
M_PI * freq);
485#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
507 for (i = 0; i < 3; i++) {
521#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
541#if STABILIZATION_INDI_FILTER_ROLL_RATE
542#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
550#if STABILIZATION_INDI_FILTER_PITCH_RATE
551#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
559#if STABILIZATION_INDI_FILTER_YAW_RATE
560#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER
616 for (i = 0; i < 3; i++) {
654 if (thrust->
type == THRUST_INCR_SP) {
683#if (INDI_OUTPUTS == 5) && (defined RADIO_CONTROL_THRUST_X) && (defined COMMAND_THRUST_X)
734#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
860#if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
869#ifdef GUIDANCE_INDI_MIN_THROTTLE
894#if STABILIZATION_INDI_RPM_FEEDBACK
906#ifdef STABILIZATION_INDI_ACT_RATE_LIMIT
1017#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
1042#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE
1088#if STABILIZATION_INDI_RPM_FEEDBACK
1092 for (i = 0; i <
num_act; i++) {
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_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.
#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).
PRINT_CONFIG_MSG("USE_INS_NAV_INIT defaulting to TRUE")
Simple first order low pass filter with bilinear transform.
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.
Hardware independent API for actuators (servos, motor controllers).
uint8_t idx
General index of the actuators (generated in airframe.h)
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)
#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)
float actuator_state_filt_vectd[INDI_NUM_ACT]
#define STABILIZATION_INDI_ADAPTIVE_MU
#define STABILIZATION_INDI_FILT_CUTOFF_P
static void bound_g_mat(void)
#define STABILIZATION_INDI_FILT_CUTOFF_Q
#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)
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)
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
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
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 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...
enum ThrustSetpoint::@282 type
int16_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint16_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]