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 
  114  .Wv        =  {1000, 1000, 1, 100, 100},
 
  116  .Wv        =  {1000, 1000, 1, 100},
 
  119#ifdef STABILIZATION_INDI_WLS_WU  
 
  139#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE 
  158#if STABILIZATION_INDI_USE_ADAPTIVE 
  164#ifdef STABILIZATION_INDI_ACT_RATE_LIMIT 
  168#ifdef STABILIZATION_INDI_ACT_IS_SERVO 
  174#ifdef STABILIZATION_INDI_ACT_IS_THRUSTER_X 
  182#ifdef 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 
  248#if STABILIZATION_INDI_RPM_FEEDBACK 
  249#ifndef STABILIZATION_INDI_ACT_FEEDBACK_ID 
  250#define STABILIZATION_INDI_ACT_FEEDBACK_ID ABI_BROADCAST 
  261#ifdef STABILIZATION_INDI_G1 
  288#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER 
  298#if PERIODIC_TELEMETRY 
  300#if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE 
  339#if GUIDANCE_INDI_HYBRID 
 
  376#ifdef STABILIZATION_INDI_ACT_FREQ 
  383#if STABILIZATION_INDI_RPM_FEEDBACK 
  397#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE 
  426#if PERIODIC_TELEMETRY 
  430  #if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE 
 
  454  float tau = 1.0 / (2.0 * 
M_PI * freq);
 
  456#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER 
 
  478  for (i = 0; i < 3; i++) {
 
  495#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER 
 
  557  for (i = 0; i < 3; i++) {
 
  590#if STABILIZATION_INDI_FILTER_ROLL_RATE 
  591#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER 
  599#if STABILIZATION_INDI_FILTER_PITCH_RATE 
  600#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER 
  608#if STABILIZATION_INDI_FILTER_YAW_RATE 
  609#if STABILIZATION_INDI_FILTER_RATES_SECOND_ORDER 
  626  if (thrust->
type == THRUST_INCR_SP) {
 
  675#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE 
 
  731#if !STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE 
  740#ifdef GUIDANCE_INDI_MIN_THROTTLE 
 
  823#if STABILIZATION_INDI_RPM_FEEDBACK 
  835#ifdef STABILIZATION_INDI_ACT_RATE_LIMIT 
 
  898#ifndef STABILIZATION_INDI_ADAPTIVE_MU 
  954#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE 
 
  979#if STABILIZATION_INDI_ALLOCATION_PSEUDO_INVERSE 
 1025#if STABILIZATION_INDI_RPM_FEEDBACK 
 1029  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_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)
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...
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]