Paparazzi UAS v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
Loading...
Searching...
No Matches
stabilization_andi.h File Reference

ANDI stabilization controller for tiltbody rotorcraft. More...

#include "firmwares/rotorcraft/stabilization.h"
#include "firmwares/rotorcraft/stabilization/stabilization_rate.h"
#include "generated/airframe.h"
#include <stdio.h>
#include "filters/low_pass_filter.h"
+ Include dependency graph for stabilization_andi.h:
+ This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Data Structures

struct  AttQuat
 Structure representing attitude in quaternion form along with its first three derivatives, used for reference. More...
 
struct  AttStateQuat
 Structure representing attitude in quaternion form along with its first two derivatives, used for state. More...
 
struct  LinState
 Structure representing linear state with velocity and acceleration vectors. More...
 
struct  ThrustRef
 Structure representing (specific) thrust reference and its derivative. More...
 
struct  PolesOrder3Vect3
 Structure defining third-order pole parameters for vectorized 3D quantities. More...
 
struct  PolesOrder2Vect3
 Structure defining second-order pole parameters for vectorized 3D quantities. More...
 
struct  GainsOrder2Vect3
 Structure defining second-order gain parameters for vectorized 3D quantities. More...
 
struct  GainsOrder3Vect3
 Structure defining third-order gain parameters for vectorized 3D quantities. More...
 

Macros

#define ANDI_NUM_ACT   COMMANDS_NB_REAL
 

Functions

void stabilization_andi_init (void)
 
void stabilization_andi_enter (void)
 Initializes the ANDI stabilization controller state upon entering stabilization mode.
 
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.
 
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.
 
float evaluate_obm_thrust_z (const float actuator_state[ANDI_NUM_ACT])
 Compute total thrust produced by the current actuator state.
 

Variables

struct PolesOrder2Vect3 andi_p_rate_ec
 
struct PolesOrder2Vect3 andi_p_rate_rm
 
struct PolesOrder3Vect3 andi_p_att_ec
 
struct PolesOrder3Vect3 andi_p_att_rm
 
float andi_p_thrust_ec
 
float andi_p_thrust_rm
 

Detailed Description

ANDI stabilization controller for tiltbody rotorcraft.

Provides declarations, configuration parameters, and interfaces for the ANDI controller implemented in stabilization_andi.c.

See also
stabilization_andi.c
Author
Justin Dubois j.p.g.nosp@m..dub.nosp@m.ois@s.nosp@m.tude.nosp@m.nt.tu.nosp@m.delf.nosp@m.t.nl

Definition in file stabilization_andi.h.


Data Structure Documentation

◆ AttQuat

struct AttQuat

Structure representing attitude in quaternion form along with its first three derivatives, used for reference.

This structure encapsulates the attitude represented as a quaternion, its first derivative (angular rates), second derivative (angular accelerations), and third derivative (angular jerks). It is primarily used for reference representation in the ANDI controller.

Definition at line 60 of file stabilization_andi.h.

+ Collaboration diagram for AttQuat:
Data Fields
struct FloatQuat att
struct FloatVect3 att_2d
struct FloatVect3 att_3d
struct FloatRates att_d

◆ AttStateQuat

struct AttStateQuat

Structure representing attitude in quaternion form along with its first two derivatives, used for state.

This structure encapsulates the attitude represented as a quaternion, its first derivative (angular rates), and second derivative (angular accelerations). It is primarily used for state representation in the ANDI controller.

Definition at line 74 of file stabilization_andi.h.

+ Collaboration diagram for AttStateQuat:
Data Fields
struct FloatQuat att
struct FloatVect3 att_2d
struct FloatRates att_d

◆ LinState

struct LinState

Structure representing linear state with velocity and acceleration vectors.

This structure encapsulates the linear state of the vehicle, including its velocity and acceleration as 3D vectors.

Definition at line 86 of file stabilization_andi.h.

+ Collaboration diagram for LinState:
Data Fields
struct FloatVect3 acc
struct FloatVect3 vel

◆ ThrustRef

struct ThrustRef

Structure representing (specific) thrust reference and its derivative.

This structure encapsulates the thrust reference, including the thrust value and its first derivative.

Definition at line 97 of file stabilization_andi.h.

Data Fields
float thrust
float thrust_d

◆ PolesOrder3Vect3

struct PolesOrder3Vect3

Structure defining third-order pole parameters for vectorized 3D quantities.

This structure holds the natural frequencies, damping ratios, and the pseudo actuator dynamics.

Definition at line 108 of file stabilization_andi.h.

