46#include "generated/airframe.h"
70#ifdef STABILIZATION_ANDI_SCHEDULE_EFF
76#ifdef STABILIZATION_ANDI_USE_STATE_DYNAMICS
82#ifdef STABILIZATION_ANDI_RELAX_OBM
88#ifdef STABILIZATION_ANDI_ACT_IS_SERVO
94#ifdef STABILIZATION_ANDI_ACT_DYNAMICS
97 #error "You must specify the actuator dynamics"
100#ifdef STABILIZATION_ANDI_ACT_DELAY
106#if defined(STABILIZATION_ANDI_ACT_MAX) && defined(STABILIZATION_ANDI_ACT_MIN)
110 #error "You must specify the actuator limits: STABILIZATION_ANDI_ACT_MAX and STABILIZATION_ANDI_ACT_MIN"
113#if defined(STABILIZATION_ANDI_ACT_RATE_MAX) && defined(STABILIZATION_ANDI_ACT_RATE_MIN)
117 #error "You must specify the actuator limits: STABILIZATION_ANDI_ACT_RATE_MAX and STABILIZATION_ANDI_ACT_RATE_MIN"
120#if defined STABILIZATION_ANDI_ACT_PREF
126#if defined STABILIZATION_ANDI_RC_RATE_MAX
132#ifdef STABILIZATION_ANDI_THRUST_MIN
138#ifdef STABILIZATION_ANDI_THRUST_MAX
141 #error "You must specify maximum specific thrust: STABILIZATION_ANDI_THRUST_MAX"
144#ifdef PERIODIC_FREQUENCY
147 #error "Periodic frequency is not defined."
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
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
157#ifdef STABILIZATION_ANDI_WLS_WV
169#ifdef STABILIZATION_ANDI_WLS_WU
175#ifdef STABILIZATION_ANDI_CUTOFF_FREQ_OMEGA
182#error "You must specify the cutoff frequency for omega: STABILIZATION_ANDI_CUTOFF_FREQ_OMEGA"
185#ifdef STABILIZATION_ANDI_CUTOFF_FREQ_OMEGA_DOT
194#error "You must specify the cutoff frequency for omega_dot: STABILIZATION_ANDI_CUTOFF_FREQ_OMEGA_DOT"
197#ifdef STABILIZATION_ANDI_CUTOFF_FREQ_ACCEL
204#error "You must specify the cutoff frequency for accel: STABILIZATION_ANDI_CUTOFF_FREQ_ACCEL"
207#ifdef STABILIZATION_ANDI_CUTOFF_FREQ_VEL
214#error "You must specify the cutoff frequency for vel: STABILIZATION_ANDI_CUTOFF_FREQ_VEL"
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)); }
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; }
257static inline float ec_k1_order2_f(
const float omega_a,
const float zeta) {
return omega_a * omega_a / (4 * zeta * zeta); }
328 .gamma_sq = 100000.0,
400#if PERIODIC_TELEMETRY
1073#if PERIODIC_TELEMETRY
Main include for ABI (AirBorneInterface).
#define ABI_BROADCAST
Broadcast address.
Event structure to store callbacks in a linked list.
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.
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.
static struct FloatQuat * stateGetNedToBodyQuat_f(void)
Get vehicle body attitude quaternion (float).
static struct FloatVect3 * stateGetAccelBody_f(void)
static struct FloatRates * stateGetBodyRates_f(void)
Get vehicle body angular rate (float).
static struct NedCoor_f * stateGetSpeedNed_f(void)
Get ground speed in local NED coordinates (float).
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.
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 act_max[ANDI_NUM_ACT_TOT]
float act_min[ANDI_NUM_ACT_TOT]
float gains[MAX_SAMPLES_LEARNING]
Paparazzi floating point algebra.
Generic interface for radio control modules.
Rotorcraft navigation functions.
static const ShellCommand commands[]
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)
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.
void stabilization_andi_enter(void)
Initializes the ANDI stabilization controller state upon entering stabilization mode.
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
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
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]
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 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)
static float ec_k2_order3_f(const float omega_n, const float zeta, const float omega_a)
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)
ANDI stabilization controller for tiltbody rotorcraft.
struct FloatVect3 omega_a
struct FloatVect3 omega_n
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 YAW_RATE_DEADBAND_EXCEEDED(_rc)
#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
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.
Periodic telemetry system header (includes downlink utility and generated code).
#define DefaultPeriodic
Set default periodic telemetry.
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
float u_pref[WLS_N_U_MAX]