+ Collaboration diagram for PolesOrder3Vect3:
Data Fields
struct FloatVect3 omega_a
struct FloatVect3 omega_n
struct FloatVect3 zeta

◆ PolesOrder2Vect3

struct PolesOrder2Vect3

Structure defining second-order pole parameters for vectorized 3D quantities.

This structure holds the natural frequencies and damping ratios.

Definition at line 119 of file stabilization_andi.h.

+ Collaboration diagram for PolesOrder2Vect3:
Data Fields
struct FloatVect3 omega_a
struct FloatVect3 zeta

◆ GainsOrder2Vect3

struct GainsOrder2Vect3

Structure defining second-order gain parameters for vectorized 3D quantities.

Definition at line 127 of file stabilization_andi.h.

+ Collaboration diagram for GainsOrder2Vect3:
Data Fields
struct FloatVect3 k1
struct FloatVect3 k2

◆ GainsOrder3Vect3

struct GainsOrder3Vect3

Structure defining third-order gain parameters for vectorized 3D quantities.

Definition at line 135 of file stabilization_andi.h.

+ Collaboration diagram for GainsOrder3Vect3:
Data Fields
struct FloatVect3 k1
struct FloatVect3 k2
struct FloatVect3 k3

Macro Definition Documentation

◆ ANDI_NUM_ACT

#define ANDI_NUM_ACT   COMMANDS_NB_REAL

Definition at line 45 of file stabilization_andi.h.

Function Documentation

◆ evaluate_obm_f_stb_u()

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.

This function computes the mapping from actuator inputs to aerodynamic/motor outputs for the stabilization model. The output is written into the provided, pre-allocated array fu_mat of size ANDI_NUM_ACT * ANDI_OUTPUTS.

The produced matrix represents the partial derivatives of the modeled outputs with respect to actuator commands (∂f/∂u) evaluated at the current state and actuator conditions. It is intended to be implemented per-airframe (see obm_cyclone for an example).

Parameters
[out]fu_matPre-allocated array (size ANDI_NUM_ACT * ANDI_OUTPUTS) receiving the flattened control-effectiveness matrix. Convention: element for output i and actuator j should be written to fu_mat[i * ANDI_NUM_ACT + j].
[in]ratesCurrent angular rates (typically p, q, r) used by the model (rad/s).
[in]vel_bodyBody-frame linear velocity vector (u, v, w) (m/s).
[in]actuator_stateCurrent actuator commands/deflections array (length ANDI_NUM_ACT). Units and normalization depend on the airframe and actuator type (e.g. radians, throttle fraction).
Note
Implementations are airframe-specific and must account for the particular actuator layout and aerodynamic/motor characteristics of the platform.
See also
obm_cyclone.c

Definition at line 319 of file obm_cyclone.c.

References actuator_state, ANDI_NUM_ACT, ce_mat_tmp, cyclone_f_stb_u(), CeMatrix::data, CycloneCoefficients::data, foo, obm_coefficients, FloatVect3::x, FloatVect3::y, and FloatVect3::z.

Referenced by stabilization_andi_enter(), stabilization_andi_init(), and stabilization_andi_run().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ evaluate_obm_f_stb_x()

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.

Computes nu_obm = F_x * x_dot, the portion of the open-body-model outputs that depends on the current state rates/accelerations (i.e. the state-dependent term). This is the term that captures how changes in state drive the modeled outputs independent of actuator inputs.

Note
This contribution is often neglected for INDI, but can be included for ANDI.
Parameters
[out]nu_obmPre-allocated output vector of length ANDI_OUTPUTS receiving the computed F_x * x_dot values.
[in]ratesCurrent angular rates (p, q, r) used by the model (rad/s).
[in]vel_bodyBody-frame velocity vector (u, v, w) (m/s).
[in]ang_accelBody angular accelerations (p_dot, q_dot, r_dot) (rad/s^2).
[in]accel_bodyBody-frame linear accelerations (ax, ay, az) (m/s^2).
[in]actuator_stateCurrent actuator commands/deflections array (length ANDI_NUM_ACT). Some terms of F_x may be actuator-state dependent (e.g. rotor wake effects).
Note
The function computes only the state-dependent part of the model. The full modeled output is typically nu_obm + F_u * delta_u (where F_u is provided by evaluate_obm_f_stb_u). Implementations must be provided per airframe.
See also
obm_cyclone.c

Definition at line 345 of file obm_cyclone.c.

References actuator_state, cyclone_f_stb_x(), CycloneCoefficients::data, foo, nu_obm, obm_coefficients, FloatRates::p, FloatRates::q, FloatRates::r, FloatVect3::x, FloatVect3::y, and FloatVect3::z.

Referenced by stabilization_andi_run().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ evaluate_obm_forces()

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.

Computes the full set of forces modeled by the on board model for the given airframe as a function of the state and input.

This function is used for complementary filtering in ANDI.

Parameters
[in]ratesCurrent angular rates (p, q, r) used by the model (rad/s).
[in]vel_bodyBody-frame linear velocity vector (u, v, w) (m/s).
[in]actuator_stateCurrent actuator commands/deflections array (length ANDI_NUM_ACT). Units and normalization depend on the airframe and actuator type (e.g. radians, throttle fraction).
Returns
Computed force vector produced by the actuators as per the OBM.
Note
Implementation is airframe-specific.
See also
obm_cyclone.c

Definition at line 273 of file obm_cyclone.c.

References actuator_state, cyclone_obm_forces(), CycloneCoefficients::data, foo, obm_coefficients, FloatVect3::x, FloatVect3::y, and FloatVect3::z.

Referenced by stabilization_andi_run().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ evaluate_obm_moments()

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.

Computes the full set of moments modeled by the on board model for the given airframe as a function of the state and input.

This function is used for complementary filtering in ANDI.

Parameters
[in]ratesCurrent angular rates (p, q, r) used by the model (rad/s).
[in]vel_bodyBody-frame linear velocity vector (u, v, w) (m/s).
[in]actuator_stateCurrent actuator commands/deflections array (length ANDI_NUM_ACT). Units and normalization depend on the airframe and actuator type (e.g. radians, throttle fraction).
Returns
Computed moment vector produced by the actuators as per the OBM.
Note
Implementation is airframe-specific.
See also
obm_cyclone.c

Definition at line 294 of file obm_cyclone.c.

References actuator_state, cyclone_obm_moments(), CycloneCoefficients::data, foo, moments, obm_coefficients, FloatVect3::x, FloatVect3::y, and FloatVect3::z.

Referenced by stabilization_andi_run().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ evaluate_obm_thrust_z()

float evaluate_obm_thrust_z ( const float  actuator_state[ANDI_NUM_ACT])

Compute total thrust produced by the current actuator state.

Returns the aggregate thrust generated by the set of actuators described by actuator_state. This value is typically used by the stabilization/obm code when converting actuator commands to net force for direct thrust control.

Note
This function does not intend to accurately compute the thrust force; it only returns an approximation of the total specific thrust in the body z-direction. The intended use is as feedback for direct throttle control in ANDI stabilization.
Parameters
[in]actuator_stateCurrent actuator commands/deflections array (length ANDI_NUM_ACT). Units and normalization depend on the airframe (e.g. rotor collective, throttle fraction).
Returns
Total specific thrust produced by the actuators (SI units, m/s^2). If the airframe model uses a normalized thrust unit, document that convention in the airframe implementation.
Note
Implementation is airframe-specific.
See also
obm_cyclone.c

Definition at line 375 of file obm_cyclone.c.

References actuator_state, and obm_coefficients.

Referenced by stabilization_andi_enter(), and stabilization_andi_run().

+ Here is the caller graph for this function:

◆ stabilization_andi_enter()

void stabilization_andi_enter ( void  )

Initializes the ANDI stabilization controller state upon entering stabilization mode.

This function resets all relevant state variables, filters, and actuator states to match the current measurements when entering the ANDI stabilization mode. It ensures that the controller starts from a consistent state when entering stabilization.

NOTE: This function currently assumes that the actuator feedback message is being received. FIXME: Transient free initialization for the cascaded complementary filters is not implemented.

Definition at line 1094 of file stabilization_andi.c.

References LinState::acc, actuator_obm_delay, actuator_obm_zohlpf, ACTUATOR_PREF, actuator_state, actuators_t4_obs, ANDI_NUM_ACT, ANDI_OUTPUTS, angular_rates_obm, AttQuat::att, AttStateQuat::att, AttQuat::att_2d, AttStateQuat::att_2d, AttQuat::att_3d, AttQuat::att_d, AttStateQuat::att_d, attitude_accel_cf, attitude_rates_cf, attitude_ref, attitude_state_cf, ce_mat, evaluate_obm_f_stb_u(), evaluate_obm_thrust_z(), fetch_actuators_t4(), float_quat_vmult(), float_vect_zero(), linear_accel_cf, linear_state_cf, linear_vel_cf, linear_velocity_obm, nu_obm, FloatRates::p, FloatRates::q, FloatRates::r, rates_prev, reset_butterworth_2_complementary_vect3(), reset_first_order_complementary_rates(), reset_first_order_complementary_vect3(), reset_first_order_zoh_low_pass_array(), reset_transport_delay_array(), stateGetBodyRates_f(), stateGetNedToBodyQuat_f(), stateGetSpeedNed_f(), ThrustRef::thrust, ThrustRef::thrust_d, thrust_ref, thrust_state, u_cmd, LinState::vel, FloatVect3::x, FloatVect3::y, and FloatVect3::z.

+ Here is the call graph for this function:

◆ stabilization_andi_init()

void stabilization_andi_init ( void  )

Definition at line 976 of file stabilization_andi.c.

References ABI_BROADCAST, LinState::acc, ACTUATOR_DELAY, actuator_obm_delay, actuator_obm_zohlpf, ACTUATOR_PREF, actuator_state, actuators_t4_in_callback(), actuators_t4_in_event, andi_k_att_ec, andi_k_att_rm, andi_k_rate_ec, andi_k_rate_rm, andi_k_thrust_ec, andi_k_thrust_rm, ANDI_NUM_ACT, andi_p_att_ec, andi_p_att_rm, andi_p_rate_ec, andi_p_rate_rm, andi_p_thrust_ec, andi_p_thrust_rm, angular_rates_obm, AttQuat::att, AttStateQuat::att, AttQuat::att_2d, AttStateQuat::att_2d, AttQuat::att_3d, AttQuat::att_d, AttStateQuat::att_d, attitude_accel_cf, attitude_bounds, attitude_rates_cf, attitude_ref, attitude_state_cf, ce_mat, compute_error_gains_order_2_vect_3(), compute_error_gains_order_3_vect_3(), compute_reference_gains_order_2_vect_3(), compute_reference_gains_order_3_vect_3(), DefaultPeriodic, du_cmd, evaluate_obm_f_stb_u(), float_quat_identity(), float_vect_zero(), foo, init_butterworth_2_complementary_vect3(), init_first_order_complementary_vect3(), init_first_order_zoh_low_pass_array(), init_transport_delay_array(), linear_accel_cf, linear_state_cf, linear_vel_cf, linear_velocity_obm, nu_ec, nu_obj, nu_obm, FloatRates::p, FloatRates::q, FloatRates::r, rates_prev, register_periodic_telemetry(), send_eff_mat_stabilization_andi(), send_stab_attitude_stabilization_andi(), send_wls_u_stabilization_andi(), send_wls_v_stabilization_andi(), ThrustRef::thrust, thrust_bounds_max, thrust_bounds_min, ThrustRef::thrust_d, THRUST_MIN, thrust_ref, thrust_state, u_cmd, LinState::vel, FloatVect3::x, FloatVect3::y, and FloatVect3::z.

+ Here is the call graph for this function:

◆ stabilization_andi_run()

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.

This function implements the core logic of the ANDI stabilization controller. The following steps are performed each time the function is called:

  1. Fetch measurements:
  • Linear state (velocity and acceleration)
  • Attitude state (quaternion, angular rates, angular accelerations)
  • Actuator states (from T4 feedback and/or on-board model estimates)
  1. Filtering:
  • Apply cascaded complementary filtering to obtain an undelayed estimates of attitude and linear states. (used for state dependent model contribution (and scheduling))
  • Apply low-pass filtering to obtain synchronized (delayed) estimates of attitude and thrust states. (used for control error computation)
  1. Reference generation:
  • Generate reference models for attitude and thrust using desired setpoints and reference model gains.
  • Apply low-pass filtering to the references to synchronize with measurement lag.
  1. Pseudo-command computation:
  • Compute error controller pseudo command for attitude and thrust reference and feedback using parallel error controller.
  • Compute state dependent on-board model pseudo command contribution based on undelayed state estimates.
  • Combine pseudo commands to form the overall virtual control input vector.
  1. Actuator command allocation:
  • Update the control effectiveness matrix based on the current state.
  • Compute actuator commands using weighted least squares allocation with bounds and scaling.
Parameters
[in]use_rate_controlFlag indicating whether to use rate control mode.
[in]in_flightFlag indicating whether the vehicle is in flight.
[in,out]stab_setpointPointer to the stabilization setpoint structure.
[in,out]thrust_setpointPointer to the thrust setpoint structure.
[out]cmdPointer to the output command array for actuators.
Note
The attitude stabilization mode is ATTITUDE_HEADING_MODE. A heading estimate and setpoint is needed. Consider implementing ATTITUDE_HEADING_RATE_MODE to avoid needing a heading estimate.

FIXME: The function currently recomputes gains at each call. This could be optimized to only recompute when parameters change. FIXME: The choice of actuator feedback source (T4 vs on-board model) should be configurable.

Definition at line 1185 of file stabilization_andi.c.

References LinState::acc, actuator_meas, actuator_obm_delay, actuator_obm_zohlpf, actuator_state, actuators_t4_obs, andi_k_att_ec, andi_k_att_rm, andi_k_rate_ec, andi_k_rate_rm, andi_k_thrust_ec, andi_k_thrust_rm, ANDI_NUM_ACT, ANDI_OUTPUTS, andi_p_att_ec, andi_p_att_rm, andi_p_rate_ec, andi_p_rate_rm, andi_p_thrust_ec, andi_p_thrust_rm, ANDI_RELAX_OBM, angular_rates_obm, AttStateQuat::att, AttStateQuat::att_2d, AttStateQuat::att_d, attitude_accel_cf, attitude_bounds, attitude_des, attitude_rates_cf, attitude_ref, attitude_state_cf, ce_mat, commands, compute_error_gains_order_2_vect_3(), compute_error_gains_order_3_vect_3(), compute_reference_gains_order_2_vect_3(), compute_reference_gains_order_3_vect_3(), compute_wls_lower_bounds(), compute_wls_u_scaler(), compute_wls_upper_bounds(), control_error_attitude(), control_error_rate(), control_error_thrust(), du_cmd, du_max, du_min, evaluate_obm_f_stb_u(), evaluate_obm_f_stb_x(), evaluate_obm_forces(), evaluate_obm_moments(), evaluate_obm_thrust_z(), fetch_actuators_t4(), float_quat_vmult(), float_rates_vect3_integrate_fi(), float_vect3_integrate_fi(), float_vect_zero(), foo, generate_reference_attitude(), generate_reference_rate(), generate_reference_thrust(), get_butterworth_2_complementary_vect3(), get_first_order_complementary_rates(), get_first_order_complementary_vect3(), get_first_order_zoh_low_pass_array(), get_transport_delay_array(), linear_accel_cf, linear_state_cf, linear_vel_cf, linear_velocity_obm, MAX_PPRZ, nu_ec, nu_obj, nu_obm, FloatRates::p, FloatRates::q, FloatRates::r, rates_des, rates_prev, SCHEDULE_EFF, stab_sp_to_quat_f(), stab_sp_to_rates_f(), stateGetAccelBody_f(), stateGetBodyRates_f(), stateGetNedToBodyQuat_f(), stateGetSpeedNed_f(), th_sp_to_thrust_f(), THRUST_AXIS_Z, thrust_bounds_max, thrust_bounds_min, thrust_des, thrust_ref, thrust_state, WLS_t::u, u_cmd, WLS_t::u_max, WLS_t::u_min, WLS_t::u_pref, update_butterworth_2_complementary_vect3(), update_first_order_complementary_rates(), update_first_order_complementary_vect3(), update_first_order_zoh_low_pass_array(), update_transport_delay_array(), USE_STATE_DYNAMICS, WLS_t::v, LinState::vel, wls_alloc(), wls_stab_p, WLS_WU, WLS_WV, WLS_t::Wu, and WLS_t::Wv.

+ Here is the call graph for this function:

Variable Documentation

◆ andi_p_att_ec

struct PolesOrder3Vect3 andi_p_att_ec
extern

Definition at line 286 of file stabilization_andi.c.

Referenced by stabilization_andi_init(), and stabilization_andi_run().

◆ andi_p_att_rm

struct PolesOrder3Vect3 andi_p_att_rm
extern

Definition at line 303 of file stabilization_andi.c.

Referenced by stabilization_andi_init(), and stabilization_andi_run().

◆ andi_p_rate_ec

struct PolesOrder2Vect3 andi_p_rate_ec
extern

Definition at line 262 of file stabilization_andi.c.

Referenced by stabilization_andi_init(), and stabilization_andi_run().

◆ andi_p_rate_rm

struct PolesOrder2Vect3 andi_p_rate_rm
extern

Definition at line 274 of file stabilization_andi.c.

Referenced by stabilization_andi_init(), and stabilization_andi_run().

◆ andi_p_thrust_ec

float andi_p_thrust_ec
extern

Definition at line 320 of file stabilization_andi.c.

Referenced by stabilization_andi_init(), and stabilization_andi_run().

◆ andi_p_thrust_rm

float andi_p_thrust_rm
extern

Definition at line 321 of file stabilization_andi.c.

Referenced by stabilization_andi_init(), and stabilization_andi_run().